From 0f9c7a93b1bf06a20d576de99fd7a7bed19422eb Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Mon, 31 Mar 2025 15:09:50 +0200 Subject: [PATCH] Set `use_sim_time` through CM NodeOptions (#533) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Christoph Fröhlich (cherry picked from commit 0e38d9558324bf1fb85ab8c6576ac6c391202cc5) --- gz_ros2_control/src/gz_ros2_control_plugin.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/gz_ros2_control/src/gz_ros2_control_plugin.cpp b/gz_ros2_control/src/gz_ros2_control_plugin.cpp index d38ce556..49288d9a 100644 --- a/gz_ros2_control/src/gz_ros2_control_plugin.cpp +++ b/gz_ros2_control/src/gz_ros2_control_plugin.cpp @@ -441,6 +441,9 @@ void GazeboSimROS2ControlPlugin::Configure( arguments.push_back("__node:=" + controllerManagerNodeName); arguments.push_back("-r"); arguments.push_back("__ns:=" + ns); + // Force setting of use_sim_time parameter + arguments.push_back("-p"); + arguments.push_back("use_sim_time:=true"); options.arguments(arguments); this->dataPtr->controller_manager_.reset( new controller_manager::ControllerManager( @@ -455,10 +458,6 @@ void GazeboSimROS2ControlPlugin::Configure( std::chrono::duration_cast( std::chrono::duration(1.0 / static_cast(this->dataPtr->update_rate)))); - // Force setting of use_sim_time parameter - this->dataPtr->controller_manager_->set_parameter( - rclcpp::Parameter("use_sim_time", rclcpp::ParameterValue(true))); - // Wait for CM to receive robot description from the topic and then initialize Resource Manager while (!this->dataPtr->controller_manager_->is_resource_manager_initialized()) { RCLCPP_WARN(