Template Class WaitSetTemplate

Inheritance Relationships

Base Types

  • private SynchronizationPolicy

  • private StoragePolicy

Class Documentation

template<class SynchronizationPolicy, class StoragePolicy>
class WaitSetTemplate : private SynchronizationPolicy, private StoragePolicy

Encapsulates sets of waitable items which can be waited on as a group.

This class uses the rcl_wait_set_t as storage, but it also helps manage the ownership of associated rclcpp types.

Public Functions

inline explicit WaitSetTemplate(const typename StoragePolicy::SubscriptionsIterable &subscriptions = {}, const typename StoragePolicy::GuardConditionsIterable &guard_conditions = {}, const typename StoragePolicy::TimersIterable &timers = {}, const typename StoragePolicy::ClientsIterable &clients = {}, const typename StoragePolicy::ServicesIterable &services = {}, const typename StoragePolicy::WaitablesIterable &waitables = {}, rclcpp::Context::SharedPtr context = rclcpp::contexts::get_global_default_context())

Construct a wait set with optional initial waitable entities and optional custom context.

For the waitables, they have additionally an “associated” entity, which you can read more about in the add and remove functions for those types in this class.

Parameters:
  • subscriptions[in] Vector of subscriptions to be added.

  • guard_conditions[in] Vector of guard conditions to be added.

  • timers[in] Vector of timers to be added.

  • clients[in] Vector of clients and their associated entity to be added.

  • services[in] Vector of services and their associated entity to be added.

  • waitables[in] Vector of waitables and their associated entity to be added.

  • context[in] Custom context to be used, defaults to global default.

Throws:

std::invalid_argument – If context is nullptr.

inline const rcl_wait_set_t &get_rcl_wait_set() const

Return the internal rcl wait set object.

This method provides no thread-safety when accessing this structure. The state of this structure can be updated at anytime by methods like wait(), add_*(), remove_*(), etc.

inline void add_subscription(std::shared_ptr<rclcpp::SubscriptionBase> subscription, rclcpp::SubscriptionWaitSetMask mask = {})

Add a subscription to this wait set.

Additionally to the documentation for add_guard_condition, this method has a mask parameter which allows you to control which parts of the subscription is added to the wait set with this call. For example, you might want to include the actual subscription to this wait set, but add the intra-process waitable to another wait set. If intra-process is disabled, no error will occur, it will just be skipped.

See also

add_guard_condition() for details of how this method works.

When introspecting after waiting, this subscription’s shared pointer will be the Waitable’s (intra-process or the QoS Events) “associated entity” pointer, for more easily figuring out which subscription which waitable goes with afterwards.

Parameters:
  • subscription[in] Subscription to be added.

  • mask[in] A class which controls which parts of the subscription to add.

Throws:
  • std::invalid_argument – if subscription is nullptr.

  • std::runtime_error – if subscription has already been added or is associated with another wait set.

  • exceptions – based on the policies used.

inline void remove_subscription(std::shared_ptr<rclcpp::SubscriptionBase> subscription, rclcpp::SubscriptionWaitSetMask mask = {})

Remove a subscription from this wait set.

Additionally to the documentation for add_guard_condition, this method has a mask parameter which allows you to control which parts of the subscription is added to the wait set with this call. You may remove items selectively from the wait set in a different order than they were added.

See also

remove_guard_condition() for details of how this method works.

Parameters:
  • subscription[in] Subscription to be removed.

  • mask[in] A class which controls which parts of the subscription to remove.

Throws:
  • std::invalid_argument – if subscription is nullptr.

  • std::runtime_error – if subscription is not part of the wait set.

  • exceptions – based on the policies used.

inline void add_guard_condition(std::shared_ptr<rclcpp::GuardCondition> guard_condition)

Add a guard condition to this wait set.

Guard condition is added to the wait set, and shared ownership is held while waiting. However, if between calls to wait() the guard condition’s reference count goes to zero, it will be implicitly removed on the next call to wait().

