diff --git a/controller_interface/include/controller_interface/controller_interface_base.hpp b/controller_interface/include/controller_interface/controller_interface_base.hpp index bbc45c85837..9d780d2b35d 100644 --- a/controller_interface/include/controller_interface/controller_interface_base.hpp +++ b/controller_interface/include/controller_interface/controller_interface_base.hpp @@ -115,8 +115,7 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy CONTROLLER_INTERFACE_PUBLIC virtual return_type init( const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate, - const std::string & namespace_ = "", - const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions().enable_logger_service(true)); + const std::string & namespace_ = ""); /// Custom configure method to read additional parameters for controller-nodes /* @@ -159,6 +158,12 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy CONTROLLER_INTERFACE_PUBLIC const std::string & get_robot_description() const; + CONTROLLER_INTERFACE_PUBLIC + virtual rclcpp::NodeOptions get_node_options() const + { + return rclcpp::NodeOptions().enable_logger_service(true); + } + /// Declare and initialize a parameter with a type. /** * diff --git a/controller_interface/src/controller_interface_base.cpp b/controller_interface/src/controller_interface_base.cpp index 4594e7ac071..1a7ccd8e01e 100644 --- a/controller_interface/src/controller_interface_base.cpp +++ b/controller_interface/src/controller_interface_base.cpp @@ -26,10 +26,11 @@ namespace controller_interface { return_type ControllerInterfaceBase::init( const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate, - const std::string & namespace_, const rclcpp::NodeOptions & node_options) + const std::string & namespace_) { node_ = std::make_shared( - controller_name, namespace_, node_options, false); // disable LifecycleNode service interfaces + controller_name, namespace_, get_node_options(), + false); // disable LifecycleNode service interfaces urdf_ = urdf; try