diff --git a/gz_ros2_control/src/gz_ros2_control_plugin.cpp b/gz_ros2_control/src/gz_ros2_control_plugin.cpp index 7c9cdf57..84d8d369 100644 --- a/gz_ros2_control/src/gz_ros2_control_plugin.cpp +++ b/gz_ros2_control/src/gz_ros2_control_plugin.cpp @@ -476,7 +476,7 @@ void GazeboSimROS2ControlPlugin::Configure( std::chrono::duration_cast( std::chrono::duration(1.0 / static_cast(this->dataPtr->update_rate)))); - // Force setting of use_sime_time parameter + // Force setting of use_sim_time parameter this->dataPtr->controller_manager_->set_parameter( rclcpp::Parameter("use_sim_time", rclcpp::ParameterValue(true)));