Except in the case of a fixed sized storage, where changes to the wait set cannot occur after construction, in which case it holds shared ownership at all times until the wait set is destroy, but this method also does not exist on a fixed sized wait set.

This function may be thread-safe depending on the SynchronizationPolicy used with this class. Using the ThreadSafeWaitSetPolicy will ensure that wait() is interrupted and returns before this function adds the guard condition. Otherwise, it is not safe to call this function concurrently with wait().

This function will not be enabled (will not be available) if the StoragePolicy does not allow editing of the wait set after initialization.

Parameters:

guard_condition[in] Guard condition to be added.

Throws:
  • std::invalid_argument – if guard_condition is nullptr.

  • std::runtime_error – if guard_condition has already been added or is associated with another wait set.

  • exceptions – based on the policies used.

inline void remove_guard_condition(std::shared_ptr<rclcpp::GuardCondition> guard_condition)

Remove a guard condition from this wait set.

Guard condition is removed from the wait set, and if needed the shared ownership is released.

This function may be thread-safe depending on the SynchronizationPolicy used with this class. Using the ThreadSafeWaitSetPolicy will ensure that wait() is interrupted and returns before this function removes the guard condition. Otherwise, it is not safe to call this function concurrently with wait().

This function will not be enabled (will not be available) if the StoragePolicy does not allow editing of the wait set after initialization.

Parameters:

guard_condition[in] Guard condition to be removed.

Throws:
  • std::invalid_argument – if guard_condition is nullptr.

  • std::runtime_error – if guard_condition is not part of the wait set.

  • exceptions – based on the policies used.

inline void add_timer(std::shared_ptr<rclcpp::TimerBase> timer)

Add a timer to this wait set.

See also

add_guard_condition() for details of how this method works.

Parameters:

timer[in] Timer to be added.

Throws:
  • std::invalid_argument – if timer is nullptr.

  • std::runtime_error – if timer has already been added or is associated with another wait set.

  • exceptions – based on the policies used.

inline void remove_timer(std::shared_ptr<rclcpp::TimerBase> timer)

Remove a timer from this wait set.

See also

remove_guard_condition() for details of how this method works.

Parameters:

timer[in] Timer to be removed.

Throws:
  • std::invalid_argument – if timer is nullptr.

  • std::runtime_error – if timer is not part of the wait set.

  • exceptions – based on the policies used.

inline void add_client(std::shared_ptr<rclcpp::ClientBase> client)

Add a client to this wait set.

See also

add_guard_condition() for details of how this method works.

Parameters:

client[in] Client to be added.

Throws:
  • std::invalid_argument – if client is nullptr.

  • std::runtime_error – if client has already been added or is associated with another wait set.

  • exceptions – based on the policies used.

inline void remove_client(std::shared_ptr<rclcpp::ClientBase> client)

Remove a client from this wait set.

See also

remove_guard_condition() for details of how this method works.

Parameters:

client[in] Client to be removed.

Throws:
  • std::invalid_argument – if client is nullptr.

  • std::runtime_error – if client is not part of the wait set.

  • exceptions – based on the policies used.

inline void add_service(std::shared_ptr<rclcpp::ServiceBase> service)

Add a service to this wait set.

See also

add_guard_condition() for details of how this method works.

Parameters:

service[in] Service to be added.

Throws:
  • std::invalid_argument – if service is nullptr.

  • std::runtime_error – if service has already been added or is associated with another wait set.

  • exceptions – based on the policies used.

inline void remove_service(std::shared_ptr<rclcpp::ServiceBase> service)

Remove a service from this wait set.

See also

remove_guard_condition() for details of how this method works.

Parameters:

service[in] Service to be removed.

Throws:
  • std::invalid_argument – if service is nullptr.

  • std::runtime_error – if service is not part of the wait set.

  • exceptions – based on the policies used.

