@@ -51,6 +51,13 @@ MultiThreadedExecutor::~MultiThreadedExecutor() {}
51
51
52
52
void
53
53
MultiThreadedExecutor::spin ()
54
+ {
55
+ spin (std::function<void (const std::exception &)>());
56
+ }
57
+
58
+ void
59
+
60
+ MultiThreadedExecutor::spin (std::function<void (const std::exception & e)> exception_handler)
54
61
{
55
62
if (spinning.exchange (true )) {
56
63
throw std::runtime_error (" spin() called while already spinning" );
@@ -61,12 +68,12 @@ MultiThreadedExecutor::spin()
61
68
{
62
69
std::lock_guard wait_lock{wait_mutex_};
63
70
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 );
65
72
threads.emplace_back (func);
66
73
}
67
74
}
68
75
69
- run (thread_id);
76
+ run (thread_id, exception_handler );
70
77
for (auto & thread : threads) {
71
78
thread.join ();
72
79
}
@@ -79,28 +86,47 @@ MultiThreadedExecutor::get_number_of_threads()
79
86
}
80
87
81
88
void
82
- MultiThreadedExecutor::run (size_t this_thread_number)
89
+ MultiThreadedExecutor::run (
90
+ size_t this_thread_number,
91
+ std::function<void (const std::exception & e)> exception_handler)
83
92
{
84
93
(void )this_thread_number;
85
- while (rclcpp::ok (this ->context_ ) && spinning.load ()) {
86
- rclcpp::AnyExecutable any_exec;
94
+ const auto run_inner = [this ]()
87
95
{
88
- std::lock_guard wait_lock{wait_mutex_};
89
- if (!rclcpp::ok (this ->context_ ) || !spinning.load ()) {
90
- return ;
91
- }
92
- if (!get_next_executable (any_exec, next_exec_timeout_)) {
93
- continue ;
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
+ }
106
+ }
107
+ if (yield_before_execute_) {
108
+ std::this_thread::yield ();
109
+ }
110
+
111
+ execute_any_executable (any_exec);
112
+
113
+ // Clear the callback_group to prevent the AnyExecutable destructor from
114
+ // resetting the callback group `can_be_taken_from`
115
+ any_exec.callback_group .reset ();
94
116
}
95
- }
96
- if (yield_before_execute_) {
97
- std::this_thread::yield ();
98
- }
117
+ };
99
118
100
- execute_any_executable (any_exec);
119
+ if (exception_handler) {
120
+ try {
121
+ run_inner ();
122
+ } catch (const std::exception & e) {
123
+ RCLCPP_ERROR_STREAM (
124
+ rclcpp::get_logger (" rclcpp" ),
125
+ " Exception while spinning : " << e.what ());
101
126
102
- // Clear the callback_group to prevent the AnyExecutable destructor from
103
- // resetting the callback group `can_be_taken_from`
104
- any_exec.callback_group .reset ();
127
+ exception_handler (e);
128
+ }
129
+ } else {
130
+ run_inner ();
105
131
}
106
132
}
0 commit comments