Skip to content

Commit c213c85

Browse files
Enabling soft realtime prioritization to the Controller Server (#3914) (#3975)
* Enabling soft realtime prioritization to the controller server * abstracting to another function * changing default priorities * linting (cherry picked from commit fbe8f56) Co-authored-by: Steve Macenski <[email protected]>
1 parent b4ea1e0 commit c213c85

File tree

6 files changed

+64
-16
lines changed

6 files changed

+64
-16
lines changed

nav2_bringup/params/nav2_params.yaml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -121,6 +121,7 @@ controller_server:
121121
progress_checker_plugins: ["progress_checker"]
122122
goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
123123
controller_plugins: ["FollowPath"]
124+
use_realtime_priority: false
124125

125126
# Progress checker parameters
126127
progress_checker:

nav2_controller/include/nav2_controller/controller_server.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -265,6 +265,7 @@ class ControllerServer : public nav2_util::LifecycleNode
265265
double min_theta_velocity_threshold_;
266266

267267
double failure_tolerance_;
268+
bool use_realtime_priority_;
268269

269270
// Whether we've published the single controller warning yet
270271
geometry_msgs::msg::PoseStamped end_pose_;

nav2_controller/src/controller_server.cpp

Lines changed: 15 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,7 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
6262
declare_parameter("speed_limit_topic", rclcpp::ParameterValue("speed_limit"));
6363

6464
declare_parameter("failure_tolerance", rclcpp::ParameterValue(0.0));
65+
declare_parameter("use_realtime_priority", rclcpp::ParameterValue(false));
6566

6667
// The costmap node is used in the implementation of the controller
6768
costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
@@ -140,6 +141,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
140141
std::string speed_limit_topic;
141142
get_parameter("speed_limit_topic", speed_limit_topic);
142143
get_parameter("failure_tolerance", failure_tolerance_);
144+
get_parameter("use_realtime_priority", use_realtime_priority_);
143145

144146
costmap_ros_->configure();
145147
// Launch a thread to run the costmap node
@@ -235,13 +237,19 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
235237
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
236238

237239
// Create the action server that we implement with our followPath method
238-
action_server_ = std::make_unique<ActionServer>(
239-
shared_from_this(),
240-
"follow_path",
241-
std::bind(&ControllerServer::computeControl, this),
242-
nullptr,
243-
std::chrono::milliseconds(500),
244-
true, server_options);
240+
// This may throw due to real-time prioritzation if user doesn't have real-time permissions
241+
try {
242+
action_server_ = std::make_unique<ActionServer>(
243+
shared_from_this(),
244+
"follow_path",
245+
std::bind(&ControllerServer::computeControl, this),
246+
nullptr,
247+
std::chrono::milliseconds(500),
248+
true /*spin thread*/, server_options, use_realtime_priority_ /*soft realtime*/);
249+
} catch (const std::runtime_error & e) {
250+
RCLCPP_ERROR(get_logger(), "Error creating action server! %s", e.what());
251+
return nav2_util::CallbackReturn::FAILURE;
252+
}
245253

246254
// Set subscribtion to the speed limiting topic
247255
speed_limit_sub_ = create_subscription<nav2_msgs::msg::SpeedLimit>(

nav2_util/include/nav2_util/node_thread.hpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,13 +32,15 @@ class NodeThread
3232
* @brief A background thread to process node callbacks constructor
3333
* @param node_base Interface to Node to spin in thread
3434
*/
35-
explicit NodeThread(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base);
35+
explicit NodeThread(
36+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base);
3637

3738
/**
3839
* @brief A background thread to process executor's callbacks constructor
3940
* @param executor Interface to executor to spin in thread
4041
*/
41-
explicit NodeThread(rclcpp::executors::SingleThreadedExecutor::SharedPtr executor);
42+
explicit NodeThread(
43+
rclcpp::executors::SingleThreadedExecutor::SharedPtr executor);
4244

4345
/**
4446
* @brief A background thread to process node callbacks constructor

nav2_util/include/nav2_util/simple_action_server.hpp

Lines changed: 37 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,8 @@ class SimpleActionServer
5757
* @param server_timeout Timeout to to react to stop or preemption requests
5858
* @param spin_thread Whether to spin with a dedicated thread internally
5959
* @param options Options to pass to the underlying rcl_action_server_t
60+
* @param realtime Whether the action server's worker thread should have elevated
61+
* prioritization (soft realtime)
6062
*/
6163
template<typename NodeT>
6264
explicit SimpleActionServer(
@@ -66,13 +68,15 @@ class SimpleActionServer
6668
CompletionCallback completion_callback = nullptr,
6769
std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500),
6870
bool spin_thread = false,
69-
const rcl_action_server_options_t & options = rcl_action_server_get_default_options())
71+
const rcl_action_server_options_t & options = rcl_action_server_get_default_options(),
72+
const bool realtime = false)
7073
: SimpleActionServer(
7174
node->get_node_base_interface(),
7275
node->get_node_clock_interface(),
7376
node->get_node_logging_interface(),
7477
node->get_node_waitables_interface(),
75-
action_name, execute_callback, completion_callback, server_timeout, spin_thread, options)
78+
action_name, execute_callback, completion_callback,
79+
server_timeout, spin_thread, options, realtime)
7680
{}
7781

