Class EventsCBGExecutor
Defined in File events_cbg_executor.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public rclcpp::Executor
Class Documentation
-
class EventsCBGExecutor : public rclcpp::Executor
Public Functions
-
explicit RCLCPP_PUBLIC EventsCBGExecutor(const rclcpp::ExecutorOptions &options = rclcpp::ExecutorOptions(), size_t number_of_threads = 0, std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))
For the yield_before_execute option, when true std::this_thread::yield() will be called after acquiring work (as an AnyExecutable) and releasing the spinning lock, but before executing the work. This is useful for reproducing some bugs related to taking work more than once.
- Parameters:
options – common options for all executors
number_of_threads – number of threads to have in the thread pool, the default 0 will use the number of cpu cores found (minimum of 2)
yield_before_execute – if true std::this_thread::yield() is called
timeout – maximum time to wait
-
virtual RCLCPP_PUBLIC ~EventsCBGExecutor()
- virtual RCLCPP_PUBLIC void add_callback_group (rclcpp::CallbackGroup::SharedPtr group_ptr, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true)
- virtual RCLCPP_PUBLIC std::vector< rclcpp::CallbackGroup::WeakPtr > get_all_callback_groups ()
- virtual RCLCPP_PUBLIC void remove_callback_group (rclcpp::CallbackGroup::SharedPtr group_ptr, bool notify=true)
- virtual RCLCPP_PUBLIC void add_node (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true)
- virtual RCLCPP_PUBLIC void add_node (std::shared_ptr< rclcpp::Node > node_ptr, bool notify=true)
Convenience function which takes Node and forwards NodeBaseInterface.
See also
rclcpp::Executor::add_node
- virtual RCLCPP_PUBLIC void remove_node (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true)
- virtual RCLCPP_PUBLIC void remove_node (std::shared_ptr< rclcpp::Node > node_ptr, bool notify=true)
Convenience function which takes Node and forwards NodeBaseInterface.
See also
rclcpp::Executor::remove_node
- RCLCPP_PUBLIC void spin ()
See also
rclcpp::Executor:spin() for more details
- Throws:
std::runtime_error – when spin() called while already spinning
- RCLCPP_PUBLIC void spin (std::function< void(const std::exception &e)> exception_handler)
The exception_handler can be called from multiple threads at the same time. The exception_handler shall rethrow the exception it if wants to terminate the program.
See also
rclcpp::Executor:spin() for more details
- Throws:
std::runtime_error – when spin() called while already spinning
- Parameters:
exception_handler – will be called for every exception in the processing threads
-
virtual void spin_once(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))
- virtual RCLCPP_PUBLIC void spin_some (std::chrono::nanoseconds max_duration=std::chrono::nanoseconds(0))
-
bool collect_and_execute_ready_events(std::chrono::nanoseconds max_duration, bool recollect_if_no_work_available)
- Returns:
true if work was available and executed
-
virtual void spin_all(std::chrono::nanoseconds max_duration)
- RCLCPP_PUBLIC void cancel ()
Cancel any running spin* function, causing it to return.
This function can be called asynchonously from any thread.
- Throws:
std::runtime_error – if there is an issue triggering the guard condition
- RCLCPP_PUBLIC size_t get_number_of_threads ()
-
inline bool is_spinning()
Protected Functions
- RCLCPP_PUBLIC void run (size_t this_thread_number)
-
void run(size_t this_thread_number, std::function<void(const std::exception &e)> exception_handler)
-
void set_callbacks(CallbackGroupData &cgd)
-
bool execute_ready_executables_until(const std::chrono::time_point<std::chrono::steady_clock> &stop_time)
-
bool execute_previous_ready_executables_until(const std::chrono::time_point<std::chrono::steady_clock> &stop_time)
This function will execute all available executables, that were ready, before this function was called.
-
struct CallbackGroupData
Public Members
-
CallbackGroup::WeakPtr callback_group
-
std::unique_ptr<RegisteredEntityCache> registered_entities
-
CallbackGroup::WeakPtr callback_group
-
explicit RCLCPP_PUBLIC EventsCBGExecutor(const rclcpp::ExecutorOptions &options = rclcpp::ExecutorOptions(), size_t number_of_threads = 0, std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))