From 5cb5efa1c1ac020b8a3898c9c41c4bc130d1f857 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 23 Aug 2024 15:34:54 +0200 Subject: [PATCH] propagate gazebo remapping and other arguments to the controller node (#396) (cherry picked from commit cbdd3a3fc6dcb49072b501984c3294a20872dcd8) --- gz_ros2_control/src/gz_ros2_control_plugin.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/gz_ros2_control/src/gz_ros2_control_plugin.cpp b/gz_ros2_control/src/gz_ros2_control_plugin.cpp index b476fb50..ff26e583 100644 --- a/gz_ros2_control/src/gz_ros2_control_plugin.cpp +++ b/gz_ros2_control/src/gz_ros2_control_plugin.cpp @@ -405,12 +405,14 @@ void GazeboSimROS2ControlPlugin::Configure( // Create the controller manager RCLCPP_INFO(this->dataPtr->node_->get_logger(), "Loading controller_manager"); + rclcpp::NodeOptions options = controller_manager::get_cm_node_options(); + options.arguments(arguments); this->dataPtr->controller_manager_.reset( new controller_manager::ControllerManager( std::move(resource_manager_), this->dataPtr->executor_, controllerManagerNodeName, - this->dataPtr->node_->get_namespace())); + this->dataPtr->node_->get_namespace(), options)); this->dataPtr->executor_->add_node(this->dataPtr->controller_manager_); this->dataPtr->update_rate = this->dataPtr->controller_manager_->get_update_rate();