Class StaticSingleThreadedExecutor
Defined in File static_single_threaded_executor.hpp
Inheritance Relationships
Base Type
public rclcpp::Executor
(Class Executor)
Class Documentation
-
class StaticSingleThreadedExecutor : public rclcpp::Executor
Static executor implementation.
This executor is a static version of the original single threaded executor. It contains some performance optimization to avoid unnecessary reconstructions of 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. This executor is deprecated because these performance improvements have now been applied to all other executors. This executor is also considered unstable due to known bugs. See the unit-tests that are only applied to
StandardExecutors
for information on the known limitations.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 destructor.
-
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 }
Protected Functions
-
bool execute_ready_executables(const rclcpp::executors::ExecutorEntitiesCollection &collection, rclcpp::WaitResult<rclcpp::WaitSet> &wait_result, bool spin_once)
Executes ready executables from wait set.
- Parameters:
collection – entities to evaluate for ready executables.
wait_result – result to check for ready executables.
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
-
std::optional<rclcpp::WaitResult<rclcpp::WaitSet>> collect_and_wait(std::chrono::nanoseconds timeout)
-
explicit StaticSingleThreadedExecutor(const rclcpp::ExecutorOptions &options = rclcpp::ExecutorOptions())