diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index fc6c846d2a..080c8f9c08 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -160,7 +160,7 @@ class ClientBase void set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const; + rmw_listener_cb_t executor_callback) const; RCLCPP_PUBLIC void diff --git a/rclcpp/include/rclcpp/executors/events_executor.hpp b/rclcpp/include/rclcpp/executors/events_executor.hpp index 339aae4bc6..1c78f79728 100644 --- a/rclcpp/include/rclcpp/executors/events_executor.hpp +++ b/rclcpp/include/rclcpp/executors/events_executor.hpp @@ -26,7 +26,7 @@ #include "rclcpp/executors/timers_manager.hpp" #include "rclcpp/node.hpp" -#include "rmw/executor_event_types.h" +#include "rmw/listener_event_types.h" namespace rclcpp { @@ -176,13 +176,13 @@ class EventsExecutor : public rclcpp::Executor // Event queue implementation is a deque only to // facilitate the removal of events from expired entities. - using EventQueue = std::deque; + using EventQueue = std::deque; // Executor callback: Push new events into the queue and trigger cv. // This function is called by the DDS entities when an event happened, // like a subscription receiving a message. static void - push_event(const void * executor_ptr, ExecutorEvent event) + push_event(const void * executor_ptr, rmw_listener_event_t event) { // Cast executor_ptr to this (need to remove constness) auto this_executor = const_cast( @@ -217,18 +217,18 @@ class EventsExecutor : public rclcpp::Executor event_queue_.erase( std::remove_if( event_queue_.begin(), event_queue_.end(), - [&entity](ExecutorEvent event) {return event.entity == entity;}), event_queue_.end()); + [&entity](rmw_listener_event_t event) {return event.entity == entity;}), event_queue_.end()); } // Remove events associated with this entity from the local event queue { std::unique_lock lock(execution_mutex_); - local_event_queue_.erase( + execution_event_queue_.erase( std::remove_if( - local_event_queue_.begin(), local_event_queue_.end(), - [&entity](ExecutorEvent event) { + execution_event_queue_.begin(), execution_event_queue_.end(), + [&entity](rmw_listener_event_t event) { return event.entity == entity; - }), local_event_queue_.end()); + }), execution_event_queue_.end()); } } @@ -240,11 +240,11 @@ class EventsExecutor : public rclcpp::Executor // Execute a single event RCLCPP_PUBLIC void - execute_event(const ExecutorEvent & event); + execute_event(const rmw_listener_event_t & event); // We use two instances of EventQueue to allow threads to push events while we execute them EventQueue event_queue_; - EventQueue local_event_queue_; + EventQueue execution_event_queue_; EventsExecutorEntitiesCollector::SharedPtr entities_collector_; EventsExecutorNotifyWaitable::SharedPtr executor_notifier_; diff --git a/rclcpp/include/rclcpp/executors/events_executor_notify_waitable.hpp b/rclcpp/include/rclcpp/executors/events_executor_notify_waitable.hpp index 5b2398c13d..ce67004ca5 100644 --- a/rclcpp/include/rclcpp/executors/events_executor_notify_waitable.hpp +++ b/rclcpp/include/rclcpp/executors/events_executor_notify_waitable.hpp @@ -64,10 +64,10 @@ class EventsExecutorNotifyWaitable final : public EventWaitable void set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const override + rmw_listener_cb_t executor_callback) const override { for (auto gc : notify_guard_conditions_) { - rcl_ret_t ret = rcl_guard_condition_set_events_executor_callback( + rcl_ret_t ret = rcl_guard_condition_set_listener_callback( executor, executor_callback, this, diff --git a/rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp b/rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp index d8be34cc74..c5d2e33455 100644 --- a/rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp +++ b/rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp @@ -74,7 +74,7 @@ class SubscriptionIntraProcessBase : public rclcpp::Waitable void set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const override; + rmw_listener_cb_t executor_callback) const override; protected: std::recursive_mutex reentrant_mutex_; diff --git a/rclcpp/include/rclcpp/qos_event.hpp b/rclcpp/include/rclcpp/qos_event.hpp index b21d58ae2c..f43e0712cb 100644 --- a/rclcpp/include/rclcpp/qos_event.hpp +++ b/rclcpp/include/rclcpp/qos_event.hpp @@ -110,7 +110,7 @@ class QOSEventHandlerBase : public Waitable void set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const override; + rmw_listener_cb_t executor_callback) const override; protected: rcl_event_t event_handle_; diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index 5a3590cc43..9e33c05374 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -130,7 +130,7 @@ class ServiceBase void set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const; + rmw_listener_cb_t executor_callback) const; RCLCPP_PUBLIC void diff --git a/rclcpp/include/rclcpp/subscription_base.hpp b/rclcpp/include/rclcpp/subscription_base.hpp index ccdb57f77c..f9a591dbd1 100644 --- a/rclcpp/include/rclcpp/subscription_base.hpp +++ b/rclcpp/include/rclcpp/subscription_base.hpp @@ -273,7 +273,7 @@ class SubscriptionBase : public std::enable_shared_from_this void set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const; + rmw_listener_cb_t executor_callback) const; RCLCPP_PUBLIC void diff --git a/rclcpp/include/rclcpp/waitable.hpp b/rclcpp/include/rclcpp/waitable.hpp index d1e2eb622c..8e45533754 100644 --- a/rclcpp/include/rclcpp/waitable.hpp +++ b/rclcpp/include/rclcpp/waitable.hpp @@ -176,7 +176,7 @@ class Waitable void set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const; + rmw_listener_cb_t executor_callback) const; RCLCPP_PUBLIC void diff --git a/rclcpp/src/rclcpp/client.cpp b/rclcpp/src/rclcpp/client.cpp index 5484597689..55fdbca3b4 100644 --- a/rclcpp/src/rclcpp/client.cpp +++ b/rclcpp/src/rclcpp/client.cpp @@ -205,9 +205,9 @@ ClientBase::exchange_in_use_by_wait_set_state(bool in_use_state) void ClientBase::set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const + rmw_listener_cb_t executor_callback) const { - rcl_ret_t ret = rcl_client_set_events_executor_callback( + rcl_ret_t ret = rcl_client_set_listener_callback( executor, executor_callback, this, diff --git a/rclcpp/src/rclcpp/executors/events_executor.cpp b/rclcpp/src/rclcpp/executors/events_executor.cpp index fbe5fdc65f..0ac56f6e34 100644 --- a/rclcpp/src/rclcpp/executors/events_executor.cpp +++ b/rclcpp/src/rclcpp/executors/events_executor.cpp @@ -67,11 +67,11 @@ EventsExecutor::spin() event_queue_cv_.wait(push_lock, has_event_predicate); std::unique_lock execution_lock(execution_mutex_); // We got an event! Swap queues while we hold both mutexes - std::swap(local_event_queue_, event_queue_); + std::swap(execution_event_queue_, event_queue_); // After swapping the queues, we don't need the push lock anymore push_lock.unlock(); // Consume events while under the execution lock only - this->consume_all_events(local_event_queue_); + this->consume_all_events(execution_event_queue_); } timers_manager_->stop(); } @@ -108,9 +108,9 @@ EventsExecutor::spin_some(std::chrono::nanoseconds max_duration) std::unique_lock push_lock(push_mutex_); event_queue_cv_.wait_for(push_lock, max_duration, has_event_predicate); std::unique_lock execution_lock(execution_mutex_); - std::swap(local_event_queue_, event_queue_); + std::swap(execution_event_queue_, event_queue_); push_lock.unlock(); - this->consume_all_events(local_event_queue_); + this->consume_all_events(execution_event_queue_); execution_lock.unlock(); timers_manager_->execute_ready_timers(); @@ -154,18 +154,18 @@ EventsExecutor::spin_all(std::chrono::nanoseconds max_duration) while (rclcpp::ok(context_) && spinning.load() && max_duration_not_elapsed()) { std::unique_lock push_lock(push_mutex_); std::unique_lock execution_lock(execution_mutex_); - std::swap(local_event_queue_, event_queue_); + std::swap(execution_event_queue_, event_queue_); push_lock.unlock(); bool ready_timer = timers_manager_->get_head_timeout() < 0ns; - bool has_events = !local_event_queue_.empty(); + bool has_events = !execution_event_queue_.empty(); if (!ready_timer && !has_events) { // Exit as there is no more work to do break; } // Execute all ready work - this->consume_all_events(local_event_queue_); + this->consume_all_events(execution_event_queue_); execution_lock.unlock(); timers_manager_->execute_ready_timers(); @@ -189,7 +189,7 @@ EventsExecutor::spin_once_impl(std::chrono::nanoseconds timeout) // When condition variable is notified, check this predicate to proceed auto has_event_predicate = [this]() {return !event_queue_.empty();}; - ExecutorEvent event; + rmw_listener_event_t event; bool has_event = false; { @@ -255,7 +255,7 @@ void EventsExecutor::consume_all_events(EventQueue & event_queue) { while (!event_queue.empty()) { - ExecutorEvent event = event_queue.front(); + rmw_listener_event_t event = event_queue.front(); event_queue.pop_front(); this->execute_event(event); @@ -263,7 +263,7 @@ EventsExecutor::consume_all_events(EventQueue & event_queue) } void -EventsExecutor::execute_event(const ExecutorEvent & event) +EventsExecutor::execute_event(const rmw_listener_event_t & event) { switch (event.type) { case SUBSCRIPTION_EVENT: diff --git a/rclcpp/src/rclcpp/executors/events_executor_entities_collector.cpp b/rclcpp/src/rclcpp/executors/events_executor_entities_collector.cpp index d7bef87097..1b214b27d8 100644 --- a/rclcpp/src/rclcpp/executors/events_executor_entities_collector.cpp +++ b/rclcpp/src/rclcpp/executors/events_executor_entities_collector.cpp @@ -484,7 +484,7 @@ void EventsExecutorEntitiesCollector::set_guard_condition_callback( const rcl_guard_condition_t * guard_condition) { - rcl_ret_t ret = rcl_guard_condition_set_events_executor_callback( + rcl_ret_t ret = rcl_guard_condition_set_listener_callback( associated_executor_, &EventsExecutor::push_event, this, @@ -500,7 +500,7 @@ void EventsExecutorEntitiesCollector::unset_guard_condition_callback( const rcl_guard_condition_t * guard_condition) { - rcl_ret_t ret = rcl_guard_condition_set_events_executor_callback( + rcl_ret_t ret = rcl_guard_condition_set_listener_callback( nullptr, nullptr, nullptr, diff --git a/rclcpp/src/rclcpp/qos_event.cpp b/rclcpp/src/rclcpp/qos_event.cpp index 910c6cb7ff..4e14f1bc13 100644 --- a/rclcpp/src/rclcpp/qos_event.cpp +++ b/rclcpp/src/rclcpp/qos_event.cpp @@ -75,9 +75,9 @@ QOSEventHandlerBase::is_ready(rcl_wait_set_t * wait_set) void QOSEventHandlerBase::set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const + rmw_listener_cb_t executor_callback) const { - rcl_ret_t ret = rcl_event_set_events_executor_callback( + rcl_ret_t ret = rcl_event_set_listener_callback( executor, executor_callback, this, diff --git a/rclcpp/src/rclcpp/service.cpp b/rclcpp/src/rclcpp/service.cpp index ca1e2e4db3..f4e4092962 100644 --- a/rclcpp/src/rclcpp/service.cpp +++ b/rclcpp/src/rclcpp/service.cpp @@ -92,9 +92,9 @@ ServiceBase::exchange_in_use_by_wait_set_state(bool in_use_state) void ServiceBase::set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const + rmw_listener_cb_t executor_callback) const { - rcl_ret_t ret = rcl_service_set_events_executor_callback( + rcl_ret_t ret = rcl_service_set_listener_callback( executor, executor_callback, this, diff --git a/rclcpp/src/rclcpp/subscription_base.cpp b/rclcpp/src/rclcpp/subscription_base.cpp index 099f376618..81b6c91646 100644 --- a/rclcpp/src/rclcpp/subscription_base.cpp +++ b/rclcpp/src/rclcpp/subscription_base.cpp @@ -296,9 +296,9 @@ SubscriptionBase::exchange_in_use_by_wait_set_state( void SubscriptionBase::set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const + rmw_listener_cb_t executor_callback) const { - rcl_ret_t ret = rcl_subscription_set_events_executor_callback( + rcl_ret_t ret = rcl_subscription_set_listener_callback( executor, executor_callback, this, diff --git a/rclcpp/src/rclcpp/subscription_intra_process_base.cpp b/rclcpp/src/rclcpp/subscription_intra_process_base.cpp index a3053b8e6d..4a2a4ccc3d 100644 --- a/rclcpp/src/rclcpp/subscription_intra_process_base.cpp +++ b/rclcpp/src/rclcpp/subscription_intra_process_base.cpp @@ -47,9 +47,9 @@ SubscriptionIntraProcessBase::get_actual_qos() const void SubscriptionIntraProcessBase::set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const + rmw_listener_cb_t executor_callback) const { - rcl_ret_t ret = rcl_guard_condition_set_events_executor_callback( + rcl_ret_t ret = rcl_guard_condition_set_listener_callback( executor, executor_callback, this, diff --git a/rclcpp/src/rclcpp/waitable.cpp b/rclcpp/src/rclcpp/waitable.cpp index 6f730f13c6..1df8e2090f 100644 --- a/rclcpp/src/rclcpp/waitable.cpp +++ b/rclcpp/src/rclcpp/waitable.cpp @@ -63,7 +63,7 @@ Waitable::exchange_in_use_by_wait_set_state(bool in_use_state) void Waitable::set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const + rmw_listener_cb_t executor_callback) const { (void)executor; (void)executor_callback; diff --git a/rclcpp/test/rclcpp/executors/test_events_executor.cpp b/rclcpp/test/rclcpp/executors/test_events_executor.cpp index 93258e3d83..8fad5b40b0 100644 --- a/rclcpp/test/rclcpp/executors/test_events_executor.cpp +++ b/rclcpp/test/rclcpp/executors/test_events_executor.cpp @@ -54,7 +54,7 @@ TEST_F(TestEventsExecutor, notify_waitable) { auto mock = mocking_utils::patch_and_return( - "lib:rclcpp", rcl_guard_condition_set_events_executor_callback, RCL_RET_ERROR); + "lib:rclcpp", rcl_guard_condition_set_listener_callback, RCL_RET_ERROR); EXPECT_THROW(std::make_shared(), std::runtime_error); } } diff --git a/rclcpp/test/rclcpp/executors/test_events_executor_entities_collector.cpp b/rclcpp/test/rclcpp/executors/test_events_executor_entities_collector.cpp index 47f0cc017d..1860ffd2c1 100644 --- a/rclcpp/test/rclcpp/executors/test_events_executor_entities_collector.cpp +++ b/rclcpp/test/rclcpp/executors/test_events_executor_entities_collector.cpp @@ -165,7 +165,7 @@ TEST_F(TestEventsExecutorEntitiesCollector, test_fancy_name) { auto mock = mocking_utils::patch_and_return( - "lib:rclcpp", rcl_guard_condition_set_events_executor_callback, RCL_RET_ERROR); + "lib:rclcpp", rcl_guard_condition_set_listener_callback, RCL_RET_ERROR); EXPECT_THROW( entities_collector_->add_node(node2->get_node_base_interface()), diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index 355e8f60f7..f6a66768c7 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -467,9 +467,9 @@ class TestWaitable : public rclcpp::Waitable void set_events_executor_callback( const rclcpp::executors::EventsExecutor * executor, - EventsExecutorCallback executor_callback) const override + rmw_listener_cb_t executor_callback) const override { - rcl_ret_t ret = rcl_guard_condition_set_events_executor_callback( + rcl_ret_t ret = rcl_guard_condition_set_listener_callback( executor, executor_callback, this,