Skip to content

Commit bb491bd

Browse files
author
iRobot ROS
authored
Merge pull request #46 from mauropasse/mauro/fix-spin-some-events-executor
Proper spin_some behaviour on EventsExecutor
2 parents e6d6426 + feef4e2 commit bb491bd

File tree

8 files changed

+124
-80
lines changed

8 files changed

+124
-80
lines changed

rclcpp/include/rclcpp/executors/events_executor.hpp

Lines changed: 29 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -82,15 +82,36 @@ class EventsExecutor : public rclcpp::Executor
8282

8383
/// Events executor implementation of spin some
8484
/**
85-
* executor.provide_callbacks();
86-
* while(condition) {
87-
* executor.spin_some();
88-
* }
85+
* This non-blocking function will execute the timers and events
86+
* that were ready when this API was called, until timeout or no
87+
* more work available. New ready-timers/events arrived while
88+
* executing work, won't be taken into account here.
89+
*
90+
* Example:
91+
* while(condition) {
92+
* spin_some();
93+
* sleep(); // User should have some sync work or
94+
* // sleep to avoid a 100% CPU usage
95+
* }
8996
*/
9097
RCLCPP_PUBLIC
9198
void
9299
spin_some(std::chrono::nanoseconds max_duration = std::chrono::nanoseconds(0)) override;
93100

101+
/// Events executor implementation of spin all
102+
/**
103+
* This non-blocking function will execute timers and events
104+
* until timeout or no more work available. If new ready-timers/events
105+
* arrive while executing work available, they will be executed
106+
* as long as the timeout hasn't expired.
107+
*
108+
* Example:
109+
* while(condition) {
110+
* spin_all();
111+
* sleep(); // User should have some sync work or
112+
* // sleep to avoid a 100% CPU usage
113+
* }
114+
*/
94115
RCLCPP_PUBLIC
95116
void
96117
spin_all(std::chrono::nanoseconds max_duration) override;
@@ -176,6 +197,10 @@ class EventsExecutor : public rclcpp::Executor
176197
void
177198
spin_once_impl(std::chrono::nanoseconds timeout) override;
178199

200+
RCLCPP_PUBLIC
201+
void
202+
spin_some_impl(std::chrono::nanoseconds max_duration, bool exhaustive);
203+
179204
private:
180205
RCLCPP_DISABLE_COPY(EventsExecutor)
181206

rclcpp/include/rclcpp/executors/timers_manager.hpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -101,11 +101,13 @@ class TimersManager
101101
std::chrono::nanoseconds execute_ready_timers();
102102

103103
/**
104-
* @brief Executes one ready timer if available
105-
*
106-
* @return true if there was a timer ready
104+
* @brief Executes head timer if ready at time point.
105+
* @param tp the timepoint to check for
106+
* @return true if head timer was ready at tp
107107
*/
108-
bool execute_head_timer();
108+
bool execute_head_timer(
109+
std::chrono::time_point<std::chrono::steady_clock> tp =
110+
std::chrono::time_point<std::chrono::steady_clock>::max());
109111

110112
/**
111113
* @brief Get the amount of time before the next timer expires.

rclcpp/include/rclcpp/experimental/buffers/events_queue.hpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -83,6 +83,15 @@ class EventsQueue
8383
bool
8484
empty() const = 0;
8585

86+
/**
87+
* @brief Returns the number of elements in the queue.
88+
* @return the number of elements in the queue.
89+
*/
90+
RCLCPP_PUBLIC
91+
virtual
92+
size_t
93+
size() const = 0;
94+
8695
/**
8796
* @brief Initializes the queue
8897
*/

rclcpp/include/rclcpp/experimental/buffers/simple_events_queue.hpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -89,6 +89,18 @@ class SimpleEventsQueue : public EventsQueue
8989
return event_queue_.empty();
9090
}
9191

92+
/**
93+
* @brief Returns the number of elements in the queue.
94+
* @return the number of elements in the queue.
95+
*/
96+
RCLCPP_PUBLIC
97+
virtual
98+
size_t
99+
size() const
100+
{
101+
return event_queue_.size();
102+
}
103+
92104
/**
93105
* @brief Initializes the queue
94106
*/

rclcpp/src/rclcpp/executors/events_executor.cpp

Lines changed: 43 additions & 65 deletions
Original file line numberDiff line numberDiff line change
@@ -60,17 +60,14 @@ EventsExecutor::spin()
6060
// When condition variable is notified, check this predicate to proceed
6161
auto has_event_predicate = [this]() {return !events_queue_->empty();};
6262

63-
// Local event queue to allow entities to push events while we execute them
64-
EventQueue execution_event_queue;
65-
6663
timers_manager_->start();
6764

