ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
guard_condition.hpp
1 // Copyright 2020 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__GUARD_CONDITION_HPP_
16 #define RCLCPP__GUARD_CONDITION_HPP_
17 
18 #include <atomic>
19 
20 #include "rcl/guard_condition.h"
21 
22 #include "rclcpp/context.hpp"
23 #include "rclcpp/contexts/default_context.hpp"
24 #include "rclcpp/macros.hpp"
25 #include "rclcpp/visibility_control.hpp"
26 
27 namespace rclcpp
28 {
29 
32 {
33 public:
34  RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(GuardCondition)
35 
36  // TODO(wjwwood): support custom allocator, maybe restrict to polymorphic allocator
38 
49  RCLCPP_PUBLIC
50  explicit GuardCondition(
51  rclcpp::Context::SharedPtr context =
52  rclcpp::contexts::get_global_default_context(),
53  rcl_guard_condition_options_t guard_condition_options =
55 
56  RCLCPP_PUBLIC
57  virtual
58  ~GuardCondition();
59 
61  RCLCPP_PUBLIC
62  rclcpp::Context::SharedPtr
63  get_context() const;
64 
66  RCLCPP_PUBLIC
69 
71  RCLCPP_PUBLIC
72  const rcl_guard_condition_t &
74 
76 
83  RCLCPP_PUBLIC
84  void
85  trigger();
86 
88 
97  RCLCPP_PUBLIC
98  bool
99  exchange_in_use_by_wait_set_state(bool in_use_state);
100 
102 
106  RCLCPP_PUBLIC
107  void
108  add_to_wait_set(rcl_wait_set_t * wait_set);
109 
110  RCLCPP_PUBLIC
111  void
112  set_on_trigger_callback(std::function<void(size_t)> callback);
113 
114 protected:
115  rclcpp::Context::SharedPtr context_;
116  rcl_guard_condition_t rcl_guard_condition_;
117  std::atomic<bool> in_use_by_wait_set_{false};
118  std::recursive_mutex reentrant_mutex_;
119  std::function<void(size_t)> on_trigger_callback_{nullptr};
120  size_t unread_count_{0};
121  rcl_wait_set_t * wait_set_{nullptr};
122 };
123 
124 } // namespace rclcpp
125 
126 #endif // RCLCPP__GUARD_CONDITION_HPP_
A condition that can be waited on in a single wait set and asynchronously triggered.
RCLCPP_PUBLIC void trigger()
Notify the wait set waiting on this condition, if any, that the condition had been met.
RCLCPP_PUBLIC rcl_guard_condition_t & get_rcl_guard_condition()
Return the underlying rcl guard condition structure.
RCLCPP_PUBLIC void add_to_wait_set(rcl_wait_set_t *wait_set)
Adds the guard condition to a waitset.
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.
RCLCPP_PUBLIC rclcpp::Context::SharedPtr get_context() const
Return the context used when creating this guard condition.
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.
RCL_PUBLIC RCL_WARN_UNUSED rcl_guard_condition_options_t rcl_guard_condition_get_default_options(void)
Return the default options in a rcl_guard_condition_options_t struct.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
Options available for a rcl guard condition.
Handle for a rcl guard condition.
Container for subscription's, guard condition's, etc to be waited on.
Definition: wait.h:42