@@ -39,13 +39,18 @@ StaticSingleThreadedExecutor::spin()
3939 // except we need to keep the wait result to reproduce the StaticSingleThreadedExecutor
4040 // behavior.
4141 while (rclcpp::ok (this ->context_ ) && spinning.load ()) {
42- this ->spin_once_impl (std::chrono::nanoseconds (- 1 ) );
42+ return this ->spin_some_impl (std::chrono::nanoseconds (0 ), true );
4343 }
4444}
4545
4646void
4747StaticSingleThreadedExecutor::spin_some (std::chrono::nanoseconds max_duration)
4848{
49+ if (spinning.exchange (true )) {
50+ throw std::runtime_error (" spin_some() called while already spinning" );
51+ }
52+ RCPPUTILS_SCOPE_EXIT (this ->spinning .store (false ););
53+
4954 // In this context a 0 input max_duration means no duration limit
5055 if (std::chrono::nanoseconds (0 ) == max_duration) {
5156 max_duration = std::chrono::nanoseconds::max ();
@@ -56,6 +61,11 @@ StaticSingleThreadedExecutor::spin_some(std::chrono::nanoseconds max_duration)
5661void
5762StaticSingleThreadedExecutor::spin_all (std::chrono::nanoseconds max_duration)
5863{
64+ if (spinning.exchange (true )) {
65+ throw std::runtime_error (" spin_some() called while already spinning" );
66+ }
67+ RCPPUTILS_SCOPE_EXIT (this ->spinning .store (false ););
68+
5969 if (max_duration < std::chrono::nanoseconds (0 )) {
6070 throw std::invalid_argument (" max_duration must be greater than or equal to 0" );
6171 }
@@ -72,11 +82,6 @@ StaticSingleThreadedExecutor::spin_some_impl(std::chrono::nanoseconds max_durati
7282 return spin_forever || (cur_duration < max_duration);
7383 };
7484
75- if (spinning.exchange (true )) {
76- throw std::runtime_error (" spin_some() called while already spinning" );
77- }
78- RCPPUTILS_SCOPE_EXIT (this ->spinning .store (false ););
79-
8085 while (rclcpp::ok (context_) && spinning.load () && max_duration_not_elapsed ()) {
8186 // Get executables that are ready now
8287 std::lock_guard<std::mutex> guard (mutex_);
0 commit comments