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] add thread_priority option to the ros2_control_node (backport #1820) #1824

Merged
merged 1 commit into from
Oct 31, 2024
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
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 @@ -12,3 +12,8 @@ controller_interface
********************

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