Skip to content

Commit 6c55f0b

Browse files
author
iRobot ROS
authored
Merge pull request #31 from mauropasse/mauro/pr-events-executor
rename local_event_queue -> execution_event_queue
2 parents 5971b41 + 0a5f3f2 commit 6c55f0b

19 files changed

+45
-45
lines changed

rclcpp/include/rclcpp/client.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -160,7 +160,7 @@ class ClientBase
160160
void
161161
set_events_executor_callback(
162162
const rclcpp::executors::EventsExecutor * executor,
163-
EventsExecutorCallback executor_callback) const;
163+
rmw_listener_cb_t executor_callback) const;
164164

165165
RCLCPP_PUBLIC
166166
void

rclcpp/include/rclcpp/executors/events_executor.hpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@
2626
#include "rclcpp/executors/timers_manager.hpp"
2727
#include "rclcpp/node.hpp"
2828

29-
#include "rmw/executor_event_types.h"
29+
#include "rmw/listener_event_types.h"
3030

3131
namespace rclcpp
3232
{
@@ -176,13 +176,13 @@ class EventsExecutor : public rclcpp::Executor
176176

177177
// Event queue implementation is a deque only to
178178
// facilitate the removal of events from expired entities.
179-
using EventQueue = std::deque<ExecutorEvent>;
179+
using EventQueue = std::deque<rmw_listener_event_t>;
180180

181181
// Executor callback: Push new events into the queue and trigger cv.
182182
// This function is called by the DDS entities when an event happened,
183183
// like a subscription receiving a message.
184184
static void
185-
push_event(const void * executor_ptr, ExecutorEvent event)
185+
push_event(const void * executor_ptr, rmw_listener_event_t event)
186186
{
187187
// Cast executor_ptr to this (need to remove constness)
188188
auto this_executor = const_cast<executors::EventsExecutor *>(
@@ -217,18 +217,18 @@ class EventsExecutor : public rclcpp::Executor
217217
event_queue_.erase(
218218
std::remove_if(
219219
event_queue_.begin(), event_queue_.end(),
220-
[&entity](ExecutorEvent event) {return event.entity == entity;}), event_queue_.end());
220+
[&entity](rmw_listener_event_t event) {return event.entity == entity;}), event_queue_.end());
221221
}
222222

223223
// Remove events associated with this entity from the local event queue
224224
{
225225
std::unique_lock<std::mutex> lock(execution_mutex_);
226-
local_event_queue_.erase(
226+
execution_event_queue_.erase(
227227
std::remove_if(
228-
local_event_queue_.begin(), local_event_queue_.end(),
229-
[&entity](ExecutorEvent event) {
228+
execution_event_queue_.begin(), execution_event_queue_.end(),
229+
[&entity](rmw_listener_event_t event) {
230230
return event.entity == entity;
231-
}), local_event_queue_.end());
231+
}), execution_event_queue_.end());
232232
}
233233
}
234234

@@ -240,11 +240,11 @@ class EventsExecutor : public rclcpp::Executor
240240
// Execute a single event
241241
RCLCPP_PUBLIC
242242
void
243-
execute_event(const ExecutorEvent & event);
243+
execute_event(const rmw_listener_event_t & event);
244244

245245
// We use two instances of EventQueue to allow threads to push events while we execute them
246246
EventQueue event_queue_;
247-
EventQueue local_event_queue_;
247+
EventQueue execution_event_queue_;
248248

249249
EventsExecutorEntitiesCollector::SharedPtr entities_collector_;
250250
EventsExecutorNotifyWaitable::SharedPtr executor_notifier_;

rclcpp/include/rclcpp/executors/events_executor_notify_waitable.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -64,10 +64,10 @@ class EventsExecutorNotifyWaitable final : public EventWaitable
6464
void
6565
set_events_executor_callback(
6666
const rclcpp::executors::EventsExecutor * executor,
67-
EventsExecutorCallback executor_callback) const override
67+
rmw_listener_cb_t executor_callback) const override
6868
{
6969
for (auto gc : notify_guard_conditions_) {
70-
rcl_ret_t ret = rcl_guard_condition_set_events_executor_callback(
70+
rcl_ret_t ret = rcl_guard_condition_set_listener_callback(
7171
executor,
7272
executor_callback,
7373
this,

rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@ class SubscriptionIntraProcessBase : public rclcpp::Waitable
7474
void
7575
set_events_executor_callback(
7676
const rclcpp::executors::EventsExecutor * executor,
77-
EventsExecutorCallback executor_callback) const override;
77+
rmw_listener_cb_t executor_callback) const override;
7878

7979
protected:
8080
std::recursive_mutex reentrant_mutex_;

rclcpp/include/rclcpp/qos_event.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,7 @@ class QOSEventHandlerBase : public Waitable
110110
void
111111
set_events_executor_callback(
112112
const rclcpp::executors::EventsExecutor * executor,
113-
EventsExecutorCallback executor_callback) const override;
113+
rmw_listener_cb_t executor_callback) const override;
114114

115115
protected:
116116
rcl_event_t event_handle_;

rclcpp/include/rclcpp/service.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ class ServiceBase
130130
void
131131
set_events_executor_callback(
132132
const rclcpp::executors::EventsExecutor * executor,
133-
EventsExecutorCallback executor_callback) const;
133+
rmw_listener_cb_t executor_callback) const;
134134

135135
RCLCPP_PUBLIC
136136
void

rclcpp/include/rclcpp/subscription_base.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -273,7 +273,7 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
273273
void
274274
set_events_executor_callback(
275275
const rclcpp::executors::EventsExecutor * executor,
276-
EventsExecutorCallback executor_callback) const;
276+
rmw_listener_cb_t executor_callback) const;
277277

