@@ -57,6 +57,8 @@ class SimpleActionServer
57
57
* @param server_timeout Timeout to to react to stop or preemption requests
58
58
* @param spin_thread Whether to spin with a dedicated thread internally
59
59
* @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)
60
62
*/
61
63
template <typename NodeT>
62
64
explicit SimpleActionServer (
@@ -66,13 +68,15 @@ class SimpleActionServer
66
68
CompletionCallback completion_callback = nullptr ,
67
69
std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500 ),
68
70
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)
70
73
: SimpleActionServer(
71
74
node->get_node_base_interface (),
72
75
node->get_node_clock_interface(),
73
76
node->get_node_logging_interface(),
74
77
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)
76
80
{}
77
81
78
82
/* *
@@ -83,6 +87,8 @@ class SimpleActionServer
83
87
* @param server_timeout Timeout to to react to stop or preemption requests
84
88
* @param spin_thread Whether to spin with a dedicated thread internally
85
89
* @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)
86
92
*/
87
93
explicit SimpleActionServer (
88
94
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
@@ -94,7 +100,8 @@ class SimpleActionServer
94
100
CompletionCallback completion_callback = nullptr ,
95
101
std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500 ),
96
102
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)
98
105
: node_base_interface_(node_base_interface),
99
106
node_clock_interface_(node_clock_interface),
100
107
node_logging_interface_(node_logging_interface),
@@ -106,6 +113,7 @@ class SimpleActionServer
106
113
spin_thread_(spin_thread)
107
114
{
108
115
using namespace std ::placeholders; // NOLINT
116
+ use_realtime_prioritization_ = realtime;
109
117
if (spin_thread_) {
110
118
callback_group_ = node_base_interface->create_callback_group (
111
119
rclcpp::CallbackGroupType::MutuallyExclusive, false );
@@ -170,6 +178,26 @@ class SimpleActionServer
170
178
return rclcpp_action::CancelResponse::ACCEPT;
171
179
}
172
180
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
+
173
201
/* *
174
202
* @brief Handles accepted goals and adds to preempted queue to switch to
175
203
* @param Goal A server goal handle to cancel
@@ -202,7 +230,11 @@ class SimpleActionServer
202
230
203
231
// Return quickly to avoid blocking the executor, so spin up a new thread
204
232
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
+ });
206
238
}
207
239
}
208
240
@@ -509,6 +541,7 @@ class SimpleActionServer
509
541
CompletionCallback completion_callback_;
510
542
std::future<void > execution_future_;
511
543
bool stop_execution_{false };
544
+ bool use_realtime_prioritization_{false };
512
545
513
546
mutable std::recursive_mutex update_mutex_;
514
547
bool server_active_{false };
0 commit comments