Skip to content

Commit

Permalink
Merge pull request ros2#3 from mauropasse/mauro-irobot/add-events-exe…
Browse files Browse the repository at this point in the history
…cutor

Rename stuff
  • Loading branch information
iRobot ROS authored Oct 12, 2020
2 parents 7a5bd1f + 6454eb8 commit 465e2ca
Show file tree
Hide file tree
Showing 15 changed files with 56 additions and 56 deletions.
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,7 @@ class ClientBase

RCLCPP_PUBLIC
void
set_callback(const void * executor_context, Event_callback executor_callback) const;
set_events_executor_callback(const void * executor_context, ExecutorEventCallback executor_callback) const;

protected:
RCLCPP_DISABLE_COPY(ClientBase)
Expand Down
10 changes: 5 additions & 5 deletions rclcpp/include/rclcpp/executors/events_executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#include <memory>
#include <queue>

#include "rcutils/event_types.h"
#include "rcutils/executor_event_types.h"

#include "rclcpp/executor.hpp"
#include "rclcpp/executors/events_executor_entities_collector.hpp"
Expand Down Expand Up @@ -132,18 +132,18 @@ class EventsExecutor : public rclcpp::Executor
/// Extract and execute events from the queue until it is empty
RCLCPP_PUBLIC
void
consume_all_events(std::queue<EventQ> &queue);
consume_all_events(std::queue<ExecutorEvent> &queue);

// Execute a single event
RCLCPP_PUBLIC
void
execute_event(const EventQ &event);
execute_event(const ExecutorEvent &event);

// 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, EventQ event)
push_event(const void * executor_ptr, ExecutorEvent event)
{
// Cast executor_ptr to this (need to remove constness)
auto this_executor = const_cast<executors::EventsExecutor*>(
Expand All @@ -160,7 +160,7 @@ class EventsExecutor : public rclcpp::Executor
}

// Event queue members
std::queue<EventQ> event_queue_;
std::queue<ExecutorEvent> event_queue_;
std::mutex event_queue_mutex_;
std::condition_variable event_queue_cv_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class EventsExecutorEntitiesCollector final : public rclcpp::Waitable
void
init(
void * executor_context,
Event_callback executor_callback,
ExecutorEventCallback executor_callback,
TimerFn push_timer,
TimerFn clear_timer,
ClearTimersFn clear_all_timers);
Expand Down Expand Up @@ -91,7 +91,7 @@ class EventsExecutorEntitiesCollector final : public rclcpp::Waitable
void * executor_context_ = nullptr;

/// Events callback
Event_callback executor_callback_ = nullptr;
ExecutorEventCallback executor_callback_ = nullptr;

/// Function pointers to push and clear timers from the timers heap
TimerFn push_timer_ = nullptr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,9 @@ class SubscriptionIntraProcessBase : public rclcpp::Waitable

RCLCPP_PUBLIC
void
set_guard_condition_callback(
set_events_executor_callback(
void * executor_context,
Event_callback executor_callback) const override;
ExecutorEventCallback executor_callback) const override;

protected:
std::recursive_mutex reentrant_mutex_;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ class ServiceBase

RCLCPP_PUBLIC
void
set_callback(const void * executor_context, Event_callback executor_callback) const;
set_events_executor_callback(const void * executor_context, ExecutorEventCallback executor_callback) const;

protected:
RCLCPP_DISABLE_COPY(ServiceBase)
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/subscription_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,7 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>

RCLCPP_PUBLIC
void
set_callback(const void * executor_context, Event_callback executor_callback) const;
set_events_executor_callback(const void * executor_context, ExecutorEventCallback executor_callback) const;

protected:
template<typename EventCallbackT>
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/waitable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -168,9 +168,9 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
set_guard_condition_callback(
set_events_executor_callback(
void * executor_context,
Event_callback executor_callback) const;
ExecutorEventCallback executor_callback) const;

private:
std::atomic<bool> in_use_by_wait_set_{false};
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/src/rclcpp/client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,11 +200,11 @@ ClientBase::exchange_in_use_by_wait_set_state(bool in_use_state)
}

