File tree Expand file tree Collapse file tree 1 file changed +3
-4
lines changed Expand file tree Collapse file tree 1 file changed +3
-4
lines changed Original file line number Diff line number Diff line change @@ -441,6 +441,9 @@ void GazeboSimROS2ControlPlugin::Configure(
441441 arguments.push_back (" __node:=" + controllerManagerNodeName);
442442 arguments.push_back (" -r" );
443443 arguments.push_back (" __ns:=" + ns);
444+ // Force setting of use_sim_time parameter
445+ arguments.push_back (" -p" );
446+ arguments.push_back (" use_sim_time:=true" );
444447 options.arguments (arguments);
445448 this ->dataPtr ->controller_manager_ .reset (
446449 new controller_manager::ControllerManager (
@@ -455,10 +458,6 @@ void GazeboSimROS2ControlPlugin::Configure(
455458 std::chrono::duration_cast<std::chrono::nanoseconds>(
456459 std::chrono::duration<double >(1.0 / static_cast <double >(this ->dataPtr ->update_rate ))));
457460
458- // Force setting of use_sim_time parameter
459- this ->dataPtr ->controller_manager_ ->set_parameter (
460- rclcpp::Parameter (" use_sim_time" , rclcpp::ParameterValue (true )));
461-
462461 // Wait for CM to receive robot description from the topic and then initialize Resource Manager
463462 while (!this ->dataPtr ->controller_manager_ ->is_resource_manager_initialized ()) {
464463 RCLCPP_WARN (
You can’t perform that action at this time.
0 commit comments