Class StaticSingleThreadedExecutor

Inheritance Relationships

Base Type

Class Documentation

class StaticSingleThreadedExecutor : public rclcpp::Executor

Static executor implementation.

This executor is a static version of the original single threaded executor. It’s static because it doesn’t reconstruct the executable list for every iteration. All nodes, callbackgroups, timers, subscriptions etc. are created before spin() is called, and modified only when an entity is added/removed to/from a node.

To run this executor instead of SingleThreadedExecutor replace: rclcpp::executors::SingleThreadedExecutor exec; by rclcpp::executors::StaticSingleThreadedExecutor exec; in your source code and spin node(s) in the following way: exec.add_node(node); exec.spin(); exec.remove_node(node);

Public Functions

explicit StaticSingleThreadedExecutor(const rclcpp::ExecutorOptions &options = rclcpp::ExecutorOptions())

Default constructor. See the default constructor for Executor.

virtual ~StaticSingleThreadedExecutor()

Default destrcutor.

virtual void spin() override

Static 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

Static executor implementation of spin some.

This non-blocking function will execute entities that were ready when this API was called, until timeout or no more work available. Entities that got ready 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

Static executor implementation of spin all.

This non-blocking function will execute entities until timeout (must be >= 0) or no more work available. If timeout is 0, potentially it blocks forever until no more work is available. If new entities get ready 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_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 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::StaticSingleThreadedExecutor::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 std::vector<rclcpp::CallbackGroup::WeakPtr> get_all_callback_groups() override

Get callback groups that belong to executor.

This function returns a vector of weak pointers that point to callback groups that were associated with the executor. The callback groups associated with this executor may have been added with add_callback_group, or added when a node was added to the executor with add_node, or automatically added when it created by a node already associated with this executor and the automatically_add_to_executor_with_node parameter was true.

Returns:

a vector of weak pointers that point to callback groups that are associated with the 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

bool execute_ready_executables(bool spin_once = false)

Executes ready executables from wait set.

Parameters:

spin_once – if true executes only the first ready executable.

Returns:

true if any executable was ready.

void spin_some_impl(std::chrono::nanoseconds max_duration, bool exhaustive)
virtual void spin_once_impl(std::chrono::nanoseconds timeout) override