ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
guard_condition.cpp
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 #include <functional>
16 
17 #include "rclcpp/guard_condition.hpp"
18 
19 #include "rclcpp/exceptions.hpp"
20 #include "rclcpp/logging.hpp"
21 
22 namespace rclcpp
23 {
24 
26  rclcpp::Context::SharedPtr context,
27  rcl_guard_condition_options_t guard_condition_options)
28 : context_(context), rcl_guard_condition_{rcl_get_zero_initialized_guard_condition()}
29 {
30  if (!context_) {
31  throw std::invalid_argument("context argument unexpectedly nullptr");
32  }
34  &this->rcl_guard_condition_,
35  context_->get_rcl_context().get(),
36  guard_condition_options);
37  if (RCL_RET_OK != ret) {
38  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to create guard condition");
39  }
40 }
41 
42 GuardCondition::~GuardCondition()
43 {
44  rcl_ret_t ret = rcl_guard_condition_fini(&this->rcl_guard_condition_);
45  if (RCL_RET_OK != ret) {
46  try {
47  rclcpp::exceptions::throw_from_rcl_error(ret);
48  } catch (const std::exception & exception) {
49  RCLCPP_ERROR(
50  rclcpp::get_logger("rclcpp"),
51  "failed to finalize guard condition: %s", exception.what());
52  }
53  }
54 }
55 
56 rclcpp::Context::SharedPtr
58 {
59  return context_;
60 }
61 
64 {
65  return rcl_guard_condition_;
66 }
67 
70 {
71  return rcl_guard_condition_;
72 }
73 
74 void
76 {
77  std::lock_guard<std::recursive_mutex> lock(reentrant_mutex_);
78 
79  if (on_trigger_callback_) {
80  on_trigger_callback_(1);
81  } else {
82  rcl_ret_t ret = rcl_trigger_guard_condition(&rcl_guard_condition_);
83  if (RCL_RET_OK != ret) {
84  rclcpp::exceptions::throw_from_rcl_error(ret);
85  }
86  unread_count_++;
87  }
88 }
89 
90 bool
92 {
93  return in_use_by_wait_set_.exchange(in_use_state);
94 }
95 
96 void
98 {
99  std::lock_guard<std::recursive_mutex> lock(reentrant_mutex_);
100 
102  if (wait_set != wait_set_) {
103  throw std::runtime_error("guard condition has already been added to a wait set.");
104  }
105  } else {
106  wait_set_ = wait_set;
107  }
108 
109  rcl_ret_t ret = rcl_wait_set_add_guard_condition(wait_set, &this->rcl_guard_condition_, NULL);
110  if (RCL_RET_OK != ret) {
111  rclcpp::exceptions::throw_from_rcl_error(
112  ret, "failed to add guard condition to wait set");
113  }
114 }
115 
116 void
117 GuardCondition::set_on_trigger_callback(std::function<void(size_t)> callback)
118 {
119  std::lock_guard<std::recursive_mutex> lock(reentrant_mutex_);
120 
121  if (callback) {
122  on_trigger_callback_ = callback;
123 
124  if (unread_count_) {
125  callback(unread_count_);
126  unread_count_ = 0;
127  }
128  return;
129  }
130 
131  on_trigger_callback_ = nullptr;
132 }
133 
134 } // namespace rclcpp
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_t rcl_get_zero_initialized_guard_condition(void)
Return a rcl_guard_condition_t struct with members set to NULL.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_trigger_guard_condition(rcl_guard_condition_t *guard_condition)
Trigger a rcl guard condition.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_guard_condition_init(rcl_guard_condition_t *guard_condition, rcl_context_t *context, const rcl_guard_condition_options_t options)
Initialize a rcl guard_condition.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_guard_condition_fini(rcl_guard_condition_t *guard_condition)
Finalize a rcl_guard_condition_t.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC Logger get_logger(const std::string &name)
Return a named logger.
Definition: logger.cpp:27
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
#define RCL_RET_OK
Success return code.
Definition: types.h:26
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:23
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_wait_set_add_guard_condition(rcl_wait_set_t *wait_set, const rcl_guard_condition_t *guard_condition, size_t *index)
Store a pointer to the guard condition in the next empty spot in the set.
Definition: wait.c:454