Class StaticExecutorEntitiesCollector

Inheritance Relationships

Base Types

  • public rclcpp::Waitable (Class Waitable)

  • public std::enable_shared_from_this< StaticExecutorEntitiesCollector >

Class Documentation

class StaticExecutorEntitiesCollector : public rclcpp::Waitable, public std::enable_shared_from_this<StaticExecutorEntitiesCollector>

Public Functions

StaticExecutorEntitiesCollector() = default
~StaticExecutorEntitiesCollector()
void init(rcl_wait_set_t *p_wait_set, rclcpp::memory_strategy::MemoryStrategy::SharedPtr memory_strategy)

Initialize StaticExecutorEntitiesCollector.

Parameters:
  • p_wait_set – A reference to the wait set to be used in the executor

  • memory_strategy – Shared pointer to the memory strategy to set.

Throws:

std::runtime_error – if memory strategy is null

inline bool is_init()

Finalize StaticExecutorEntitiesCollector to clear resources.

void fini()
virtual void execute(std::shared_ptr<void> &data) override

Execute the waitable.

virtual std::shared_ptr<void> take_data() override

Take the data so that it can be consumed with execute.

For StaticExecutorEntitiesCollector, this always return nullptr.

void refresh_wait_set(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))

Function to add_handles_to_wait_set and wait for work and.

block until the wait set is ready or until the timeout has been exceeded.

Throws:
  • std::runtime_error – if wait set couldn’t be cleared or filled.

  • any – rcl errors from rcl_wait,

virtual void add_to_wait_set(rcl_wait_set_t *wait_set) override
Throws:

std::runtime_error – if it couldn’t add guard condition to wait set

virtual size_t get_number_of_ready_guard_conditions() override

Get the number of ready guard_conditions.

Returns a value of 0 by default. This should be overridden if the Waitable contains one or more guard_conditions.

Returns:

The number of guard_conditions associated with the Waitable.

bool add_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)

Add a callback group to an executor.

bool add_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, WeakCallbackGroupsToNodesMap &weak_groups_to_nodes)

Add a callback group to an executor.

Returns:

boolean whether the node from the callback group is new

bool remove_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr)

Remove a callback group from the executor.

bool remove_callback_group_from_map(rclcpp::CallbackGroup::SharedPtr group_ptr, WeakCallbackGroupsToNodesMap &weak_groups_to_nodes)

Remove a callback group from the executor.

bool add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)

Throws:

std::runtime_error – if node was already added

bool remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)

Throws:

std::runtime_error – if no guard condition is associated with node.

std::vector<rclcpp::CallbackGroup::WeakPtr> get_all_callback_groups()
std::vector<rclcpp::CallbackGroup::WeakPtr> get_manually_added_callback_groups()

Get callback groups that belong to executor.

std::vector<rclcpp::CallbackGroup::WeakPtr> get_automatically_added_callback_groups_from_nodes()

Get callback groups that belong to executor.

virtual bool is_ready(rcl_wait_set_t *wait_set) override

Complete all available queued work without blocking.

This function checks if after the guard condition was triggered (or a spurious wakeup happened) we are really ready to execute i.e. re-collect entities

inline size_t get_number_of_timers()

Return number of timers.

Returns:

number of timers

inline size_t get_number_of_subscriptions()

Return number of subscriptions.

Returns:

number of subscriptions

inline size_t get_number_of_services()

Return number of services.

Returns:

number of services

inline size_t get_number_of_clients()

Return number of clients.

Returns:

number of clients

inline size_t get_number_of_waitables()

Return number of waitables.

Returns:

number of waitables

inline rclcpp::SubscriptionBase::SharedPtr get_subscription(size_t i)

Return a SubscritionBase Sharedptr by index.

Parameters:

i[in] The index of the SubscritionBase

Throws:

std::out_of_range – if the argument is higher than the size of the structrue.

Returns:

a SubscritionBase shared pointer

inline rclcpp::TimerBase::SharedPtr get_timer(size_t i)

Return a TimerBase Sharedptr by index.

Parameters:

i[in] The index of the TimerBase

Throws:

std::out_of_range – if the argument is higher than the size.

Returns:

a TimerBase shared pointer

inline rclcpp::ServiceBase::SharedPtr get_service(size_t i)

Return a ServiceBase Sharedptr by index.

Parameters:

i[in] The index of the ServiceBase

Throws:

std::out_of_range – if the argument is higher than the size.

Returns:

a ServiceBase shared pointer

inline rclcpp::ClientBase::SharedPtr get_client(size_t i)

Return a ClientBase Sharedptr by index

Parameters:

i[in] The index of the ClientBase

Throws:

std::out_of_range – if the argument is higher than the size.

Returns:

a ClientBase shared pointer

inline rclcpp::Waitable::SharedPtr get_waitable(size_t i)

Return a Waitable Sharedptr by index

Parameters:

i[in] The index of the Waitable

Throws:

std::out_of_range – if the argument is higher than the size.

Returns:

a Waitable shared pointer