Skip to content
This repository was archived by the owner on Mar 28, 2025. It is now read-only.

Commit 530161a

Browse files
Set use_sim_time parameter prior to node creation
1 parent 1e14357 commit 530161a

File tree

1 file changed

+3
-3
lines changed

1 file changed

+3
-3
lines changed

gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -346,6 +346,9 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element
346346
// Create the controller manager
347347
RCLCPP_INFO(impl_->model_nh_->get_logger(), "Loading controller_manager");
348348
rclcpp::NodeOptions options = controller_manager::get_cm_node_options();
349+
// Force setting of use_sime_time parameter
350+
arguments.push_back("--param");
351+
arguments.push_back("use_sim_time:=True");
349352
options.arguments(arguments);
350353
impl_->controller_manager_.reset(
351354
new controller_manager::ControllerManager(
@@ -373,9 +376,6 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element
373376
" s) is slower than the gazebo simulation period (" <<
374377
gazebo_period.seconds() << " s).");
375378
}
376-
// Force setting of use_sime_time parameter
377-
impl_->controller_manager_->set_parameter(
378-
rclcpp::Parameter("use_sim_time", rclcpp::ParameterValue(true)));
379379

380380
impl_->stop_ = false;
381381
auto spin = [this]()

0 commit comments

Comments
 (0)