@@ -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,49 +88,40 @@ 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-
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}
0 commit comments