Class GuardCondition

Class Documentation

class GuardCondition

A condition that can be waited on in a single wait set and asynchronously triggered.

Public Functions

explicit GuardCondition(rclcpp::Context::SharedPtr context = rclcpp::contexts::get_global_default_context(), rcl_guard_condition_options_t guard_condition_options = rcl_guard_condition_get_default_options())

Construct the guard condition, optionally specifying which Context to use.

Parameters:
  • context[in] Optional custom context to be used. Defaults to using the global default context singleton. Shared ownership of the context is held with the guard condition until destruction.

  • guard_condition_options[in] Optional guard condition options to be used. Defaults to using the default guard condition options.

Throws:
  • std::invalid_argument – if the context is nullptr.

  • rclcpp::exceptions::RCLError – based exceptions when underlying rcl functions fail.

virtual ~GuardCondition()
rclcpp::Context::SharedPtr get_context() const

Return the context used when creating this guard condition.

rcl_guard_condition_t &get_rcl_guard_condition()

Return the underlying rcl guard condition structure.

const rcl_guard_condition_t &get_rcl_guard_condition() const

Return the underlying rcl guard condition structure.

void trigger()

Notify the wait set waiting on this condition, if any, that the condition had been met.

This function is thread-safe, and may be called concurrently with waiting on this guard condition in a wait set.

Throws:

rclcpp::exceptions::RCLError – based exceptions when underlying rcl functions fail.

bool exchange_in_use_by_wait_set_state(bool in_use_state)

Exchange the “in use by wait set” state for this guard condition.

This is used to ensure this guard condition is not used by multiple wait sets at the same time.

Parameters:

in_use_state[in] the new state to exchange into the state, true indicates it is now in use by a wait set, and false is that it is no longer in use by a wait set.

Returns:

the previous state.

void add_to_wait_set(rcl_wait_set_t *wait_set)

Adds the guard condition to a waitset.

This function is thread-safe.

Parameters:

wait_set[in] pointer to a wait set where to add the guard condition

void set_on_trigger_callback(std::function<void(size_t)> callback)

Protected Attributes

rclcpp::Context::SharedPtr context_
rcl_guard_condition_t rcl_guard_condition_
std::atomic<bool> in_use_by_wait_set_ = {false}
std::recursive_mutex reentrant_mutex_
std::function<void(size_t)> on_trigger_callback_ = {nullptr}
size_t unread_count_ = {0}
rcl_wait_set_t *wait_set_ = {nullptr}