From 2651b993967eab87961d7fec7d0b7ec134b6d658 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Thu, 24 Oct 2024 18:13:02 +0200 Subject: [PATCH 1/2] make ros2_control_node handle simulation environments --- controller_manager/src/ros2_control_node.cpp | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/controller_manager/src/ros2_control_node.cpp b/controller_manager/src/ros2_control_node.cpp index e0094b7e01..953e26e5bb 100644 --- a/controller_manager/src/ros2_control_node.cpp +++ b/controller_manager/src/ros2_control_node.cpp @@ -57,10 +57,12 @@ int main(int argc, char ** argv) auto cm = std::make_shared( executor, manager_node_name, "", cm_node_options); + const bool use_sim_time = cm->get_parameter_or("use_sim_time", false); + rclcpp::Rate rate(cm->get_update_rate(), cm->get_clock()); RCLCPP_INFO(cm->get_logger(), "update rate is %d Hz", cm->get_update_rate()); std::thread cm_thread( - [cm]() + [cm, use_sim_time, &rate]() { if (!realtime_tools::configure_sched_fifo(kSchedPriority)) { @@ -101,7 +103,14 @@ int main(int argc, char ** argv) // wait until we hit the end of the period next_iteration_time += period; - std::this_thread::sleep_until(next_iteration_time); + if (use_sim_time) + { + rate.sleep(); + } + else + { + std::this_thread::sleep_until(next_iteration_time); + } } cm->shutdown_async_controllers_and_components(); From bb5f0f15d80d05395c8aba4918e59a6a617a9c22 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Thu, 24 Oct 2024 18:16:08 +0200 Subject: [PATCH 2/2] add release_notes --- doc/release_notes.rst | 1 + 1 file changed, 1 insertion(+) diff --git a/doc/release_notes.rst b/doc/release_notes.rst index 611e8d8176..a25c743e0b 100644 --- a/doc/release_notes.rst +++ b/doc/release_notes.rst @@ -76,6 +76,7 @@ controller_manager * The ``--controller-type`` or ``-t`` spawner arg is removed. Now the controller type is defined in the controller configuration file with ``type`` field (`#1639 `_). * The ``--namespace`` or ``-n`` spawner arg is deprecated. Now the spawner namespace can be defined using the ROS 2 standard way (`#1640 `_). * Added support for the wildcard entries for the controller configuration files (`#1724 `_). +* ``ros2_control_node`` can now handle the sim time used by different simulators, when ``use_sim_time`` is set to true (`#1810 `_). hardware_interface ******************