Skip to content

Commit

Permalink
fixed lambda capture for rt prio
Browse files Browse the repository at this point in the history
  • Loading branch information
mhubii committed Oct 19, 2024
1 parent f76be58 commit b33aec2
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 9 deletions.
20 changes: 12 additions & 8 deletions lbr_fri_ros2/src/app.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,15 +88,19 @@ void App::run_async(int rt_prio) {
ColorScheme::WARNING << "App already running" << ColorScheme::ENDC);
return;
}
run_thread_ = std::thread([&]() {
if (realtime_tools::has_realtime_kernel()) {
if (!realtime_tools::configure_sched_fifo(rt_prio)) {
RCLCPP_WARN_STREAM(rclcpp::get_logger(LOGGER_NAME),
ColorScheme::WARNING << "Failed to set FIFO realtime scheduling policy"
<< ColorScheme::ENDC);
}
run_thread_ = std::thread([this, rt_prio]() {
if (!realtime_tools::configure_sched_fifo(rt_prio)) {
RCLCPP_WARN_STREAM(rclcpp::get_logger(LOGGER_NAME),
ColorScheme::WARNING
<< "Failed to set FIFO realtime scheduling policy. Refer to "
"[https://control.ros.org/master/doc/ros2_control/"
"controller_manager/doc/userdoc.html]."
<< ColorScheme::ENDC);
} else {
RCLCPP_INFO(rclcpp::get_logger(LOGGER_NAME), "Realtime kernel recommended but not required");
RCLCPP_INFO_STREAM(rclcpp::get_logger(LOGGER_NAME),
ColorScheme::OKGREEN
<< "Realtime scheduling policy set to FIFO with priority '" << rt_prio
<< "'" << ColorScheme::ENDC);
}

RCLCPP_INFO(rclcpp::get_logger(LOGGER_NAME), "Starting run thread");
Expand Down
2 changes: 1 addition & 1 deletion lbr_ros2_control/config/lbr_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
# managers regardless of their namespace. Usefull in multi-robot setups.
/**/controller_manager:
ros__parameters:
update_rate: 200
update_rate: 100

# ROS 2 control broadcasters
joint_state_broadcaster:
Expand Down

0 comments on commit b33aec2

Please sign in to comment.