Skip to content
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

[ros2_control_node] Handle simulation environment clocks #1810

Merged
Show file tree
Hide file tree
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
14 changes: 12 additions & 2 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,9 @@ int main(int argc, char ** argv)
auto cm = std::make_shared<controller_manager::ControllerManager>(
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());

const bool lock_memory = cm->get_parameter_or<bool>("lock_memory", true);
std::string message;
if (lock_memory && !realtime_tools::lock_memory(message))
Expand All @@ -82,7 +85,7 @@ int main(int argc, char ** argv)
thread_priority);

std::thread cm_thread(
[cm, thread_priority]()
[cm, thread_priority, use_sim_time, &rate]()
{
if (!realtime_tools::configure_sched_fifo(thread_priority))
{
Expand Down Expand Up @@ -123,7 +126,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();
Expand Down
1 change: 1 addition & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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 <https://github.com/ros-controls/ros2_control/pull/1639>`_).
* The ``--namespace`` or ``-n`` spawner arg is deprecated. Now the spawner namespace can be defined using the ROS 2 standard way (`#1640 <https://github.com/ros-controls/ros2_control/pull/1640>`_).
* Added support for the wildcard entries for the controller configuration files (`#1724 <https://github.com/ros-controls/ros2_control/pull/1724>`_).
* ``ros2_control_node`` can now handle the sim time used by different simulators, when ``use_sim_time`` is set to true (`#1810 <https://github.com/ros-controls/ros2_control/pull/1810>`_).
* The ``ros2_control_node`` node now accepts the ``thread_priority`` parameter to set the scheduler priority of the controller_manager's RT thread (`#1820 <https://github.com/ros-controls/ros2_control/pull/1820>`_).
* The ``ros2_control_node`` node has a new ``lock_memory`` parameter to lock memory at startup to physical RAM in order to avoid page faults (`#1822 <https://github.com/ros-controls/ros2_control/pull/1822>`_).
* The ``ros2_control_node`` node has a new ``cpu_affinity`` parameter to bind the process to a specific CPU core. By default, this is not enabled. (`#1852 <https://github.com/ros-controls/ros2_control/pull/1852>`_).
Expand Down
Loading