ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
Public Member Functions | Protected Attributes | List of all members
rclcpp::GuardCondition Class Reference

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

#include <rclcpp/guard_condition.hpp>

Collaboration diagram for rclcpp::GuardCondition:
Collaboration graph
[legend]

Public Member Functions

RCLCPP_PUBLIC 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. More...
 
RCLCPP_PUBLIC rclcpp::Context::SharedPtr get_context () const
 Return the context used when creating this guard condition.
 
RCLCPP_PUBLIC rcl_guard_condition_tget_rcl_guard_condition ()
 Return the underlying rcl guard condition structure.
 
RCLCPP_PUBLIC const rcl_guard_condition_tget_rcl_guard_condition () const
 Return the underlying rcl guard condition structure.
 
RCLCPP_PUBLIC void trigger ()
 Notify the wait set waiting on this condition, if any, that the condition had been met. More...
 
RCLCPP_PUBLIC bool exchange_in_use_by_wait_set_state (bool in_use_state)
 Exchange the "in use by wait set" state for this guard condition. More...
 
RCLCPP_PUBLIC void add_to_wait_set (rcl_wait_set_t *wait_set)
 Adds the guard condition to a waitset. More...
 
RCLCPP_PUBLIC 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_twait_set_ {nullptr}
 

Detailed Description

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

Definition at line 31 of file guard_condition.hpp.

Constructor & Destructor Documentation

◆ GuardCondition()

rclcpp::GuardCondition::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() 
)
explicit

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

Parameters
[in]contextOptional 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.
[in]guard_condition_optionsOptional guard condition options to be used. Defaults to using the default guard condition options.
Exceptions
std::invalid_argumentif the context is nullptr.
rclcpp::exceptions::RCLErrorbased exceptions when underlying rcl functions fail.

Definition at line 25 of file guard_condition.cpp.

References rcl_guard_condition_init(), and RCL_RET_OK.

Here is the call graph for this function:

Member Function Documentation

◆ add_to_wait_set()

void rclcpp::GuardCondition::add_to_wait_set ( rcl_wait_set_t wait_set)

Adds the guard condition to a waitset.

This function is thread-safe.

Parameters
[in]wait_setpointer to a wait set where to add the guard condition

Definition at line 97 of file guard_condition.cpp.

References exchange_in_use_by_wait_set_state(), RCL_RET_OK, and rcl_wait_set_add_guard_condition().

Here is the call graph for this function:

◆ exchange_in_use_by_wait_set_state()

bool rclcpp::GuardCondition::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]in_use_statethe 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.

Definition at line 91 of file guard_condition.cpp.

Referenced by add_to_wait_set().

Here is the caller graph for this function:

◆ trigger()

void rclcpp::GuardCondition::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.

Exceptions
rclcpp::exceptions::RCLErrorbased exceptions when underlying rcl functions fail.

Definition at line 75 of file guard_condition.cpp.

References RCL_RET_OK, and rcl_trigger_guard_condition().

Referenced by rclcpp::executors::StaticSingleThreadedExecutor::add_callback_group(), rclcpp::Executor::add_callback_group_to_map(), rclcpp::executors::StaticSingleThreadedExecutor::add_node(), rclcpp::node_interfaces::NodeTimers::add_timer(), rclcpp::Executor::cancel(), rclcpp::Executor::execute_any_executable(), rclcpp::node_interfaces::NodeGraph::notify_graph_change(), rclcpp::executors::StaticSingleThreadedExecutor::remove_callback_group(), rclcpp::Executor::remove_callback_group_from_map(), and rclcpp::executors::StaticSingleThreadedExecutor::remove_node().

Here is the call graph for this function:
Here is the caller graph for this function:

The documentation for this class was generated from the following files: