ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
Public Member Functions | List of all members
rclcpp::executors::SingleThreadedExecutor Class Reference

Single-threaded executor implementation. More...

#include <rclcpp/executors/single_threaded_executor.hpp>

Inheritance diagram for rclcpp::executors::SingleThreadedExecutor:
Inheritance graph
[legend]
Collaboration diagram for rclcpp::executors::SingleThreadedExecutor:
Collaboration graph
[legend]

Public Member Functions

RCLCPP_PUBLIC SingleThreadedExecutor (const rclcpp::ExecutorOptions &options=rclcpp::ExecutorOptions())
 Default constructor. See the default constructor for Executor.
 
virtual RCLCPP_PUBLIC ~SingleThreadedExecutor ()
 Default destructor.
 
RCLCPP_PUBLIC void spin () override
 Single-threaded implementation of spin. More...
 
- Public Member Functions inherited from rclcpp::Executor
RCLCPP_PUBLIC Executor (const rclcpp::ExecutorOptions &options=rclcpp::ExecutorOptions())
 Default constructor. More...
 
virtual RCLCPP_PUBLIC ~Executor ()
 Default destructor.
 
virtual RCLCPP_PUBLIC 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 RCLCPP_PUBLIC std::vector< rclcpp::CallbackGroup::WeakPtr > get_all_callback_groups ()
 Get callback groups that belong to executor. More...
 
virtual RCLCPP_PUBLIC std::vector< rclcpp::CallbackGroup::WeakPtr > get_manually_added_callback_groups ()
 Get callback groups that belong to executor. More...
 
virtual RCLCPP_PUBLIC std::vector< rclcpp::CallbackGroup::WeakPtr > get_automatically_added_callback_groups_from_nodes ()
 Get callback groups that belong to executor. More...
 
virtual RCLCPP_PUBLIC void remove_callback_group (rclcpp::CallbackGroup::SharedPtr group_ptr, bool notify=true)
 Remove a callback group from the executor. More...
 
virtual RCLCPP_PUBLIC void add_node (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true)
 Add a node to the executor. More...
 
virtual RCLCPP_PUBLIC void add_node (std::shared_ptr< rclcpp::Node > node_ptr, bool notify=true)
 Convenience function which takes Node and forwards NodeBaseInterface. More...
 
virtual RCLCPP_PUBLIC void remove_node (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true)
 Remove a node from the executor. More...
 
virtual RCLCPP_PUBLIC 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.
 
RCLCPP_PUBLIC void spin_node_some (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node)
 Add a node, complete all immediately available work, and remove the node. More...
 
RCLCPP_PUBLIC void spin_node_some (std::shared_ptr< rclcpp::Node > node)
 Convenience function which takes Node and forwards NodeBaseInterface.
 
virtual RCLCPP_PUBLIC 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 RCLCPP_PUBLIC 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 RCLCPP_PUBLIC 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...
 
RCLCPP_PUBLIC void cancel ()
 Cancel any running spin* function, causing it to return. More...
 
RCLCPP_PUBLIC void set_memory_strategy (memory_strategy::MemoryStrategy::SharedPtr memory_strategy)
 Support dynamic switching of the memory strategy. More...
 
RCLCPP_PUBLIC bool is_spinning ()
 Returns true if the executor is currently spinning. More...
 

Additional Inherited Members

- Protected Types inherited from rclcpp::Executor
typedef std::map< rclcpp::CallbackGroup::WeakPtr, const rclcpp::GuardCondition *, std::owner_less< rclcpp::CallbackGroup::WeakPtr > > WeakCallbackGroupsToGuardConditionsMap
 
- Protected Member Functions inherited from rclcpp::Executor
RCLCPP_PUBLIC void spin_node_once_nanoseconds (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, std::chrono::nanoseconds timeout)
 
RCLCPP_PUBLIC void spin_some_impl (std::chrono::nanoseconds max_duration, bool exhaustive)
 
RCLCPP_PUBLIC void execute_any_executable (AnyExecutable &any_exec)
 Find the next available executable and do the work associated with it. More...
 
RCLCPP_PUBLIC void wait_for_work (std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_by_group (const WeakCallbackGroupsToNodesMap &weak_groups_to_nodes, rclcpp::CallbackGroup::SharedPtr group)
 
RCLCPP_PUBLIC 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_PUBLIC rclcpp::CallbackGroup::SharedPtr get_group_by_timer (rclcpp::TimerBase::SharedPtr timer)
 
virtual RCLCPP_PUBLIC 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 RCLCPP_PUBLIC 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...
 
RCLCPP_PUBLIC bool get_next_ready_executable (AnyExecutable &any_executable)
 
RCLCPP_PUBLIC bool get_next_ready_executable_from_map (AnyExecutable &any_executable, const WeakCallbackGroupsToNodesMap &weak_groups_to_nodes)
 
RCLCPP_PUBLIC bool get_next_executable (AnyExecutable &any_executable, std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 
virtual RCLCPP_PUBLIC 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.
 
virtual RCLCPP_PUBLIC void spin_once_impl (std::chrono::nanoseconds timeout)
 
WeakCallbackGroupsToGuardConditionsMap weak_groups_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY (mutex_)
 maps callback groups to guard conditions
 
WeakCallbackGroupsToNodesMap weak_groups_associated_with_executor_to_nodes_ RCPPUTILS_TSA_GUARDED_BY (mutex_)
 maps callback groups associated to nodes
 
WeakCallbackGroupsToNodesMap weak_groups_to_nodes_associated_with_executor_ RCPPUTILS_TSA_GUARDED_BY (mutex_)
 maps callback groups to nodes associated with executor
 
WeakCallbackGroupsToNodesMap weak_groups_to_nodes_ RCPPUTILS_TSA_GUARDED_BY (mutex_)
 maps all callback groups to nodes
 
std::list< rclcpp::node_interfaces::NodeBaseInterface::WeakPtr > weak_nodes_ RCPPUTILS_TSA_GUARDED_BY (mutex_)
 nodes that are associated with the executor
 
- Static Protected Member Functions inherited from rclcpp::Executor
static RCLCPP_PUBLIC void execute_subscription (rclcpp::SubscriptionBase::SharedPtr subscription)
 
static RCLCPP_PUBLIC void execute_timer (rclcpp::TimerBase::SharedPtr timer)
 
static RCLCPP_PUBLIC void execute_service (rclcpp::ServiceBase::SharedPtr service)
 
static RCLCPP_PUBLIC void execute_client (rclcpp::ClientBase::SharedPtr client)
 
- Protected Attributes inherited from rclcpp::Executor
std::atomic_bool spinning
 Spinning state, used to prevent multi threaded calls to spin and to cancel blocking spins.
 
rclcpp::GuardCondition interrupt_guard_condition_
 Guard condition for signaling the rmw layer to wake up for special events.
 
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.
 
std::mutex mutex_
 
std::shared_ptr< rclcpp::Contextcontext_
 The context associated with this executor.
 
rclcpp::OnShutdownCallbackHandle shutdown_callback_handle_
 shutdown callback handle registered to Context
 

Detailed Description

Single-threaded executor implementation.

This is the default executor created by rclcpp::spin.

Definition at line 42 of file single_threaded_executor.hpp.

Member Function Documentation

◆ spin()

void SingleThreadedExecutor::spin ( )
overridevirtual

Single-threaded implementation of spin.

This function will block until work comes in, execute it, and then repeat the process until canceled. It may be interrupt by a call to rclcpp::Executor::cancel() or by ctrl-c if the associated context is configured to shutdown on SIGINT.

Exceptions
std::runtime_errorwhen spin() called while already spinning

Implements rclcpp::Executor.

Definition at line 28 of file single_threaded_executor.cpp.

References rclcpp::Executor::context_, rclcpp::Executor::execute_any_executable(), rclcpp::ok(), and rclcpp::Executor::spinning.

Referenced by rclcpp::spin().

Here is the call graph for this function:
Here is the caller graph for this function:

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