void
ClientBase::set_callback(
ClientBase::set_events_executor_callback(
const void * executor_context,
Event_callback executor_callback) const
ExecutorEventCallback executor_callback) const
{
rcl_ret_t ret = rcl_client_set_callback(
rcl_ret_t ret = rcl_client_set_events_executor_callback(
executor_context,
executor_callback,
this,
Expand Down
30 changes: 15 additions & 15 deletions rclcpp/src/rclcpp/executors/events_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ EventsExecutor::EventsExecutor(
rcl_ret_t ret;

// Set the global ctrl-c guard condition callback
ret = rcl_guard_condition_set_callback(
ret = rcl_guard_condition_set_events_executor_callback(
this,
&EventsExecutor::push_event,
entities_collector_.get(),
Expand All @@ -58,7 +58,7 @@ EventsExecutor::EventsExecutor(
}

// Set the executor interrupt guard condition callback
ret = rcl_guard_condition_set_callback(
ret = rcl_guard_condition_set_events_executor_callback(
this,
&EventsExecutor::push_event,
entities_collector_.get(),
Expand All @@ -84,7 +84,7 @@ EventsExecutor::spin()
auto predicate = [this]() { return !event_queue_.empty(); };

// Local event queue
std::queue<EventQ> local_event_queue;
std::queue<ExecutorEvent> local_event_queue;

timers_manager_->start();

Expand Down Expand Up @@ -124,7 +124,7 @@ EventsExecutor::spin_some(std::chrono::nanoseconds max_duration)
max_duration = next_timer_timeout;
}

std::queue<EventQ> local_event_queue;
std::queue<ExecutorEvent> local_event_queue;

{
// Wait until timeout or event
Expand All @@ -149,7 +149,7 @@ EventsExecutor::spin_all(std::chrono::nanoseconds max_duration)
}
RCLCPP_SCOPE_EXIT(this->spinning.store(false););

std::queue<EventQ> local_event_queue;
std::queue<ExecutorEvent> local_event_queue;

auto start = std::chrono::steady_clock::now();
auto max_duration_not_elapsed = [max_duration, start]() {
Expand Down Expand Up @@ -204,7 +204,7 @@ EventsExecutor::spin_once_impl(std::chrono::nanoseconds timeout)
timeout = next_timer_timeout;
}

EventQ event;
ExecutorEvent event;
bool has_event = false;

{
Expand Down Expand Up @@ -256,36 +256,36 @@ EventsExecutor::add_node(
group->find_subscription_ptrs_if(
[this](const rclcpp::SubscriptionBase::SharedPtr & subscription) {
if (subscription) {
subscription->set_callback(this, &EventsExecutor::push_event);
subscription->set_events_executor_callback(this, &EventsExecutor::push_event);
}
return false;
});
group->find_service_ptrs_if(
[this](const rclcpp::ServiceBase::SharedPtr & service) {
if (service) {
service->set_callback(this, &EventsExecutor::push_event);
service->set_events_executor_callback(this, &EventsExecutor::push_event);
}
return false;
});
group->find_client_ptrs_if(
[this](const rclcpp::ClientBase::SharedPtr & client) {
if (client) {
client->set_callback(this, &EventsExecutor::push_event);
client->set_events_executor_callback(this, &EventsExecutor::push_event);
}
return false;
});
group->find_waitable_ptrs_if(
[this](const rclcpp::Waitable::SharedPtr & waitable) {
if (waitable) {
waitable->set_guard_condition_callback(this, &EventsExecutor::push_event);
waitable->set_events_executor_callback(this, &EventsExecutor::push_event);
}
return false;
});
}

// Set node's guard condition callback, so if new entities are added while
// spinning we can set their callback.
rcl_ret_t ret = rcl_guard_condition_set_callback(
rcl_ret_t ret = rcl_guard_condition_set_events_executor_callback(
this,
&EventsExecutor::push_event,
entities_collector_.get(),
Expand Down Expand Up @@ -321,18 +321,18 @@ EventsExecutor::remove_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify)
}

void
EventsExecutor::consume_all_events(std::queue<EventQ> &event_queue)
EventsExecutor::consume_all_events(std::queue<ExecutorEvent> &event_queue)
{
while (!event_queue.empty()) {
EventQ event = event_queue.front();
ExecutorEvent event = event_queue.front();
event_queue.pop();

this->execute_event(event);
}
}

void
EventsExecutor::execute_event(const EventQ &event)
EventsExecutor::execute_event(const ExecutorEvent &event)
{
switch(event.type) {
case SUBSCRIPTION_EVENT:
Expand All @@ -359,7 +359,7 @@ EventsExecutor::execute_event(const EventQ &event)
break;
}

case GUARD_CONDITION_EVENT:
case WAITABLE_EVENT:
{
auto waitable = const_cast<rclcpp::Waitable*>(
static_cast<const rclcpp::Waitable*>(event.entity));
Expand Down
20 changes: 10 additions & 10 deletions rclcpp/src/rclcpp/executors/events_executor_entities_collector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ EventsExecutorEntitiesCollector::~EventsExecutorEntitiesCollector()
void
EventsExecutorEntitiesCollector::init(
void * executor_context,
Event_callback executor_callback,
ExecutorEventCallback executor_callback,
TimerFn push_timer,
TimerFn clear_timer,
ClearTimersFn clear_all_timers)
Expand Down Expand Up @@ -85,7 +85,7 @@ EventsExecutorEntitiesCollector::remove_node(
bool matched = (node_it->lock() == node_ptr);
if (matched) {
// Node found: unset its entities callbacks
rcl_ret_t ret = rcl_guard_condition_set_callback(
rcl_ret_t ret = rcl_guard_condition_set_events_executor_callback(
nullptr, nullptr, nullptr,
node_ptr->get_notify_guard_condition(),
false);
Expand All @@ -110,28 +110,28 @@ EventsExecutorEntitiesCollector::remove_node(
group->find_subscription_ptrs_if(
[this](const rclcpp::SubscriptionBase::SharedPtr & subscription) {
if (subscription) {
subscription->set_callback(nullptr, nullptr);
subscription->set_events_executor_callback(nullptr, nullptr);
}
return false;
});
group->find_service_ptrs_if(
[this](const rclcpp::ServiceBase::SharedPtr & service) {
if (service) {
service->set_callback(nullptr, nullptr);
service->set_events_executor_callback(nullptr, nullptr);
}
return false;
});
group->find_client_ptrs_if(
[this](const rclcpp::ClientBase::SharedPtr & client) {
if (client) {
client->set_callback(nullptr, nullptr);
client->set_events_executor_callback(nullptr, nullptr);
}
return false;
});
group->find_waitable_ptrs_if(
[this](const rclcpp::Waitable::SharedPtr & waitable) {
if (waitable) {
waitable->set_guard_condition_callback(nullptr, nullptr);
waitable->set_events_executor_callback(nullptr, nullptr);
}
return false;
});
Expand Down Expand Up @@ -169,28 +169,28 @@ EventsExecutorEntitiesCollector::set_entities_callbacks()
group->find_subscription_ptrs_if(
[this](const rclcpp::SubscriptionBase::SharedPtr & subscription) {
if (subscription) {
subscription->set_callback(executor_context_, executor_callback_);
subscription->set_events_executor_callback(executor_context_, executor_callback_);
}
return false;
});
group->find_service_ptrs_if(
[this](const rclcpp::ServiceBase::SharedPtr & service) {
if (service) {
service->set_callback(executor_context_, executor_callback_);
service->set_events_executor_callback(executor_context_, executor_callback_);
}
return false;
});
group->find_client_ptrs_if(
[this](const rclcpp::ClientBase::SharedPtr & client) {
if (client) {
client->set_callback(executor_context_, executor_callback_);
client->set_events_executor_callback(executor_context_, executor_callback_);
}
return false;
});
group->find_waitable_ptrs_if(
[this](const rclcpp::Waitable::SharedPtr & waitable) {
if (waitable) {
waitable->set_guard_condition_callback(executor_context_, executor_callback_);
waitable->set_events_executor_callback(executor_context_, executor_callback_);
}
return false;
});
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/src/rclcpp/service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,11 +86,11 @@ ServiceBase::exchange_in_use_by_wait_set_state(bool in_use_state)
}

void
ServiceBase::set_callback(
ServiceBase::set_events_executor_callback(
const void * executor_context,
Event_callback executor_callback) const
ExecutorEventCallback executor_callback) const
{
rcl_ret_t ret = rcl_service_set_callback(
rcl_ret_t ret = rcl_service_set_events_executor_callback(
executor_context,
executor_callback,
this,
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/src/rclcpp/subscription_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -290,11 +290,11 @@ SubscriptionBase::exchange_in_use_by_wait_set_state(
}

void
SubscriptionBase::set_callback(
SubscriptionBase::set_events_executor_callback(
const void * executor_context,
Event_callback executor_callback) const
ExecutorEventCallback executor_callback) const
{
rcl_ret_t ret = rcl_subscription_set_callback(
rcl_ret_t ret = rcl_subscription_set_events_executor_callback(
executor_context,
executor_callback,
this,
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/src/rclcpp/subscription_intra_process_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,11 @@ SubscriptionIntraProcessBase::get_actual_qos() const
}

void
SubscriptionIntraProcessBase::set_guard_condition_callback(
SubscriptionIntraProcessBase::set_events_executor_callback(
void * executor_context,
Event_callback executor_callback) const
ExecutorEventCallback executor_callback) const
{
rcl_ret_t ret = rcl_guard_condition_set_callback(
rcl_ret_t ret = rcl_guard_condition_set_events_executor_callback(
executor_context,
executor_callback,
this,
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/src/rclcpp/waitable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,12 +61,12 @@ Waitable::exchange_in_use_by_wait_set_state(bool in_use_state)
}

void
Waitable::set_guard_condition_callback(
Waitable::set_events_executor_callback(
void * executor_context,
Event_callback executor_callback) const
ExecutorEventCallback executor_callback) const
{
(void)executor_context;
(void)executor_callback;

throw std::runtime_error("Custom waitables should override set_guard_condition_callback() to use events executor");
throw std::runtime_error("Custom waitables should override set_events_executor_callback() to use events executor");
}
Loading

0 comments on commit 465e2ca

Please sign in to comment.