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:
rclcpp::executor::Executor

Public Member Functions

 SingleThreadedExecutor (const executor::ExecutorArgs &args=rclcpp::executor::create_default_executor_arguments())
 Default constructor. See the default constructor for Executor. More...
 
virtual ~SingleThreadedExecutor ()
 Default destrcutor. More...
 
void spin ()
 Single-threaded implementation of spin. More...
 
- Public Member Functions inherited from rclcpp::executor::Executor
 Executor (const ExecutorArgs &args=create_default_executor_arguments())
 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 T = std::milli>
void spin_node_once (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, std::chrono::duration< int64_t, T > timeout=std::chrono::duration< int64_t, 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 T = std::milli>
void spin_node_once (std::shared_ptr< NodeT > node, std::chrono::duration< int64_t, T > timeout=std::chrono::duration< int64_t, 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 ()
 Complete all available queued work without blocking. More...
 
virtual void spin_once (std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 
template<typename ResponseT , typename TimeT = std::milli>
FutureReturnCode spin_until_future_complete (std::shared_future< ResponseT > &future, std::chrono::duration< int64_t, TimeT > timeout=std::chrono::duration< int64_t, 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::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::callback_group::CallbackGroup::SharedPtr group)
 
rclcpp::callback_group::CallbackGroup::SharedPtr get_group_by_timer (rclcpp::TimerBase::SharedPtr timer)
 
void get_next_timer (AnyExecutable &any_exec)
 
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::Executor
static void execute_subscription (rclcpp::SubscriptionBase::SharedPtr subscription)
 
static void execute_intra_process_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::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...
 
memory_strategy::MemoryStrategy::SharedPtr memory_strategy_
 The memory strategy: an interface for handling user-defined memory allocation strategies. More...
 

Detailed Description

Single-threaded executor implementation.

Constructor & Destructor Documentation

◆ SingleThreadedExecutor()

rclcpp::executors::SingleThreadedExecutor::SingleThreadedExecutor ( const executor::ExecutorArgs args = rclcpp::executor::create_default_executor_arguments())

Default constructor. See the default constructor for Executor.

◆ ~SingleThreadedExecutor()

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

Default destrcutor.

Member Function Documentation

◆ spin()

void rclcpp::executors::SingleThreadedExecutor::spin ( )
virtual

Single-threaded implementation of spin.

Implements rclcpp::executor::Executor.


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