Skip to content

Commit 8611bbf

Browse files
Janosch MachowinskiJanosch Machowinski
authored andcommitted
feat(MultiThreadedExecutor): Added ability to handle exceptions from threads
This commit adds external exception handling for the worker threads, allowing application code to implement custom exception handling. feat(Executor): Added spin API with exception handler. Signed-off-by: Janosch Machowinski <[email protected]>
1 parent dec22a2 commit 8611bbf

File tree

16 files changed

+343
-16
lines changed

16 files changed

+343
-16
lines changed

rclcpp/include/rclcpp/executor.hpp

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -82,6 +82,18 @@ class Executor
8282
virtual void
8383
spin() = 0;
8484

85+
/**
86+
* \sa rclcpp::Executor:spin() for more details
87+
* \throws std::runtime_error when spin() called while already spinning
88+
* @param exception_handler will be called for every exception in the processing threads
89+
*
90+
* The exception_handler can be called from multiple threads at the same time.
91+
* The exception_handler shall rethrow the exception it if wants to terminate the program.
92+
*/
93+
RCLCPP_PUBLIC
94+
virtual void
95+
spin(const std::function<void(const std::exception & e)> & exception_handler) = 0;
96+
8597
/// Add a callback group to an executor.
8698
/**
8799
* An executor can have zero or more callback groups which provide work during `spin` functions.
@@ -470,6 +482,18 @@ class Executor
470482
void
471483
execute_any_executable(AnyExecutable & any_exec);
472484

485+
/// Find the next available executable and do the work associated with it.
486+
/**
487+
* \param[in] any_exec Union structure that can hold any executable type (timer, subscription,
488+
* service, client).
489+
* \throws std::runtime_error if there is an issue triggering the guard condition
490+
*/
491+
RCLCPP_PUBLIC
492+
void
493+
execute_any_executable(
494+
AnyExecutable & any_exec,
495+
const std::function<void(const std::exception & e)> & exception_handler);
496+
473497
/// Run subscription executable.
474498
/**
475499
* Do necessary setup and tear-down as well as executing the subscription.

rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -69,14 +69,28 @@ class MultiThreadedExecutor : public rclcpp::Executor
6969
void
7070
spin() override;
7171

72+
/**
73+
* \sa rclcpp::Executor:spin() for more details
74+
* \throws std::runtime_error when spin() called while already spinning
75+
* @param exception_handler will be called for every exception in the processing threads
76+
*
77+
* The exception_handler can be called from multiple threads at the same time.
78+
* The exception_handler shall rethrow the exception it if wants to terminate the program.
79+
*/
80+
RCLCPP_PUBLIC
81+
void
82+
spin(const std::function<void(const std::exception & e)> & exception_handler) override;
83+
7284
RCLCPP_PUBLIC
7385
size_t
7486
get_number_of_threads();
7587

7688
protected:
7789
RCLCPP_PUBLIC
7890
void
79-
run(size_t this_thread_number);
91+
run(
92+
size_t this_thread_number,
93+
const std::function<void(const std::exception & e)> & exception_handler);
8094

8195
private:
8296
RCLCPP_DISABLE_COPY(MultiThreadedExecutor)

rclcpp/include/rclcpp/executors/single_threaded_executor.hpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,18 @@ class SingleThreadedExecutor : public rclcpp::Executor
6565
void
6666
spin() override;
6767

68+
/// Single-threaded implementation of spin.
69+
/**
70+
* \sa rclcpp::SingleThreadedExecutor:spin() for more details
71+
* \throws std::runtime_error when spin() called while already spinning
72+
* @param exception_handler will be called for every exception in the processing threads
73+
*
74+
* The exception_handler shall rethrow the exception it if wants to terminate the program.
75+
*/
76+
RCLCPP_PUBLIC
77+
void
78+
spin(const std::function<void(const std::exception & e)> & exception_handler) override;
79+
6880
private:
6981
RCLCPP_DISABLE_COPY(SingleThreadedExecutor)
7082
};

rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,16 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor
6868
void
6969
spin() override;
7070

71+
/**
72+
* \sa rclcpp::SingleThreadedExecutor:spin() for more details
73+
* \throws std::runtime_error when spin() called while already spinning
74+
* @param exception_handler will be called for every exception in the processing threads
75+
*
76+
* The exception_handler shall rethrow the exception it if wants to terminate the program.
77+
*/RCLCPP_PUBLIC
78+
virtual void
79+
spin(const std::function<void(const std::exception & e)> & exception_handler) override;
80+
7181
/// Static executor implementation of spin some
7282
/**
7383
* This non-blocking function will execute entities that
@@ -125,6 +135,11 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor
125135
void
126136
spin_once_impl(std::chrono::nanoseconds timeout) override;
127137

138+
void
139+
spin_once_impl(
140+
std::chrono::nanoseconds timeout,
141+
const std::function<void(const std::exception & e)> & exception_handler);
142+
128143
std::optional<rclcpp::WaitResult<rclcpp::WaitSet>>
129144
collect_and_wait(std::chrono::nanoseconds timeout);
130145

rclcpp/include/rclcpp/experimental/executors/events_executor/events_executor.hpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,18 @@ class EventsExecutor : public rclcpp::Executor
9292
void
9393
spin() override;
9494

95+
/**
96+
* \sa rclcpp::Executor:spin() for more details
97+
* \throws std::runtime_error when spin() called while already spinning
98+
* @param exception_handler will be called for every exception in the processing threads
99+
*
100+
* The exception_handler can be called from multiple threads at the same time.
101+
* The exception_handler shall rethrow the exception it if wants to terminate the program.
102+
*/
103+
RCLCPP_PUBLIC
104+
void
105+
spin(const std::function<void(const std::exception & e)> & exception_handler) override;
106+
95107
/// Events executor implementation of spin some
96108
/**
97109
* This non-blocking function will execute the timers and events

rclcpp/include/rclcpp/experimental/timers_manager.hpp

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -125,9 +125,14 @@ class TimersManager
125125
/**
126126
* @brief Starts a thread that takes care of executing the timers stored in this object.
127127
* Function will throw an error if the timers thread was already running.
128+
*
129+
* @param exception_handler if valid, the execution of the timer will be done in a try catch block,
130+
* and any occurring exception will be passed to the given handler
128131
*/
129132
RCLCPP_PUBLIC
130-
void start();
133+
void start(
134+
const std::function<void(const std::exception & e)> & exception_handler = std::function<void(
135+
const std::exception & e)>());
131136

132137
/**
133138
* @brief Stops the timers thread.
@@ -511,6 +516,11 @@ class TimersManager
511516
*/
512517
void run_timers();
513518

519+
/**
520+
* @brief calls run_timers with a try catch block.
521+
*/
522+
void run_timers(const std::function<void(const std::exception & e)> & exception_handler);
523+
514524
/**
515525
* @brief Get the amount of time before the next timer triggers.
516526
* This function is not thread safe, acquire a mutex before calling it.
@@ -528,7 +538,7 @@ class TimersManager
528538
* while keeping the heap correctly sorted.
529539
* This function is not thread safe, acquire the timers_mutex_ before calling it.
530540
*/
531-
void execute_ready_timers_unsafe();
541+
void execute_ready_timers_unsafe(std::function<void(const std::exception & e)> exception_handler);
532542

533543
// Callback to be called when timer is ready
534544
std::function<void(const rclcpp::TimerBase *,

rclcpp/src/rclcpp/executor.cpp

Lines changed: 70 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -408,6 +408,76 @@ Executor::execute_any_executable(AnyExecutable & any_exec)
408408
}
409409
}
410410