inline void add_waitable(std::shared_ptr<rclcpp::Waitable> waitable, std::shared_ptr<void> associated_entity = nullptr)

Add a waitable to this wait set.

Additionally, this function has an optional parameter which can be used to more quickly associate this waitable with an entity when it is ready, and so that the ownership maybe held in order to keep the waitable’s parent in scope while waiting. If it is set to nullptr it will be ignored. The destruction of the associated entity’s shared pointer will not cause the waitable to be removed, but it will cause the associated entity pointer to be nullptr when introspecting this waitable after waiting.

See also

add_guard_condition() for details of how this method works.

Note that rclcpp::QOSEventHandlerBase are just a special case of rclcpp::Waitable and can be added with this function.

Parameters:
  • waitable[in] Waitable to be added.

  • associated_entity[in] Type erased shared pointer associated with the waitable. This may be nullptr.

Throws:
  • std::invalid_argument – if waitable is nullptr.

  • std::runtime_error – if waitable has already been added or is associated with another wait set.

  • exceptions – based on the policies used.

inline void remove_waitable(std::shared_ptr<rclcpp::Waitable> waitable)

Remove a waitable from this wait set.

See also

remove_guard_condition() for details of how this method works.

Parameters:

waitable[in] Waitable to be removed.

Throws:
  • std::invalid_argument – if waitable is nullptr.

  • std::runtime_error – if waitable is not part of the wait set.

  • exceptions – based on the policies used.

inline void prune_deleted_entities()

Remove any destroyed entities from the wait set.

When the storage policy does not maintain shared ownership for the life of the wait set, e.g. the DynamicStorage policy, it is possible for an entity to go out of scope and be deleted without this wait set noticing. Therefore there are weak references in this wait set which need to be periodically cleared. This function performs that clean up.

Since this involves removing entities from the wait set, and is only needed if the wait set does not keep ownership of the added entities, the storage policies which are static will not need this function and therefore do not provide this function.

Throws:

exceptions – based on the policies used.

template<class Rep = int64_t, class Period = std::milli>
inline WaitResult<WaitSetTemplate> wait(std::chrono::duration<Rep, Period> time_to_wait = std::chrono::duration<Rep, Period>(-1))

Wait for any of the entities in the wait set to be ready, or a period of time to pass.

This function will return when either one of the entities within this wait set is ready, or a period of time has passed, which ever is first. The term “ready” means different things for different entities, but generally it means some condition is met asynchronously for which this function waits.

This function can either wait for a period of time, do no waiting (non-blocking), or wait indefinitely, all based on the value of the time_to_wait parameter. Waiting is always measured against the std::chrono::steady_clock. If waiting indefinitely, the Timeout result is not possible. There is no “cancel wait” function on this class, but if you want to wait indefinitely but have a way to asynchronously interrupt this method, then you can use a dedicated rclcpp::GuardCondition for that purpose.

This function will modify the internal rcl_wait_set_t, so introspecting the wait set during a call to wait is never safe. You should always wait, then introspect, and then, only when done introspecting, wait again.

It may be thread-safe to add and remove entities to the wait set concurrently with this function, depending on the SynchronizationPolicy that is used. With the rclcpp::wait_set_policies::ThreadSafeSynchronization policy this function will stop waiting to allow add or remove of an entity, and then resume waiting, so long as the timeout has not been reached.

Parameters:

time_to_wait[in] If > 0, time to wait for entities to be ready, if == 0, check if anything is ready without blocking, or if < 0, wait indefinitely until one of the items is ready. Default is -1, so wait indefinitely.

Throws:
  • rclcpp::exceptions::RCLError – on unhandled rcl errors or,

  • std::runtime_error – if unknown WaitResultKind

Returns:

Ready when one of the entities is ready, or

Returns:

Timeout when the given time to wait is exceeded, not possible when time_to_wait is < 0, or

Returns:

Empty if the wait set is empty, avoiding the possibility of waiting indefinitely on an empty wait set.