7882
/**
@@ -83,6 +87,8 @@ class SimpleActionServer
8387
* @param server_timeout Timeout to to react to stop or preemption requests
8488
* @param spin_thread Whether to spin with a dedicated thread internally
8589
* @param options Options to pass to the underlying rcl_action_server_t
90+
* @param realtime Whether the action server's worker thread should have elevated
91+
* prioritization (soft realtime)
8692
*/
8793
explicit SimpleActionServer(
8894
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
@@ -94,7 +100,8 @@ class SimpleActionServer
94100
CompletionCallback completion_callback = nullptr,
95101
std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500),
96102
bool spin_thread = false,
97-
const rcl_action_server_options_t & options = rcl_action_server_get_default_options())
103+
const rcl_action_server_options_t & options = rcl_action_server_get_default_options(),
104+
const bool realtime = false)
98105
: node_base_interface_(node_base_interface),
99106
node_clock_interface_(node_clock_interface),
100107
node_logging_interface_(node_logging_interface),
@@ -106,6 +113,7 @@ class SimpleActionServer
106113
spin_thread_(spin_thread)
107114
{
108115
using namespace std::placeholders; // NOLINT
116+
use_realtime_prioritization_ = realtime;
109117
if (spin_thread_) {
110118
callback_group_ = node_base_interface->create_callback_group(
111119
rclcpp::CallbackGroupType::MutuallyExclusive, false);
@@ -170,6 +178,26 @@ class SimpleActionServer
170178
return rclcpp_action::CancelResponse::ACCEPT;
171179
}
172180

181+
/**
182+
* @brief Sets thread priority level
183+
*/
184+
void setSoftRealTimePriority()
185+
{
186+
if (use_realtime_prioritization_) {
187+
sched_param sch;
188+
sch.sched_priority = 49;
189+
if (sched_setscheduler(0, SCHED_FIFO, &sch) == -1) {
190+
std::string errmsg(
191+
"Cannot set as real-time thread. Users must set: <username> hard rtprio 99 and "
192+
"<username> soft rtprio 99 in /etc/security/limits.conf to enable "
193+
"realtime prioritization! Error: ");
194+
throw std::runtime_error(errmsg + std::strerror(errno));
195+
} else {
196+
debug_msg("Soft realtime prioritization successfully set!");
197+
}
198+
}
199+
}
200+
173201
/**
174202
* @brief Handles accepted goals and adds to preempted queue to switch to
175203
* @param Goal A server goal handle to cancel
@@ -202,7 +230,11 @@ class SimpleActionServer
202230

203231
// Return quickly to avoid blocking the executor, so spin up a new thread
204232
debug_msg("Executing goal asynchronously.");
205-
execution_future_ = std::async(std::launch::async, [this]() {work();});
233+
execution_future_ = std::async(
234+
std::launch::async, [this]() {
235+
setSoftRealTimePriority();
236+
work();
237+
});
206238
}
207239
}
208240

@@ -509,6 +541,7 @@ class SimpleActionServer
509541
CompletionCallback completion_callback_;
510542
std::future<void> execution_future_;
511543
bool stop_execution_{false};
544+
bool use_realtime_prioritization_{false};
512545

513546
mutable std::recursive_mutex update_mutex_;
514547
bool server_active_{false};

nav2_util/src/node_thread.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -13,13 +13,13 @@
1313
// limitations under the License.
1414

1515
#include <memory>
16-
1716
#include "nav2_util/node_thread.hpp"
1817

1918
namespace nav2_util
2019
{
2120

22-
NodeThread::NodeThread(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base)
21+
NodeThread::NodeThread(
22+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base)
2323
: node_(node_base)
2424
{
2525
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
@@ -35,7 +35,10 @@ NodeThread::NodeThread(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr nod
3535
NodeThread::NodeThread(rclcpp::executors::SingleThreadedExecutor::SharedPtr executor)
3636
: executor_(executor)
3737
{
38-
thread_ = std::make_unique<std::thread>([&]() {executor_->spin();});
38+
thread_ = std::make_unique<std::thread>(
39+
[&]() {
40+
executor_->spin();
41+
});
3942
}
4043

4144
NodeThread::~NodeThread()

0 commit comments

Comments
 (0)