411+
template<typename Function>
412+
void execute_guarded(
413+
const Function & fun,
414+
const std::function<void(const std::exception & e)> & exception_handler)
415+
{
416+
try {
417+
fun();
418+
} catch (const std::exception & e) {
419+
RCLCPP_ERROR_STREAM(
420+
rclcpp::get_logger("rclcpp"),
421+
"Exception while spinning : " << e.what());
422+
423+
exception_handler(e);
424+
}
425+
}
426+
427+
void
428+
Executor::execute_any_executable(
429+
AnyExecutable & any_exec,
430+
const std::function<void(const std::exception & e)> & exception_handler)
431+
{
432+
if (!spinning.load()) {
433+
return;
434+
}
435+
436+
if (any_exec.timer) {
437+
TRACETOOLS_TRACEPOINT(
438+
rclcpp_executor_execute,
439+
static_cast<const void *>(any_exec.timer->get_timer_handle().get()));
440+
execute_guarded([&any_exec]() {
441+
execute_timer(any_exec.timer, any_exec.data);
442+
}, exception_handler);
443+
}
444+
if (any_exec.subscription) {
445+
TRACETOOLS_TRACEPOINT(
446+
rclcpp_executor_execute,
447+
static_cast<const void *>(any_exec.subscription->get_subscription_handle().get()));
448+
execute_guarded(
449+
[&any_exec]() {
450+
execute_subscription(any_exec.subscription);
451+
}, exception_handler);
452+
}
453+
if (any_exec.service) {
454+
execute_guarded([&any_exec]() {execute_service(any_exec.service);}, exception_handler);
455+
}
456+
if (any_exec.client) {
457+
execute_guarded([&any_exec]() {execute_client(any_exec.client);}, exception_handler);
458+
}
459+
if (any_exec.waitable) {
460+
execute_guarded([&any_exec]() {
461+
const std::shared_ptr<void> & const_data = any_exec.data;
462+
any_exec.waitable->execute(const_data);
463+
}, exception_handler);
464+
}
465+
// Reset the callback_group, regardless of type
466+
if(any_exec.callback_group) {
467+
any_exec.callback_group->can_be_taken_from().store(true);
468+
}
469+
// Wake the wait, because it may need to be recalculated or work that
470+
// was previously blocked is now available.
471+
try {
472+
interrupt_guard_condition_->trigger();
473+
} catch (const rclcpp::exceptions::RCLError & ex) {
474+
throw std::runtime_error(
475+
std::string(
476+
"Failed to trigger guard condition from execute_any_executable: ") + ex.what());
477+
}
478+
}
479+
480+
411481
template<typename Taker, typename Handler>
412482
static
413483
void

rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp

Lines changed: 13 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,13 @@ MultiThreadedExecutor::~MultiThreadedExecutor() {}
5151

