@@ -51,6 +51,13 @@ MultiThreadedExecutor::~MultiThreadedExecutor() {}
5151
5252void
5353MultiThreadedExecutor::spin ()
54+ {
55+ spin ([](const std::exception & e) {throw e;});
56+ }
57+
58+ void
59+
60+ MultiThreadedExecutor::spin (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,40 +86,51 @@ MultiThreadedExecutor::get_number_of_threads()
7986}
8087
8188void
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)
8392{
84- (void )this_thread_number;
85- while (rclcpp::ok (this ->context_ ) && spinning.load ()) {
86- rclcpp::AnyExecutable any_exec;
87- {
88- std::lock_guard wait_lock{wait_mutex_};
89- if (!rclcpp::ok (this ->context_ ) || !spinning.load ()) {
90- return ;
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+ }
91106 }
92- if (! get_next_executable (any_exec, next_exec_timeout_) ) {
93- continue ;
107+ if (yield_before_execute_ ) {
108+ std::this_thread::yield () ;
94109 }
95- }
96- if (yield_before_execute_) {
97- std::this_thread::yield ();
98- }
99110
100- execute_any_executable (any_exec);
101-
102- if (any_exec.callback_group &&
103- any_exec.callback_group ->type () == CallbackGroupType::MutuallyExclusive)
104- {
105- try {
106- interrupt_guard_condition_->trigger ();
107- } catch (const rclcpp::exceptions::RCLError & ex) {
108- throw std::runtime_error (
109- std::string (
110- " Failed to trigger guard condition on callback group change: " ) + ex.what ());
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+ }
111123 }
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 ();
112128 }
129+ } catch (const std::exception & e) {
130+ RCLCPP_ERROR_STREAM (
131+ rclcpp::get_logger (" rclcpp" ),
132+ " Exception while spinning : " << e.what ());
113133
114- // Clear the callback_group to prevent the AnyExecutable destructor from
115- // resetting the callback group `can_be_taken_from`
116- any_exec.callback_group .reset ();
134+ exception_handler (e);
117135 }
118136}
0 commit comments