278278
RCLCPP_PUBLIC
279279
void

rclcpp/include/rclcpp/waitable.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -176,7 +176,7 @@ class Waitable
176176
void
177177
set_events_executor_callback(
178178
const rclcpp::executors::EventsExecutor * executor,
179-
EventsExecutorCallback executor_callback) const;
179+
rmw_listener_cb_t executor_callback) const;
180180

181181
RCLCPP_PUBLIC
182182
void

rclcpp/src/rclcpp/client.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -205,9 +205,9 @@ ClientBase::exchange_in_use_by_wait_set_state(bool in_use_state)
205205
void
206206
ClientBase::set_events_executor_callback(
207207
const rclcpp::executors::EventsExecutor * executor,
208-
EventsExecutorCallback executor_callback) const
208+
rmw_listener_cb_t executor_callback) const
209209
{
210-
rcl_ret_t ret = rcl_client_set_events_executor_callback(
210+
rcl_ret_t ret = rcl_client_set_listener_callback(
211211
executor,
212212
executor_callback,
213213
this,

rclcpp/src/rclcpp/executors/events_executor.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -67,11 +67,11 @@ EventsExecutor::spin()
6767
event_queue_cv_.wait(push_lock, has_event_predicate);
6868
std::unique_lock<std::mutex> execution_lock(execution_mutex_);
6969
// We got an event! Swap queues while we hold both mutexes
70-
std::swap(local_event_queue_, event_queue_);
70+
std::swap(execution_event_queue_, event_queue_);
7171
// After swapping the queues, we don't need the push lock anymore
7272
push_lock.unlock();
7373
// Consume events while under the execution lock only
74-
this->consume_all_events(local_event_queue_);
74+
this->consume_all_events(execution_event_queue_);
7575
}
7676
timers_manager_->stop();
7777
}
@@ -108,9 +108,9 @@ EventsExecutor::spin_some(std::chrono::nanoseconds max_duration)
108108
std::unique_lock<std::mutex> push_lock(push_mutex_);
109109
event_queue_cv_.wait_for(push_lock, max_duration, has_event_predicate);
110110
std::unique_lock<std::mutex> execution_lock(execution_mutex_);
111-
std::swap(local_event_queue_, event_queue_);
111+
std::swap(execution_event_queue_, event_queue_);
112112
push_lock.unlock();
113-
this->consume_all_events(local_event_queue_);
113+
this->consume_all_events(execution_event_queue_);
114114
execution_lock.unlock();
115115

116116
timers_manager_->execute_ready_timers();
@@ -154,18 +154,18 @@ EventsExecutor::spin_all(std::chrono::nanoseconds max_duration)
154154
while (rclcpp::ok(context_) && spinning.load() && max_duration_not_elapsed()) {
155155
std::unique_lock<std::mutex> push_lock(push_mutex_);
156156
std::unique_lock<std::mutex> execution_lock(execution_mutex_);
157-
std::swap(local_event_queue_, event_queue_);
157+
std::swap(execution_event_queue_, event_queue_);
158158
push_lock.unlock();
159159

160160
bool ready_timer = timers_manager_->get_head_timeout() < 0ns;
161-
bool has_events = !local_event_queue_.empty();
161+
bool has_events = !execution_event_queue_.empty();
162162
if (!ready_timer && !has_events) {
163163
// Exit as there is no more work to do
164164
break;
165165
}
166166
// Execute all ready work
167167

168-
this->consume_all_events(local_event_queue_);
168+
this->consume_all_events(execution_event_queue_);
169169
execution_lock.unlock();
170170

171171
timers_manager_->execute_ready_timers();
@@ -189,7 +189,7 @@ EventsExecutor::spin_once_impl(std::chrono::nanoseconds timeout)
189189
// When condition variable is notified, check this predicate to proceed
190190
auto has_event_predicate = [this]() {return !event_queue_.empty();};
191191

192-
ExecutorEvent event;
192+
rmw_listener_event_t event;
193193
bool has_event = false;
194194

195195
{
@@ -255,15 +255,15 @@ void
255255
EventsExecutor::consume_all_events(EventQueue & event_queue)
256256
{
257257
while (!event_queue.empty()) {
258-
ExecutorEvent event = event_queue.front();
258+
rmw_listener_event_t event = event_queue.front();
259259
event_queue.pop_front();
260260

261261
this->execute_event(event);
262262
}
263263
}
264264

265265
void
266-
EventsExecutor::execute_event(const ExecutorEvent & event)
266+
EventsExecutor::execute_event(const rmw_listener_event_t & event)
267267
{
268268
switch (event.type) {
269269
case SUBSCRIPTION_EVENT:

0 commit comments

Comments
 (0)