6865
while (rclcpp::ok(context_) && spinning.load()) {
6966
std::unique_lock<std::mutex> push_lock(push_mutex_);
7067
// We wait here until something has been pushed to the event queue
7168
events_queue_cv_.wait(push_lock, has_event_predicate);
7269
// Local event queue to allow entities to push events while we execute them
73-
execution_event_queue = events_queue_->get_all_events();
70+
EventQueue execution_event_queue = events_queue_->get_all_events();
7471
// Unlock the mutex
7572
push_lock.unlock();
7673
// Consume all available events, this queue will be empty at the end of the function
@@ -82,43 +79,12 @@ EventsExecutor::spin()
8279
void
8380
EventsExecutor::spin_some(std::chrono::nanoseconds max_duration)
8481
{
85-
if (spinning.exchange(true)) {
86-
throw std::runtime_error("spin_some() called while already spinning");
87-
}
88-
RCLCPP_SCOPE_EXIT(this->spinning.store(false););
89-
9082
// In this context a 0 input max_duration means no duration limit
9183
if (std::chrono::nanoseconds(0) == max_duration) {
9284
max_duration = timers_manager_->MAX_TIME;
9385
}
9486

95-
// This function will wait until the first of the following events occur:
96-
// - The input max_duration is elapsed
97-
// - A timer triggers
98-
// - An executor event is received and processed
99-
100-
// When condition variable is notified, check this predicate to proceed
101-
auto has_event_predicate = [this]() {return !events_queue_->empty();};
102-
103-
104-
// Select the smallest between input max_duration and timer timeout
105-
auto next_timer_timeout = timers_manager_->get_head_timeout();
106-
if (next_timer_timeout < max_duration) {
107-
max_duration = next_timer_timeout;
108-
}
109-
110-
std::unique_lock<std::mutex> push_lock(push_mutex_);
111-
// Wait until timeout or event
112-
events_queue_cv_.wait_for(push_lock, max_duration, has_event_predicate);
113-
// Local event queue to allow entities to push events while we execute them
114-
EventQueue execution_event_queue = events_queue_->get_all_events();
115-
// We don't need the lock anymore
116-
push_lock.unlock();
117-
118-
// Execute all ready timers
119-
timers_manager_->execute_ready_timers();
120-
// Consume all available events, this queue will be empty at the end of the function
121-
this->consume_all_events(execution_event_queue);
87+
return this->spin_some_impl(max_duration, false);
12288
}
12389

12490
void
@@ -127,54 +93,66 @@ EventsExecutor::spin_all(std::chrono::nanoseconds max_duration)
12793
if (max_duration <= 0ns) {
12894
throw std::invalid_argument("max_duration must be positive");
12995
}
96+
return this->spin_some_impl(max_duration, true);
97+
}
13098

