rclcpp  master
C++ ROS Client Library API
Public Member Functions | Protected Types | Protected Member Functions | Static Protected Member Functions | Protected Attributes | List of all members
rclcpp::Executor Class Referenceabstract

Coordinate the order and timing of available communication tasks. More...

#include <executor.hpp>

Inheritance diagram for rclcpp::Executor:
Inheritance graph
[legend]
Collaboration diagram for rclcpp::Executor:
Collaboration graph
[legend]

Public Member Functions

 Executor (const rclcpp::ExecutorOptions &options=rclcpp::ExecutorOptions())
 Default constructor. More...
 
virtual ~Executor ()
 Default destructor. More...
 
virtual void spin ()=0
 Do work periodically as it becomes available to us. Blocking call, may block indefinitely. More...
 
virtual void add_callback_group (rclcpp::CallbackGroup::SharedPtr group_ptr, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true)
 Add a callback group to an executor. More...
 
virtual std::vector< rclcpp::CallbackGroup::WeakPtr > get_all_callback_groups ()
 Get callback groups that belong to executor. More...
 
virtual std::vector< rclcpp::CallbackGroup::WeakPtr > get_manually_added_callback_groups ()
 Get callback groups that belong to executor. More...
 
virtual std::vector< rclcpp::CallbackGroup::WeakPtr > get_automatically_added_callback_groups_from_nodes ()
 Get callback groups that belong to executor. More...
 
virtual void remove_callback_group (rclcpp::CallbackGroup::SharedPtr group_ptr, bool notify=true)
 Remove a callback group from the executor. More...
 
virtual void add_node (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true)
 Add a node to the executor. More...
 
virtual void add_node (std::shared_ptr< rclcpp::Node > node_ptr, bool notify=true)
 Convenience function which takes Node and forwards NodeBaseInterface. More...
 
virtual void remove_node (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true)
 Remove a node from the executor. More...
 
virtual void remove_node (std::shared_ptr< rclcpp::Node > node_ptr, bool notify=true)
 Convenience function which takes Node and forwards NodeBaseInterface. More...
 
template<typename RepT = int64_t, typename T = std::milli>
void spin_node_once (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, std::chrono::duration< RepT, T > timeout=std::chrono::duration< RepT, T >(-1))
 Add a node to executor, execute the next available unit of work, and remove the node. More...
 
template<typename NodeT = rclcpp::Node, typename RepT = int64_t, typename T = std::milli>
void spin_node_once (std::shared_ptr< NodeT > node, std::chrono::duration< RepT, T > timeout=std::chrono::duration< RepT, T >(-1))
 Convenience function which takes Node and forwards NodeBaseInterface. More...
 
void spin_node_some (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node)
 Add a node, complete all immediately available work, and remove the node. More...
 
void spin_node_some (std::shared_ptr< rclcpp::Node > node)
 Convenience function which takes Node and forwards NodeBaseInterface. More...
 
virtual void spin_some (std::chrono::nanoseconds max_duration=std::chrono::nanoseconds(0))
 Collect work once and execute all available work, optionally within a duration. More...
 
virtual void spin_all (std::chrono::nanoseconds max_duration)
 Collect and execute work repeatedly within a duration or until no more work is available. More...
 
