rclcpp  master
C++ ROS Client Library API
Public Member Functions | List of all members
rclcpp::executors::SingleThreadedExecutor Class Reference

Single-threaded executor implementation. More...

#include <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

 SingleThreadedExecutor (const rclcpp::ExecutorOptions &options=rclcpp::ExecutorOptions())
 Default constructor. See the default constructor for Executor. More...
 
virtual ~SingleThreadedExecutor ()
 Default destructor. More...
 
void spin () override
 Single-threaded implementation of spin. More...
 
- Public Member Functions inherited from rclcpp::Executor
 Executor (const rclcpp::ExecutorOptions &options=rclcpp::ExecutorOptions())
 Default constructor. More...
 
virtual ~Executor ()
 Default destructor. 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))
 Complete all available queued work without blocking. More...
 
virtual void spin_once (std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 
template<typename ResponseT , typename TimeRepT = int64_t, typename TimeT = std::milli>
FutureReturnCode spin_until_future_complete (const std::shared_future< ResponseT > &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...
 

Additional Inherited Members

- Protected Member Functions inherited from rclcpp::Executor
void spin_node_once_nanoseconds (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, std::chrono::nanoseconds timeout)
 
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 (rclcpp::CallbackGroup::SharedPtr group)
 
rclcpp::CallbackGroup::SharedPtr get_group_by_timer (rclcpp::TimerBase::SharedPtr timer)
 
bool get_next_ready_executable (AnyExecutable &any_executable)
 
bool get_next_executable (AnyExecutable &any_executable, std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 
- Static Protected Member Functions inherited from rclcpp::Executor
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 inherited from rclcpp::Executor
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...
 
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 memory_strategy_mutex_
 
memory_strategy::MemoryStrategy::SharedPtr memory_strategy_
 The memory strategy: an interface for handling user-defined memory allocation strategies. More...
 
std::shared_ptr< rclcpp::Contextcontext_
 The context associated with this executor. More...
 
std::list< rclcpp::node_interfaces::NodeBaseInterface::WeakPtr > weak_nodes_
 
std::list< const rcl_guard_condition_t * > guard_conditions_
 

Detailed Description

Single-threaded executor implementation.

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

Constructor & Destructor Documentation

◆ SingleThreadedExecutor()

rclcpp::executors::SingleThreadedExecutor::SingleThreadedExecutor ( const rclcpp::ExecutorOptions options = rclcpp::ExecutorOptions())
explicit

Default constructor. See the default constructor for Executor.

◆ ~SingleThreadedExecutor()

virtual rclcpp::executors::SingleThreadedExecutor::~SingleThreadedExecutor ( )
virtual

Default destructor.

Member Function Documentation

◆ spin()

void rclcpp::executors::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.


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