Skip to content

Commit

Permalink
add thread_priority option to the ros2_control_node (#1820)
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Oct 31, 2024
1 parent 7ca9d7f commit 9a4ee8d
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 2 deletions.
8 changes: 6 additions & 2 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,13 +45,17 @@ int main(int argc, char ** argv)
auto cm = std::make_shared<controller_manager::ControllerManager>(executor, manager_node_name);

RCLCPP_INFO(cm->get_logger(), "update rate is %d Hz", cm->get_update_rate());
const int thread_priority = cm->get_parameter_or<int>("thread_priority", kSchedPriority);
RCLCPP_INFO(
cm->get_logger(), "Spawning %s RT thread with scheduler priority: %d", cm->get_name(),
thread_priority);

std::thread cm_thread(
[cm]()
[cm, thread_priority]()
{
if (realtime_tools::has_realtime_kernel())
{
if (!realtime_tools::configure_sched_fifo(kSchedPriority))
if (!realtime_tools::configure_sched_fifo(thread_priority))
{
RCLCPP_WARN(
cm->get_logger(),
Expand Down
5 changes: 5 additions & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -13,3 +13,8 @@ controller_interface
For details see the controller_manager section.

* The new ``PoseSensor`` semantic component provides a standard interface for hardware providing cartesian poses (`#1775 <https://github.com/ros-controls/ros2_control/pull/1775>`_)

controller_manager
******************

* 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>`_).

0 comments on commit 9a4ee8d

Please sign in to comment.