99+
void
100+
EventsExecutor::spin_some_impl(std::chrono::nanoseconds max_duration, bool exhaustive)
101+
{
131102
if (spinning.exchange(true)) {
132103
throw std::runtime_error("spin_some() called while already spinning");
133104
}
134-
RCLCPP_SCOPE_EXIT(this->spinning.store(false););
135105

136-
// When condition variable is notified, check this predicate to proceed
137-
auto has_event_predicate = [this]() {return !events_queue_->empty();};
138-
139-
// Local event queue to allow entities to push events while we execute them
140-
EventQueue execution_event_queue;
106+
RCLCPP_SCOPE_EXIT(this->spinning.store(false););
141107

142108
auto start = std::chrono::steady_clock::now();
109+
143110
auto max_duration_not_elapsed = [max_duration, start]() {
144111
auto elapsed_time = std::chrono::steady_clock::now() - start;
145112
return elapsed_time < max_duration;
146113
};
147114

148-
// Select the smallest between input max duration and timer timeout
149-
auto next_timer_timeout = timers_manager_->get_head_timeout();
150-
if (next_timer_timeout < max_duration) {
151-
max_duration = next_timer_timeout;
152-
}
115+
size_t ready_events_at_start = 0;
116+
size_t executed_events = 0;
153117

154-
{
155-
// Wait once until timeout or event
156-
std::unique_lock<std::mutex> push_lock(push_mutex_);
157-
events_queue_cv_.wait_for(push_lock, max_duration, has_event_predicate);
118+
if (!exhaustive) {
119+
// Get the number of events ready at start
120+
std::unique_lock<std::mutex> lock(push_mutex_);
121+
ready_events_at_start = events_queue_->size();
122+
lock.unlock();
158123
}
159124

160-
auto timeout = timers_manager_->get_head_timeout();
161-
162-
// Keep executing until no more work to do or timeout expired
163125
while (rclcpp::ok(context_) && spinning.load() && max_duration_not_elapsed()) {
164-
std::unique_lock<std::mutex> push_lock(push_mutex_);
165-
execution_event_queue = events_queue_->get_all_events();
166-
push_lock.unlock();
126+
// Execute first ready event from queue if exists
127+
if (exhaustive || (executed_events < ready_events_at_start)) {
128+
std::unique_lock<std::mutex> lock(push_mutex_);
129+
bool has_event = !events_queue_->empty();
130+
131+
if (has_event) {
132+
rmw_listener_event_t event = events_queue_->front();
133+
events_queue_->pop();
134+
this->execute_event(event);
135+
executed_events++;
136+
continue;
137+
}
138+
}
167139

168-
// Exit if there is no more work to do
169-
const bool ready_timer = timeout < 0ns;
170-
const bool has_events = !execution_event_queue.empty();
171-
if (!ready_timer && !has_events) {
172-
break;
140+
bool timer_executed;
141+
142+
if (exhaustive) {
143+
// Execute timer if is ready
144+
timer_executed = timers_manager_->execute_head_timer();
145+
} else {
146+
// Execute timer if was ready at start
147+
timer_executed = timers_manager_->execute_head_timer(start);
173148
}
174149

175-
// Execute all ready work
176-
timeout = timers_manager_->execute_ready_timers();
177-
this->consume_all_events(execution_event_queue);
150+
if (timer_executed) {
151+
continue;
152+
}
153+
154+
// If there's no more work available, exit
155+
break;
178156
}
179157
}
180158

rclcpp/src/rclcpp/executors/timers_manager.cpp

Lines changed: 15 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -116,7 +116,8 @@ std::chrono::nanoseconds TimersManager::execute_ready_timers()
116116
return this->get_head_timeout_unsafe(timers_heap);
117117
}
118118

119-
bool TimersManager::execute_head_timer()
119+
bool TimersManager::execute_head_timer(
120+
std::chrono::time_point<std::chrono::steady_clock> timepoint)
120121
{
121122
// Do not allow to interfere with the thread running
122123
if (running_) {
@@ -127,13 +128,25 @@ bool TimersManager::execute_head_timer()
127128
std::unique_lock<std::mutex> lock(timers_mutex_);
128129

129130
TimersHeap timers_heap = weak_timers_heap_.validate_and_lock();
131+
130132
// Nothing to do if we don't have any timer
131133
if (timers_heap.empty()) {
132134
return false;
133135
}
134136

135137
TimerPtr head = timers_heap.front();
136-
if (head->is_ready()) {
138+
139+
bool timer_ready = false;
140+
141+
auto max_time = std::chrono::time_point<std::chrono::steady_clock>::max();
142+
143+
if (timepoint != max_time) {
144+
timer_ready = timer_was_ready_at_tp(head, timepoint);
145+
} else {
146+
timer_ready = head->is_ready();
147+
}
148+
149+
if (timer_ready) {
137150
// Head timer is ready, execute
138151
head->execute_callback();
139152
timers_heap.heapify_root();

rclcpp/test/rclcpp/executors/test_events_executor.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -187,6 +187,9 @@ TEST_F(TestEventsExecutor, spin_some_max_duration)
187187
t_runs++;
188188
});
189189

190+
// Sleep some time for the timer to be ready when spin
191+
std::this_thread::sleep_for(10ms);
192+
190193
EventsExecutor executor;
191194
executor.add_node(node);
192195

@@ -209,6 +212,9 @@ TEST_F(TestEventsExecutor, spin_some_zero_duration)
209212
t_runs++;
210213
});
211214

215+
// Sleep some time for the timer to be ready when spin
216+
std::this_thread::sleep_for(20ms);
217+
212218
EventsExecutor executor;
213219
executor.add_node(node);
214220
executor.spin_some(0ms);
@@ -248,6 +254,9 @@ TEST_F(TestEventsExecutor, spin_all_max_duration)
248254
t_runs++;
249255
});
250256

257+
// Sleep some time for the timer to be ready when spin
258+
std::this_thread::sleep_for(10ms);
259+
251260
EventsExecutor executor;
252261
executor.add_node(node);
253262

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -501,6 +501,7 @@ TYPED_TEST(TestExecutorsStable, spinAll) {
501501
// executor.
502502
bool spin_exited = false;
503503
std::thread spinner([&spin_exited, &executor, this]() {
504+
std::this_thread::sleep_for(10ms);
504505
executor.spin_all(1s);
505506
executor.remove_node(this->node, true);
506507
spin_exited = true;
@@ -547,11 +548,6 @@ TYPED_TEST(TestExecutorsStable, spinSome) {
547548
spin_exited = true;
548549
});
549550

550-
// Give some time for executor to start spinning
551-
// otherwise when it will start looking for work to do it will already find
552-
// more than 1 notification
553-
std::this_thread::sleep_for(10ms);
554-
555551
// Do some work until sufficient calls to the waitable occur, but keep going until either
556552
// count becomes too large, spin exits, or the 1 second timeout completes.
557553
auto start = std::chrono::steady_clock::now();

0 commit comments

Comments
 (0)