ROS 2 rclcpp + rcl - kilted  kilted
ROS 2 C++ Client Library with ROS Client Library
add_guard_condition_to_rcl_wait_set.cpp
1 // Copyright 2021 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 "rclcpp/detail/add_guard_condition_to_rcl_wait_set.hpp"
16 #include "rclcpp/exceptions.hpp"
17 
18 namespace rclcpp
19 {
20 namespace detail
21 {
22 
23 void
24 add_guard_condition_to_rcl_wait_set(
25  rcl_wait_set_t & wait_set,
26  const rclcpp::GuardCondition & guard_condition)
27 {
28  const auto & gc = guard_condition.get_rcl_guard_condition();
29 
30  rcl_ret_t ret = rcl_wait_set_add_guard_condition(&wait_set, &gc, NULL);
31 
32  if (RCL_RET_OK != ret) {
33  rclcpp::exceptions::throw_from_rcl_error(
34  ret, "failed to add guard condition to wait set");
35  }
36 }
37 
38 } // namespace detail
39 } // namespace rclcpp
A condition that can be waited on in a single wait set and asynchronously triggered.
RCLCPP_PUBLIC rcl_guard_condition_t & get_rcl_guard_condition()
Return the underlying rcl guard condition structure.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
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:27
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:24
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:441