@@ -57,7 +57,7 @@ MultiThreadedExecutor::spin()
5757
5858void
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,48 +88,38 @@ MultiThreadedExecutor::get_number_of_threads()
8888void
8989MultiThreadedExecutor::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- (void )this_thread_number;
95- while (rclcpp::ok (this ->context_ ) && spinning.load ()) {
96- rclcpp::AnyExecutable any_exec;
97- {
98- std::lock_guard wait_lock{wait_mutex_};
99- if (!rclcpp::ok (this ->context_ ) || !spinning.load ()) {
100- return ;
101- }
102- if (!get_next_executable (any_exec, next_exec_timeout_)) {
103- continue ;
104- }
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 ;
105100 }
106- if (yield_before_execute_ ) {
107- std::this_thread::yield () ;
101+ if (! get_next_executable (any_exec, next_exec_timeout_) ) {
102+ continue ;
108103 }
104+ }
105+ if (yield_before_execute_) {
106+ std::this_thread::yield ();
107+ }
109108
110- execute_any_executable (any_exec);
111-
112- if (any_exec.callback_group &&
113- any_exec.callback_group ->type () == CallbackGroupType::MutuallyExclusive)
114- {
115- try {
116- interrupt_guard_condition_->trigger ();
117- } catch (const rclcpp::exceptions::RCLError & ex) {
118- throw std::runtime_error (
119- std::string (
120- " Failed to trigger guard condition on callback group change: " ) + ex.what ());
121- }
122- }
109+ execute_any_executable (any_exec, exception_handler);
123110
124- // Clear the callback_group to prevent the AnyExecutable destructor from
125- // resetting the callback group `can_be_taken_from`
126- any_exec.callback_group .reset ();
127- }
128- } catch (const std::exception & e) {
129- RCLCPP_ERROR_STREAM (
130- rclcpp::get_logger (" rclcpp" ),
131- " Exception while spinning : " << e.what ());
111+ // Clear the callback_group to prevent the AnyExecutable destructor from
112+ // resetting the callback group `can_be_taken_from`
113+ any_exec.callback_group .reset ();
132114
133- exception_handler (e);
115+ // Wake the wait, because it may need to be recalculated or work that
116+ // was previously blocked is now available.
117+ try {
118+ interrupt_guard_condition_->trigger ();
119+ } catch (const rclcpp::exceptions::RCLError & ex) {
120+ throw std::runtime_error (
121+ std::string (
122+ " Failed to trigger guard condition from execute_any_executable: " ) + ex.what ());
123+ }
134124 }
135125}
0 commit comments