virtual void spin_once (std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 
template<typename FutureT , typename TimeRepT = int64_t, typename TimeT = std::milli>
FutureReturnCode spin_until_future_complete (const FutureT &future, std::chrono::duration< TimeRepT, TimeT > timeout=std::chrono::duration< TimeRepT, TimeT >(-1))
 Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted. More...
 
void cancel ()
 Cancel any running spin* function, causing it to return. More...
 
void set_memory_strategy (memory_strategy::MemoryStrategy::SharedPtr memory_strategy)
 Support dynamic switching of the memory strategy. More...
 

Protected Types

typedef std::map< rclcpp::node_interfaces::NodeBaseInterface::WeakPtr, const rcl_guard_condition_t *, std::owner_less< rclcpp::node_interfaces::NodeBaseInterface::WeakPtr > > WeakNodesToGuardConditionsMap
 

Protected Member Functions

void spin_node_once_nanoseconds (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, std::chrono::nanoseconds timeout)
 
void spin_some_impl (std::chrono::nanoseconds max_duration, bool exhaustive)
 
void execute_any_executable (AnyExecutable &any_exec)
 Find the next available executable and do the work associated with it. More...
 
void wait_for_work (std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_by_group (const WeakCallbackGroupsToNodesMap &weak_groups_to_nodes, rclcpp::CallbackGroup::SharedPtr group)
 
bool has_node (const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, const WeakCallbackGroupsToNodesMap &weak_groups_to_nodes) const
 Return true if the node has been added to this executor. More...
 
rclcpp::CallbackGroup::SharedPtr get_group_by_timer (rclcpp::TimerBase::SharedPtr timer)
 
virtual void add_callback_group_to_map (rclcpp::CallbackGroup::SharedPtr group_ptr, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, WeakCallbackGroupsToNodesMap &weak_groups_to_nodes, bool notify=true) RCPPUTILS_TSA_REQUIRES(mutex_)
 Add a callback group to an executor. More...
 
virtual void remove_callback_group_from_map (rclcpp::CallbackGroup::SharedPtr group_ptr, WeakCallbackGroupsToNodesMap &weak_groups_to_nodes, bool notify=true) RCPPUTILS_TSA_REQUIRES(mutex_)
 Remove a callback group from the executor. More...
 
bool get_next_ready_executable (AnyExecutable &any_executable)
 
bool get_next_ready_executable_from_map (AnyExecutable &any_executable, const WeakCallbackGroupsToNodesMap &weak_groups_to_nodes)
 
bool get_next_executable (AnyExecutable &any_executable, std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 
virtual void add_callback_groups_from_nodes_associated_to_executor () RCPPUTILS_TSA_REQUIRES(mutex_)
 Add all callback groups that can be automatically added from associated nodes. More...
 
memory_strategy::MemoryStrategy::SharedPtr memory_strategy_ RCPPUTILS_TSA_PT_GUARDED_BY (mutex_)
 The memory strategy: an interface for handling user-defined memory allocation strategies. More...
 
virtual void spin_once_impl (std::chrono::nanoseconds timeout)
 
WeakNodesToGuardConditionsMap weak_nodes_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY (mutex_)
 maps nodes to guard conditions More...
 
WeakCallbackGroupsToNodesMap weak_groups_associated_with_executor_to_nodes_ RCPPUTILS_TSA_GUARDED_BY (mutex_)
 maps callback groups associated to nodes More...
 
WeakCallbackGroupsToNodesMap weak_groups_to_nodes_associated_with_executor_ RCPPUTILS_TSA_GUARDED_BY (mutex_)
 maps callback groups to nodes associated with executor More...
 
WeakCallbackGroupsToNodesMap weak_groups_to_nodes_ RCPPUTILS_TSA_GUARDED_BY (mutex_)
 maps all callback groups to nodes More...
 
std::list< rclcpp::node_interfaces::NodeBaseInterface::WeakPtr > weak_nodes_ RCPPUTILS_TSA_GUARDED_BY (mutex_)
 nodes that are associated with the executor More...
 

Static Protected Member Functions

static void execute_subscription (rclcpp::SubscriptionBase::SharedPtr subscription)
 
static void execute_timer (rclcpp::TimerBase::SharedPtr timer)
 
static void execute_service (rclcpp::ServiceBase::SharedPtr service)
 
static void execute_client (rclcpp::ClientBase::SharedPtr client)
 

Protected Attributes

std::atomic_bool spinning
 Spinning state, used to prevent multi threaded calls to spin and to cancel blocking spins. More...
 
rcl_guard_condition_t interrupt_guard_condition_ = rcl_get_zero_initialized_guard_condition()
 Guard condition for signaling the rmw layer to wake up for special events. More...
 
std::shared_ptr< rclcpp::GuardConditionshutdown_guard_condition_
 
rcl_wait_set_t wait_set_ = rcl_get_zero_initialized_wait_set()
 Wait set for managing entities that the rmw layer waits on. More...
 
std::mutex mutex_
 
std::shared_ptr< rclcpp::Contextcontext_
 The context associated with this executor. More...
 
rclcpp::OnShutdownCallbackHandle shutdown_callback_handle_
 shutdown callback handle registered to Context More...
 

Detailed Description

Coordinate the order and timing of available communication tasks.

Executor provides spin functions (including spin_node_once and spin_some). It coordinates the nodes and callback groups by looking for available work and completing it, based on the threading or concurrency scheme provided by the subclass implementation. An example of available work is executing a subscription callback, or a timer callback. The executor structure allows for a decoupling of the communication graph and the execution model. See SingleThreadedExecutor and MultiThreadedExecutor for examples of execution paradigms.

Member Typedef Documentation

◆ WeakNodesToGuardConditionsMap

typedef std::map<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr, const rcl_guard_condition_t *, std::owner_less<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr> > rclcpp::Executor::WeakNodesToGuardConditionsMap
protected

Constructor & Destructor Documentation

◆ Executor()

rclcpp::Executor::Executor ( const rclcpp::ExecutorOptions options = rclcpp::ExecutorOptions())
explicit

Default constructor.

Parameters
[in]optionsOptions used to configure the executor.

◆ ~Executor()

virtual rclcpp::Executor::~Executor ( )
virtual

Default destructor.

Member Function Documentation

◆ spin()

virtual void rclcpp::Executor::spin ( )
pure virtual

Do work periodically as it becomes available to us. Blocking call, may block indefinitely.

Implemented in rclcpp::executors::StaticSingleThreadedExecutor, rclcpp::executors::MultiThreadedExecutor, and rclcpp::executors::SingleThreadedExecutor.

◆ add_callback_group()

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

Add a callback group to an executor.

An executor can have zero or more callback groups which provide work during spin functions. When an executor attempts to add a callback group, the executor checks to see if it is already associated with another executor, and if it has been, then an exception is thrown. Otherwise, the callback group is added to the executor.

Adding a callback group with this method does not associate its node with this executor in any way

Parameters
[in]group_ptra shared ptr that points to a callback group
[in]node_ptra shared pointer that points to a node base interface
[in]notifyTrue to trigger the interrupt guard condition during this function. If the executor is blocked at the rmw layer while waiting for work and it is notified that a new callback group was added, it will wake up.
Exceptions
std::runtime_errorif the callback group is associated to an executor

Reimplemented in rclcpp::executors::StaticSingleThreadedExecutor.

◆ get_all_callback_groups()

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

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

Reimplemented in rclcpp::executors::StaticSingleThreadedExecutor.

◆ get_manually_added_callback_groups()

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

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 have been added with add_callback_group.

Returns
a vector of weak pointers that point to callback groups that are associated with the executor

Reimplemented in rclcpp::executors::StaticSingleThreadedExecutor.

◆ get_automatically_added_callback_groups_from_nodes()

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

Get callback groups that belong to executor.

This function returns a vector of weak pointers that point to callback groups that were added from a node that is associated with the executor. The callback groups are added when a node is added to the executor with add_node, or automatically if they are created in the future by that node and have the automatically_add_to_executor_with_node argument set to true.

Returns
a vector of weak pointers that point to callback groups from a node associated with the executor

Reimplemented in rclcpp::executors::StaticSingleThreadedExecutor.

◆ remove_callback_group()

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

Remove a callback group from the executor.

The callback group is removed from and disassociated with the executor. If the callback group removed was the last callback group from the node that is associated with the executor, the interrupt guard condition is triggered and node's guard condition is removed from the executor.

This function only removes a callback group that was manually added with rclcpp::Executor::add_callback_group. To remove callback groups that were added from a node using rclcpp::Executor::add_node, use rclcpp::Executor::remove_node instead.

Parameters
[in]group_ptrShared pointer to the callback group to be added.
[in]notifyTrue to trigger the interrupt guard condition during this function. If the executor is blocked at the rmw layer while waiting for work and it is notified that a callback group was removed, it will wake up.
Exceptions
std::runtime_errorif node is deleted before callback group
std::runtime_errorif the callback group is not associated with the executor

Reimplemented in rclcpp::executors::StaticSingleThreadedExecutor.

◆ add_node() [1/2]

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

Add a node to the executor.

Nodes have associated callback groups, and this method adds any of those callback groups to this executor which have their automatically_add_to_executor_with_node parameter true. The node is also associated with the executor so that future callback groups which are created on the node with the automatically_add_to_executor_with_node parameter set to true are also automatically associated with this executor.

Callback groups with the automatically_add_to_executor_with_node parameter set to false must be manually added to an executor using the rclcpp::Executor::add_callback_group method.

If a node is already associated with an executor, this method throws an exception.

Parameters
[in]node_ptrShared pointer to the node to be added.
[in]notifyTrue to trigger the interrupt guard condition during this function. If the executor is blocked at the rmw layer while waiting for work and it is notified that a new node was added, it will wake up.
Exceptions
std::runtime_errorif a node is already associated to an executor

Reimplemented in rclcpp::executors::StaticSingleThreadedExecutor.

◆ add_node() [2/2]

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

Convenience function which takes Node and forwards NodeBaseInterface.

See also
rclcpp::Executor::add_node

Reimplemented in rclcpp::executors::StaticSingleThreadedExecutor.

◆ remove_node() [1/2]

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

Remove a node from the executor.

Any callback groups automatically added when this node was added with rclcpp::Executor::add_node are automatically removed, and the node is no longer associated with this executor.

This also means that future callback groups created by the given node are no longer automatically added to this executor.

Parameters
[in]node_ptrShared pointer to the node to remove.
[in]notifyTrue to trigger the interrupt guard condition and wake up the executor. This is useful if the last node was removed from the executor while the executor was blocked waiting for work in another thread, because otherwise the executor would never be notified.
Exceptions
std::runtime_errorif the node is not associated with an executor.
std::runtime_errorif the node is not associated with this executor.

Reimplemented in rclcpp::executors::StaticSingleThreadedExecutor.

◆ remove_node() [2/2]

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

Convenience function which takes Node and forwards NodeBaseInterface.

See also
rclcpp::Executor::remove_node

Reimplemented in rclcpp::executors::StaticSingleThreadedExecutor.

◆ spin_node_once() [1/2]

template<typename RepT = int64_t, typename T = std::milli>
void rclcpp::Executor::spin_node_once ( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node,
std::chrono::duration< RepT, T >  timeout = std::chrono::duration<RepT, T>(-1) 
)
inline

Add a node to executor, execute the next available unit of work, and remove the node.

Parameters
[in]nodeShared pointer to the node to add.
[in]timeoutHow long to wait for work to become available. Negative values cause spin_node_once to block indefinitely (the default behavior). A timeout of 0 causes this function to be non-blocking.

◆ spin_node_once() [2/2]

template<typename NodeT = rclcpp::Node, typename RepT = int64_t, typename T = std::milli>
void rclcpp::Executor::spin_node_once ( std::shared_ptr< NodeT >  node,
std::chrono::duration< RepT, T >  timeout = std::chrono::duration<RepT, T>(-1) 
)
inline

Convenience function which takes Node and forwards NodeBaseInterface.

◆ spin_node_some() [1/2]

void rclcpp::Executor::spin_node_some ( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node)

Add a node, complete all immediately available work, and remove the node.

Parameters
[in]nodeShared pointer to the node to add.

◆ spin_node_some() [2/2]

void rclcpp::Executor::spin_node_some ( std::shared_ptr< rclcpp::Node node)

Convenience function which takes Node and forwards NodeBaseInterface.

◆ spin_some()

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

Collect work once and execute all available work, optionally within a duration.

This function can be overridden. The default implementation is suitable for a single-threaded model of execution. Adding subscriptions, timers, services, etc. with blocking callbacks will cause this function to block (which may have unintended consequences).

Parameters
[in]max_durationThe maximum amount of time to spend executing work, or 0 for no limit. Note that spin_some() may take longer than this time as it only returns once max_duration has been exceeded.

Reimplemented in rclcpp::executors::StaticSingleThreadedExecutor.

◆ spin_all()

virtual void rclcpp::Executor::spin_all ( std::chrono::nanoseconds  max_duration)
virtual

Collect and execute work repeatedly within a duration or until no more work is available.

This function can be overridden. The default implementation is suitable for a single-threaded model of execution. Adding subscriptions, timers, services, etc. with blocking callbacks will cause this function to block (which may have unintended consequences). If the time that waitables take to be executed is longer than the period on which new waitables become ready, this method will execute work repeatedly until max_duration has elapsed.

Parameters
[in]max_durationThe maximum amount of time to spend executing work. Must be positive. Note that spin_all() may take longer than this time as it only returns once max_duration has been exceeded.

Reimplemented in rclcpp::executors::StaticSingleThreadedExecutor.

◆ spin_once()

virtual void rclcpp::Executor::spin_once ( std::chrono::nanoseconds  timeout = std::chrono::nanoseconds(-1))
virtual

◆ spin_until_future_complete()

template<typename FutureT , typename TimeRepT = int64_t, typename TimeT = std::milli>
FutureReturnCode rclcpp::Executor::spin_until_future_complete ( const FutureT &  future,
std::chrono::duration< TimeRepT, TimeT >  timeout = std::chrono::duration<TimeRepT, TimeT>(-1) 
)
inline

Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.

Parameters
[in]futureThe future to wait on. If this function returns SUCCESS, the future can be accessed without blocking (though it may still throw an exception).
[in]timeoutOptional timeout parameter, which gets passed to Executor::spin_node_once. -1 is block forever, 0 is non-blocking. If the time spent inside the blocking loop exceeds this timeout, return a TIMEOUT return code.
Returns
The return code, one of SUCCESS, INTERRUPTED, or TIMEOUT.

◆ cancel()

void rclcpp::Executor::cancel ( )

Cancel any running spin* function, causing it to return.

This function can be called asynchonously from any thread.

Exceptions
std::runtime_errorif there is an issue triggering the guard condition

◆ set_memory_strategy()

void rclcpp::Executor::set_memory_strategy ( memory_strategy::MemoryStrategy::SharedPtr  memory_strategy)

Support dynamic switching of the memory strategy.

Switching the memory strategy while the executor is spinning in another threading could have unintended consequences.

Parameters
[in]memory_strategyShared pointer to the memory strategy to set.
Exceptions
std::runtime_errorif memory_strategy is null

◆ spin_node_once_nanoseconds()

void rclcpp::Executor::spin_node_once_nanoseconds ( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node,
std::chrono::nanoseconds  timeout 
)
protected

◆ spin_some_impl()

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

◆ execute_any_executable()

void rclcpp::Executor::execute_any_executable ( AnyExecutable any_exec)
protected

Find the next available executable and do the work associated with it.

Parameters
[in]any_execUnion structure that can hold any executable type (timer, subscription, service, client).
Exceptions
std::runtime_errorif there is an issue triggering the guard condition

◆ execute_subscription()

static void rclcpp::Executor::execute_subscription ( rclcpp::SubscriptionBase::SharedPtr  subscription)
staticprotected

◆ execute_timer()

static void rclcpp::Executor::execute_timer ( rclcpp::TimerBase::SharedPtr  timer)
staticprotected

◆ execute_service()

static void rclcpp::Executor::execute_service ( rclcpp::ServiceBase::SharedPtr  service)
staticprotected

◆ execute_client()

static void rclcpp::Executor::execute_client ( rclcpp::ClientBase::SharedPtr  client)
staticprotected

◆ wait_for_work()

void rclcpp::Executor::wait_for_work ( std::chrono::nanoseconds  timeout = std::chrono::nanoseconds(-1))
protected
Exceptions
std::runtime_errorif the wait set can be cleared

◆ get_node_by_group()

rclcpp::node_interfaces::NodeBaseInterface::SharedPtr rclcpp::Executor::get_node_by_group ( const WeakCallbackGroupsToNodesMap weak_groups_to_nodes,
rclcpp::CallbackGroup::SharedPtr  group 
)
protected

◆ has_node()

bool rclcpp::Executor::has_node ( const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node_ptr,
const WeakCallbackGroupsToNodesMap weak_groups_to_nodes 
) const
protected

Return true if the node has been added to this executor.

Parameters
[in]node_ptra shared pointer that points to a node base interface
Returns
true if the node is associated with the executor, otherwise false

◆ get_group_by_timer()

rclcpp::CallbackGroup::SharedPtr rclcpp::Executor::get_group_by_timer ( rclcpp::TimerBase::SharedPtr  timer)
protected

◆ add_callback_group_to_map()

virtual void rclcpp::Executor::add_callback_group_to_map ( rclcpp::CallbackGroup::SharedPtr  group_ptr,
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node_ptr,
WeakCallbackGroupsToNodesMap weak_groups_to_nodes,
bool  notify = true 
)
protectedvirtual

Add a callback group to an executor.

See also
rclcpp::Executor::add_callback_group

◆ remove_callback_group_from_map()

virtual void rclcpp::Executor::remove_callback_group_from_map ( rclcpp::CallbackGroup::SharedPtr  group_ptr,
WeakCallbackGroupsToNodesMap weak_groups_to_nodes,
bool  notify = true 
)
protectedvirtual

Remove a callback group from the executor.

See also
rclcpp::Executor::remove_callback_group

◆ get_next_ready_executable()

bool rclcpp::Executor::get_next_ready_executable ( AnyExecutable any_executable)
protected

◆ get_next_ready_executable_from_map()

bool rclcpp::Executor::get_next_ready_executable_from_map ( AnyExecutable any_executable,
const WeakCallbackGroupsToNodesMap weak_groups_to_nodes 
)
protected

◆ get_next_executable()

bool rclcpp::Executor::get_next_executable ( AnyExecutable any_executable,
std::chrono::nanoseconds  timeout = std::chrono::nanoseconds(-1) 
)
protected

◆ add_callback_groups_from_nodes_associated_to_executor()

virtual void rclcpp::Executor::add_callback_groups_from_nodes_associated_to_executor ( )
protectedvirtual

Add all callback groups that can be automatically added from associated nodes.

The executor, before collecting entities, verifies if any callback group from nodes associated with the executor, which is not already associated to an executor, can be automatically added to this executor. This takes care of any callback group that has been added to a node but not explicitly added to the executor. It is important to note that in order for the callback groups to be automatically added to an executor through this function, the node of the callback groups needs to have been added through the add_node method.

◆ RCPPUTILS_TSA_PT_GUARDED_BY()

memory_strategy::MemoryStrategy::SharedPtr memory_strategy_ rclcpp::Executor::RCPPUTILS_TSA_PT_GUARDED_BY ( mutex_  )
protected

The memory strategy: an interface for handling user-defined memory allocation strategies.

◆ spin_once_impl()

virtual void rclcpp::Executor::spin_once_impl ( std::chrono::nanoseconds  timeout)
protectedvirtual

◆ RCPPUTILS_TSA_GUARDED_BY() [1/5]

WeakNodesToGuardConditionsMap weak_nodes_to_guard_conditions_ rclcpp::Executor::RCPPUTILS_TSA_GUARDED_BY ( mutex_  )
protected

maps nodes to guard conditions

◆ RCPPUTILS_TSA_GUARDED_BY() [2/5]

WeakCallbackGroupsToNodesMap weak_groups_associated_with_executor_to_nodes_ rclcpp::Executor::RCPPUTILS_TSA_GUARDED_BY ( mutex_  )
protected

maps callback groups associated to nodes

◆ RCPPUTILS_TSA_GUARDED_BY() [3/5]

WeakCallbackGroupsToNodesMap weak_groups_to_nodes_associated_with_executor_ rclcpp::Executor::RCPPUTILS_TSA_GUARDED_BY ( mutex_  )
protected

maps callback groups to nodes associated with executor

◆ RCPPUTILS_TSA_GUARDED_BY() [4/5]

WeakCallbackGroupsToNodesMap weak_groups_to_nodes_ rclcpp::Executor::RCPPUTILS_TSA_GUARDED_BY ( mutex_  )
protected

maps all callback groups to nodes

◆ RCPPUTILS_TSA_GUARDED_BY() [5/5]

std::list<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr> weak_nodes_ rclcpp::Executor::RCPPUTILS_TSA_GUARDED_BY ( mutex_  )
protected

nodes that are associated with the executor

Member Data Documentation

◆ spinning

std::atomic_bool rclcpp::Executor::spinning
protected

Spinning state, used to prevent multi threaded calls to spin and to cancel blocking spins.

◆ interrupt_guard_condition_

rcl_guard_condition_t rclcpp::Executor::interrupt_guard_condition_ = rcl_get_zero_initialized_guard_condition()
protected

Guard condition for signaling the rmw layer to wake up for special events.

◆ shutdown_guard_condition_

std::shared_ptr<rclcpp::GuardCondition> rclcpp::Executor::shutdown_guard_condition_
protected

◆ wait_set_

rcl_wait_set_t rclcpp::Executor::wait_set_ = rcl_get_zero_initialized_wait_set()
protected

Wait set for managing entities that the rmw layer waits on.

◆ mutex_

std::mutex rclcpp::Executor::mutex_
mutableprotected

◆ context_

std::shared_ptr<rclcpp::Context> rclcpp::Executor::context_
protected

The context associated with this executor.

◆ shutdown_callback_handle_

rclcpp::OnShutdownCallbackHandle rclcpp::Executor::shutdown_callback_handle_
protected

shutdown callback handle registered to Context


The documentation for this class was generated from the following file: