Class ExecutorEntitiesCollector

Class Documentation

class ExecutorEntitiesCollector

Class to monitor a set of nodes and callback groups for changes in entity membership.

This is to be used with an executor to track the membership of various nodes, groups, and entities (timers, subscriptions, clients, services, etc) and report status to the executor.

In general, users will add either nodes or callback groups to an executor. Each node may have callback groups that are automatically associated with executors, or callback groups that must be manually associated with an executor.

This object tracks both types of callback groups as well as nodes that have been previously added to the executor. When a new callback group is added/removed or new entities are added/removed, the corresponding node or callback group will signal this to the executor so that the entity collection may be rebuilt according to that executor’s implementation.

Public Functions

explicit ExecutorEntitiesCollector(std::shared_ptr<ExecutorNotifyWaitable> notify_waitable)

Constructor.

Parameters:

notify_waitable[in] Waitable that is used to signal to the executor when nodes or callback groups have been added or removed.

~ExecutorEntitiesCollector()

Destructor.

bool has_pending() const

Indicate if the entities collector has pending additions or removals.

Returns:

true if there are pending additions or removals

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

Add a node to the entity collector.

Parameters:

node_ptr[in] a shared pointer that points to a node base interface

Throws:

std::runtime_error – if the node is associated with an executor

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

Remove a node from the entity collector.

Parameters:

node_ptr[in] a shared pointer that points to a node base interface

Throws:
  • std::runtime_error – if the node is associated with an executor

  • std::runtime_error – if the node is associated with this executor

void add_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr)

Add a callback group to the entity collector.

Parameters:

group_ptr[in] a shared pointer that points to a callback group

Throws:

std::runtime_error – if the callback_group is associated with an executor

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

Remove a callback group from the entity collector.

Parameters:

group_ptr[in] a shared pointer that points to a callback group

Throws:
  • std::runtime_error – if the callback_group is not associated with an executor

  • std::runtime_error – if the callback_group is not associated with this executor

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

Get all callback groups known to this entity collector.

This will include manually added and automatically added (node associated) groups

Returns:

vector of all callback groups

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

Get manually-added callback groups known to this entity collector.

This will include callback groups that have been added via add_callback_group

Returns:

vector of manually-added callback groups

std::vector<rclcpp::CallbackGroup::WeakPtr> get_automatically_added_callback_groups() const

Get automatically-added callback groups known to this entity collector.

This will include callback groups that are associated with nodes added via add_node

Returns:

vector of automatically-added callback groups

void update_collections()

Update the underlying collections.

This will prune nodes and callback groups that are no longer valid as well as add new callback groups from any associated nodes.

Protected Types

using NodeCollection = std::set<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr, std::owner_less<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>>
using CallbackGroupCollection = std::set<rclcpp::CallbackGroup::WeakPtr, std::owner_less<rclcpp::CallbackGroup::WeakPtr>>
using WeakNodesToGuardConditionsMap = std::map<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr, rclcpp::GuardCondition::WeakPtr, std::owner_less<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>>
using WeakGroupsToGuardConditionsMap = std::map<rclcpp::CallbackGroup::WeakPtr, rclcpp::GuardCondition::WeakPtr, std::owner_less<rclcpp::CallbackGroup::WeakPtr>>

Protected Functions

NodeCollection::iterator remove_weak_node(NodeCollection::iterator weak_node)

Implementation of removing a node from the collector.

This will disassociate the node from the collector and remove any automatically-added callback groups

This takes and returns an iterator so it may be used as:

it = remove_weak_node(it);

Parameters:

weak_node[in] iterator to the weak node to be removed

Returns:

Valid updated iterator in the same collection

CallbackGroupCollection::iterator remove_weak_callback_group(CallbackGroupCollection::iterator weak_group_it, CallbackGroupCollection &collection)

Implementation of removing a callback group from the collector.

This will disassociate the callback group from the collector

This takes and returns an iterator so it may be used as:

it = remove_weak_callback_group(it);

Parameters:
  • weak_group_it[in] iterator to the weak group to be removed

  • collection[in] the collection to remove the group from (manually or automatically added)

Returns:

Valid updated iterator in the same collection

void add_callback_group_to_collection(rclcpp::CallbackGroup::SharedPtr group_ptr, CallbackGroupCollection &collection)

Implementation of adding a callback group.

Parameters:
  • group_ptr[in] the group to add

  • collection[in] the collection to add the group to

void process_queues()

Iterate over queued added/remove nodes and callback_groups.

void add_automatically_associated_callback_groups(const NodeCollection &nodes_to_check)

Check a collection of nodes and add any new callback_groups that are set to be automatically associated via the node.

void prune_invalid_nodes_and_groups()

Check all nodes and group for expired weak pointers and remove them.

Protected Attributes

mutable std::mutex mutex_

mutex to protect collections and pending queues

CallbackGroupCollection manually_added_groups_

Callback groups that were added via add_callback_group

CallbackGroupCollection automatically_added_groups_

Callback groups that were added by their association with added nodes.

NodeCollection weak_nodes_

nodes that are associated with the executor

WeakNodesToGuardConditionsMap weak_nodes_to_guard_conditions_

Track guard conditions associated with added nodes.

WeakGroupsToGuardConditionsMap weak_groups_to_guard_conditions_

Track guard conditions associated with added callback groups.

NodeCollection pending_added_nodes_

nodes that have been added since the last update.

NodeCollection pending_removed_nodes_

nodes that have been removed since the last update.

CallbackGroupCollection pending_manually_added_groups_

callback groups that have been added since the last update.

CallbackGroupCollection pending_manually_removed_groups_

callback groups that have been removed since the last update.

std::shared_ptr<ExecutorNotifyWaitable> notify_waitable_

Waitable to add guard conditions to.