Class EventsExecutor

Inheritance Relationships

Base Type

Class Documentation

class EventsExecutor : public rclcpp::Executor

Events executor implementation.

This executor uses an events queue and a timers manager to execute entities from its associated nodes and callback groups. ROS 2 entities allow to set callback functions that are invoked when the entity is triggered or has work to do. The events-executor sets these callbacks such that they push an event into its queue.

This executor tries to reduce as much as possible the amount of maintenance operations. This allows to use customized EventsQueue classes to achieve different goals such as very low CPU usage, bounded memory requirement, determinism, etc.

The executor uses a weak ownership model and it locks entities only while executing their related events.

To run this executor: rclcpp::experimental::executors::EventsExecutor executor; executor.add_node(node); executor.spin(); executor.remove_node(node);

Public Functions

explicit EventsExecutor(rclcpp::experimental::executors::EventsQueue::UniquePtr events_queue = std::make_unique<rclcpp::experimental::executors::SimpleEventsQueue>(), bool execute_timers_separate_thread = false, const rclcpp::ExecutorOptions &options = rclcpp::ExecutorOptions())

Default constructor. See the default constructor for Executor.

Parameters:
  • events_queue[in] The queue used to store events.

  • execute_timers_separate_thread[in] If true, timers are executed in a separate thread. If false, timers are executed in the same thread as all other entities.

  • options[in] Options used to configure the executor.

virtual ~EventsExecutor()

Default destructor.

virtual void spin() override

Events executor implementation of spin.

This function will block until work comes in, execute it, and keep blocking. It will only be interrupted by a CTRL-C (managed by the global signal handler).

Throws:

std::runtime_error – when spin() called while already spinning

virtual void spin_some(std::chrono::nanoseconds max_duration = std::chrono::nanoseconds(0)) override

Events executor implementation of spin some.

This non-blocking function will execute the timers and events that were ready when this API was called, until timeout or no more work available. New ready-timers/events arrived while executing work, won’t be taken into account here.

Example: while(condition) { spin_some(); sleep(); // User should have some sync work or // sleep to avoid a 100% CPU usage }

virtual void spin_all(std::chrono::nanoseconds max_duration) override

Events executor implementation of spin all.

This non-blocking function will execute timers and events until timeout or no more work available. If new ready-timers/events arrive while executing work available, they will be executed as long as the timeout hasn’t expired.

Example: while(condition) { spin_all(); sleep(); // User should have some sync work or // sleep to avoid a 100% CPU usage }

virtual void add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true) override

Add a node to the executor.

virtual void add_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify = true) override

Convenience function which takes Node and forwards NodeBaseInterface.

See also

rclcpp::EventsExecutor::add_node

virtual void remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true) override

Remove a node from the executor.

virtual void remove_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify = true) override

Convenience function which takes Node and forwards NodeBaseInterface.

virtual void add_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true) override

Add a callback group to an executor.

virtual void remove_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr, bool notify = true) override

Remove callback group from the executor.

virtual std::vector<rclcpp::CallbackGroup::WeakPtr> get_all_callback_groups() override

Get callback groups that belong to executor.

virtual std::vector<rclcpp::CallbackGroup::WeakPtr> get_manually_added_callback_groups() override

Get callback groups that belong to executor.

virtual std::vector<rclcpp::CallbackGroup::WeakPtr> get_automatically_added_callback_groups_from_nodes() override

Get callback groups that belong to executor.

Protected Functions

virtual void spin_once_impl(std::chrono::nanoseconds timeout) override

Internal implementation of spin_once.

void spin_some_impl(std::chrono::nanoseconds max_duration, bool exhaustive)

Internal implementation of spin_some.