Skip to content

Commit 9d20c70

Browse files
Janosch MachowinskiJanosch Machowinski
Janosch Machowinski
authored and
Janosch Machowinski
committed
feat(Executor): Added spin API with exception handler.
Signed-off-by: Janosch Machowinski <[email protected]> # Conflicts: # rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp # rclcpp/src/rclcpp/experimental/timers_manager.cpp
1 parent 142c921 commit 9d20c70

16 files changed

+322
-93
lines changed

rclcpp/include/rclcpp/executor.hpp

+24
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

+4-2
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@ class MultiThreadedExecutor : public rclcpp::Executor
7979
*/
8080
RCLCPP_PUBLIC
8181
void
82-
spin(std::function<void(const std::exception & e)> exception_handler);
82+
spin(const std::function<void(const std::exception & e)> & exception_handler) override;
8383

8484
RCLCPP_PUBLIC
8585
size_t
@@ -88,7 +88,9 @@ class MultiThreadedExecutor : public rclcpp::Executor
8888
protected:
8989
RCLCPP_PUBLIC
9090
void
91-
run(size_t this_thread_number, std::function<void(const std::exception & e)> exception_handler);
91+
run(
92+
size_t this_thread_number,
93+
const std::function<void(const std::exception & e)> & exception_handler);
9294

9395
private:
9496
RCLCPP_DISABLE_COPY(MultiThreadedExecutor)

rclcpp/include/rclcpp/executors/single_threaded_executor.hpp

+12
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

+10
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

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

+12
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

+12-2
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

+67
Original file line numberDiff line numberDiff line change
@@ -408,6 +408,73 @@ 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+
any_exec.waitable->execute(static_cast<const std::shared_ptr<void>>(any_exec.data));
462+
}, exception_handler);
463+
}
464+
// Reset the callback_group, regardless of type
465+
any_exec.callback_group->can_be_taken_from().store(true);
466+
// Wake the wait, because it may need to be recalculated or work that
467+
// was previously blocked is now available.
468+
try {
469+
interrupt_guard_condition_->trigger();
470+
} catch (const rclcpp::exceptions::RCLError & ex) {
471+
throw std::runtime_error(
472+
std::string(
473+
"Failed to trigger guard condition from execute_any_executable: ") + ex.what());
474+
}
475+
}
476+
477+
411478
template<typename Taker, typename Handler>
412479
static
413480
void

rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp

+29-38
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ MultiThreadedExecutor::spin()
5757

5858
void
5959

60-
MultiThreadedExecutor::spin(std::function<void(const std::exception & e)> exception_handler)
60+
MultiThreadedExecutor::spin(const std::function<void(const std::exception & e)> & exception_handler)
6161
{
6262
if (spinning.exchange(true)) {
6363
throw std::runtime_error("spin() called while already spinning");
@@ -88,49 +88,40 @@ MultiThreadedExecutor::get_number_of_threads()
8888
void
8989
MultiThreadedExecutor::run(
9090
size_t this_thread_number,
91-
std::function<void(const std::exception & e)> exception_handler)
91+
const std::function<void(const std::exception & e)> & exception_handler)
9292
{
93-
try {
94-
95-
(void)this_thread_number;
96-
while (rclcpp::ok(this->context_) && spinning.load()) {
97-
rclcpp::AnyExecutable any_exec;
98-
{
99-
std::lock_guard wait_lock{wait_mutex_};
100-
if (!rclcpp::ok(this->context_) || !spinning.load()) {
101-
return;
102-
}
103-
if (!get_next_executable(any_exec, next_exec_timeout_)) {
104-
continue;
105-
}
93+
(void)this_thread_number;
94+
while (rclcpp::ok(this->context_) && spinning.load()) {
95+
rclcpp::AnyExecutable any_exec;
96+
{
97+
std::lock_guard wait_lock{wait_mutex_};
98+
if (!rclcpp::ok(this->context_) || !spinning.load()) {
99+
return;
106100
}
107-
if (yield_before_execute_) {
108-
std::this_thread::yield();
101+
if (!get_next_executable(any_exec, next_exec_timeout_)) {
102+
continue;
109103
}
104+
}
105+
if (yield_before_execute_) {
106+
std::this_thread::yield();
107+
}
110108

111-
execute_any_executable(any_exec);
112-
113-
if (any_exec.callback_group &&
114-
any_exec.callback_group->type() == CallbackGroupType::MutuallyExclusive)
115-
{
116-
try {
117-
interrupt_guard_condition_->trigger();
118-
} catch (const rclcpp::exceptions::RCLError & ex) {
119-
throw std::runtime_error(
120-
std::string(
121-
"Failed to trigger guard condition on callback group change: ") + ex.what());
122-
}
109+
execute_any_executable(any_exec, exception_handler);
110+
111+
if (any_exec.callback_group &&
112+
any_exec.callback_group->type() == CallbackGroupType::MutuallyExclusive)
113+
{
114+
try {
115+
interrupt_guard_condition_->trigger();
116+
} catch (const rclcpp::exceptions::RCLError & ex) {
117+
throw std::runtime_error(
118+
std::string(
119+
"Failed to trigger guard condition on callback group change: ") + ex.what());
123120
}
124-
125-
// Clear the callback_group to prevent the AnyExecutable destructor from
126-
// resetting the callback group `can_be_taken_from`
127-
any_exec.callback_group.reset();
128121
}
129-
} catch (const std::exception & e) {
130-
RCLCPP_ERROR_STREAM(
131-
rclcpp::get_logger("rclcpp"),
132-
"Exception while spinning : " << e.what());
133122

134-
exception_handler(e);
123+
// Clear the callback_group to prevent the AnyExecutable destructor from
124+
// resetting the callback group `can_be_taken_from`
125+
any_exec.callback_group.reset();
135126
}
136127
}

rclcpp/src/rclcpp/executors/single_threaded_executor.cpp

+17
Original file line numberDiff line numberDiff line change
@@ -43,3 +43,20 @@ 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+
while (rclcpp::ok(this->context_) && spinning.load()) {
57+
rclcpp::AnyExecutable any_executable;
58+
if (get_next_executable(any_executable)) {
59+
execute_any_executable(any_executable, exception_handler);
60+
}
61+
}
62+
}

rclcpp/src/rclcpp/executors/static_single_threaded_executor.cpp

+27
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,33 @@ 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+
if (rclcpp::ok(context_) && spinning.load()) {
57+
std::lock_guard<std::mutex> guard(mutex_);
58+
auto wait_result = this->collect_and_wait(std::chrono::nanoseconds(-1));
59+
if (wait_result.has_value()) {
60+
try {
61+
this->execute_ready_executables(current_collection_, wait_result.value(), true);
62+
} catch (const std::exception & e) {
63+
RCLCPP_ERROR_STREAM(
64+
rclcpp::get_logger("rclcpp"),
65+
"Exception while spinning : " << e.what());
66+
67+
exception_handler(e);
68+
}
69+
}
70+
}
71+
}
72+
4673
void
4774
StaticSingleThreadedExecutor::spin_some(std::chrono::nanoseconds max_duration)
4875
{

0 commit comments

Comments
 (0)