Skip to content

Set use_sim_time through CM NodeOptions #533

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 3 commits into from
Mar 31, 2025
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 3 additions & 4 deletions gz_ros2_control/src/gz_ros2_control_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand All @@ -455,10 +458,6 @@ void GazeboSimROS2ControlPlugin::Configure(
std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::duration<double>(1.0 / static_cast<double>(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(
Expand Down