5252
void
5353
MultiThreadedExecutor::spin()
54+
{
55+
spin([](const std::exception & e) {throw e;});
56+
}
57+
58+
void
59+
60+
MultiThreadedExecutor::spin(const std::function<void(const std::exception & e)> & exception_handler)
5461
{
5562
if (spinning.exchange(true)) {
5663
throw std::runtime_error("spin() called while already spinning");
@@ -61,12 +68,12 @@ MultiThreadedExecutor::spin()
6168
{
6269
std::lock_guard wait_lock{wait_mutex_};
6370
for (; thread_id < number_of_threads_ - 1; ++thread_id) {
64-
auto func = std::bind(&MultiThreadedExecutor::run, this, thread_id);
71+
auto func = std::bind(&MultiThreadedExecutor::run, this, thread_id, exception_handler);
6572
threads.emplace_back(func);
6673
}
6774
}
6875

69-
run(thread_id);
76+
run(thread_id, exception_handler);
7077
for (auto & thread : threads) {
7178
thread.join();
7279
}
@@ -79,7 +86,9 @@ MultiThreadedExecutor::get_number_of_threads()
7986
}
8087

8188
void
82-
MultiThreadedExecutor::run(size_t this_thread_number)
89+
MultiThreadedExecutor::run(
90+
size_t this_thread_number,
91+
const std::function<void(const std::exception & e)> & exception_handler)
8392
{
8493
(void)this_thread_number;
8594
while (rclcpp::ok(this->context_) && spinning.load()) {
@@ -97,7 +106,7 @@ MultiThreadedExecutor::run(size_t this_thread_number)
97106
std::this_thread::yield();
98107
}
99108

100-
execute_any_executable(any_exec);
109+
execute_any_executable(any_exec, exception_handler);
101110

102111
if (any_exec.callback_group &&
103112
any_exec.callback_group->type() == CallbackGroupType::MutuallyExclusive)

rclcpp/src/rclcpp/executors/single_threaded_executor.cpp

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,3 +43,25 @@ SingleThreadedExecutor::spin()
4343
}
4444
}
4545
}
46+
47+
48+
void
49+
SingleThreadedExecutor::spin(
50+
const std::function<void(const std::exception & e)> & exception_handler)
51+
{
52+
if (spinning.exchange(true)) {
53+
throw std::runtime_error("spin() called while already spinning");
54+
}
55+
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
56+
57+
// Clear any previous result and rebuild the waitset
58+
this->wait_result_.reset();
59+
this->entities_need_rebuild_ = true;
60+
61+
while (rclcpp::ok(this->context_) && spinning.load()) {
62+
rclcpp::AnyExecutable any_executable;
63+
if (get_next_executable(any_executable)) {
64+
execute_any_executable(any_executable, exception_handler);
65+
}
66+
}
67+
}

rclcpp/src/rclcpp/executors/static_single_threaded_executor.cpp

Lines changed: 39 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,24 @@ StaticSingleThreadedExecutor::spin()
4343
}
4444
}
4545

46+
47+
void
48+
StaticSingleThreadedExecutor::spin(
49+
const std::function<void(const std::exception & e)> & exception_handler)
50+
{
51+
if (spinning.exchange(true)) {
52+
throw std::runtime_error("spin() called while already spinning");
53+
}
54+
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
55+
56+
// This is essentially the contents of the rclcpp::Executor::wait_for_work method,
57+
// except we need to keep the wait result to reproduce the StaticSingleThreadedExecutor
58+
// behavior.
59+
while (rclcpp::ok(this->context_) && spinning.load()) {
60+
this->spin_once_impl(std::chrono::nanoseconds(-1), exception_handler);
61+
}
62+
}
63+
4664
void
4765
StaticSingleThreadedExecutor::spin_some(std::chrono::nanoseconds max_duration)
4866
{
@@ -97,12 +115,32 @@ StaticSingleThreadedExecutor::spin_some_impl(std::chrono::nanoseconds max_durati
97115

98116
void
99117
StaticSingleThreadedExecutor::spin_once_impl(std::chrono::nanoseconds timeout)
118+
{
119+
spin_once_impl(timeout, std::function<void(const std::exception & e)>());
120+
}
121+
122+
void
123+
StaticSingleThreadedExecutor::spin_once_impl(
124+
std::chrono::nanoseconds timeout,
125+
const std::function<void(const std::exception & e)> & exception_handler)
100126
{
101127
if (rclcpp::ok(context_) && spinning.load()) {
102128
std::lock_guard<std::mutex> guard(mutex_);
103129
auto wait_result = this->collect_and_wait(timeout);
104130
if (wait_result.has_value()) {
105-
this->execute_ready_executables(current_collection_, wait_result.value(), true);
131+
if(exception_handler) {
132+
try {
133+
this->execute_ready_executables(current_collection_, wait_result.value(), true);
134+
} catch (const std::exception & e) {
135+
RCLCPP_ERROR_STREAM(
136+
rclcpp::get_logger("rclcpp"),
137+
"Exception while spinning : " << e.what());
138+
139+
exception_handler(e);
140+
}
141+
} else {
142+
this->execute_ready_executables(current_collection_, wait_result.value(), true);
143+
}
106144
}
107145
}
108146
}

0 commit comments

Comments
 (0)