Class CBGScheduler

Nested Relationships

Nested Types

Class Documentation

class CBGScheduler

Public Functions

inline CallbackGroupHandle *add_callback_group(const rclcpp::CallbackGroup::SharedPtr &callback_group)
inline void remove_callback_group(const CallbackGroupHandle *callback_handle)
inline void callback_group_ready(CallbackGroupHandle *handle)
virtual std::optional<ExecutableEntity> get_next_ready_entity() = 0

Returns the next ready entity that shall be executed. If a entity is removed here, the scheduler may assume that it will be executed, and that the function mark_entity_as_executed will be called afterwards.

virtual std::optional<ExecutableEntity> get_next_ready_entity(GlobalEventIdProvider::MonotonicId max_id) = 0
inline void mark_entity_as_executed(const ExecutableEntity &e)

Must be called, after a entity was executed. This function will normally be used, to mark the associated callback group as ready again.

inline void unblock_one_worker_thread()

This function inserts a dummy event into the scheduler, so that a worker thread is unblocked, but does not execute any work afterwards. This is essential a hack, to allow the executor to perform its callback group syncing, without returning, making the spin some function return

inline void block_worker_thread()
inline void block_worker_thread_for(std::chrono::nanoseconds timeout)
inline void wakeup_one_worker_thread()
inline void release_all_worker_threads()

Protected Functions

virtual std::unique_ptr<CallbackGroupHandle> get_handle_for_callback_group(const rclcpp::CallbackGroup::SharedPtr &callback_group) = 0

Protected Attributes

std::mutex ready_callback_groups_mutex
std::deque<CallbackGroupHandle*> ready_callback_groups
bool release_workers = false
bool release_worker_once = false
std::condition_variable work_ready_conditional
std::list<std::unique_ptr<CallbackGroupHandle>> callback_groups
struct CallbackEventType

Public Functions

inline explicit CallbackEventType(std::function<void()> callback)
inline bool expired() const

Public Members

std::function<void()> callback
struct CallbackGroupHandle

Public Functions

inline explicit CallbackGroupHandle(CBGScheduler &scheduler)
virtual ~CallbackGroupHandle() = default
virtual std::function<void(size_t)> get_ready_callback_for_entity(const rclcpp::SubscriptionBase::WeakPtr &entity) = 0
virtual std::function<void(std::function<void()> executed_callback)> get_ready_callback_for_entity(const rclcpp::TimerBase::WeakPtr &entity) = 0
virtual std::function<void(size_t)> get_ready_callback_for_entity(const rclcpp::ClientBase::WeakPtr &entity) = 0
virtual std::function<void(size_t)> get_ready_callback_for_entity(const rclcpp::ServiceBase::WeakPtr &entity) = 0
virtual std::function<void(size_t, int)> get_ready_callback_for_entity(const rclcpp::Waitable::WeakPtr &entity) = 0
virtual std::function<void(size_t)> get_ready_callback_for_entity(const CallbackEventType &entity) = 0
inline void mark_as_executed()
bool is_ready()

Protected Functions

virtual bool has_ready_entities() const = 0

Will always be called under lock of ready_mutex

inline void check_move_to_ready()

This function checks if the callback group is currently idle, and may be moved into the list of ready callback groups

Must be called with ready_mutex locked

inline void mark_as_skiped()

Protected Attributes

CBGScheduler &scheduler
std::mutex ready_mutex
struct ExecutableEntity

Public Members

std::function<void()> execute_function
CallbackGroupHandle *callback_handle = nullptr
struct WaitableWithEventType

Public Functions

inline bool expired() const

Public Members

rclcpp::Waitable::WeakPtr waitable
int internal_event_type