ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
wait_for_message.hpp
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 #ifndef RCLCPP__WAIT_FOR_MESSAGE_HPP_
16 #define RCLCPP__WAIT_FOR_MESSAGE_HPP_
17 
18 #include <future>
19 #include <memory>
20 #include <string>
21 
22 #include "rcpputils/scope_exit.hpp"
23 
24 #include "rclcpp/node.hpp"
25 #include "rclcpp/visibility_control.hpp"
26 #include "rclcpp/wait_set.hpp"
27 #include "rclcpp/qos.hpp"
28 
29 namespace rclcpp
30 {
32 
43 template<class MsgT, class Rep = int64_t, class Period = std::milli>
45  MsgT & out,
46  std::shared_ptr<rclcpp::Subscription<MsgT>> subscription,
47  std::shared_ptr<rclcpp::Context> context,
48  std::chrono::duration<Rep, Period> time_to_wait = std::chrono::duration<Rep, Period>(-1))
49 {
50  auto gc = std::make_shared<rclcpp::GuardCondition>(context);
51  auto shutdown_callback_handle = context->add_on_shutdown_callback(
52  [weak_gc = std::weak_ptr<rclcpp::GuardCondition>{gc}]() {
53  auto strong_gc = weak_gc.lock();
54  if (strong_gc) {
55  strong_gc->trigger();
56  }
57  });
58 
59  rclcpp::WaitSet wait_set;
60  wait_set.add_subscription(subscription);
61  RCPPUTILS_SCOPE_EXIT(wait_set.remove_subscription(subscription); );
62  wait_set.add_guard_condition(gc);
63  auto ret = wait_set.wait(time_to_wait);
64  if (ret.kind() != rclcpp::WaitResultKind::Ready) {
65  return false;
66  }
67 
68  if (wait_set.get_rcl_wait_set().guard_conditions[0]) {
69  return false;
70  }
71 
73  if (!subscription->take(out, info)) {
74  return false;
75  }
76 
77  return true;
78 }
79 
81 
92 template<class MsgT, class Rep = int64_t, class Period = std::milli>
94  MsgT & out,
95  rclcpp::Node::SharedPtr node,
96  const std::string & topic,
97  std::chrono::duration<Rep, Period> time_to_wait = std::chrono::duration<Rep, Period>(-1),
98  const rclcpp::QoS & qos = rclcpp::SystemDefaultsQoS())
99 {
100  auto sub = node->create_subscription<MsgT>(topic, qos, [](const std::shared_ptr<const MsgT>) {});
101  return wait_for_message<MsgT, Rep, Period>(
102  out, sub, node->get_node_options().context(), time_to_wait);
103 }
104 
105 } // namespace rclcpp
106 
107 #endif // RCLCPP__WAIT_FOR_MESSAGE_HPP_
Additional meta data about messages taken from subscriptions.
Encapsulation of Quality of Service settings.
Definition: qos.hpp:111
Subscription implementation, templated on the type of message this subscription receives.
Encapsulates sets of waitable items which can be waited on as a group.
void add_guard_condition(std::shared_ptr< rclcpp::GuardCondition > guard_condition)
Add a guard condition to this wait set.
void add_subscription(std::shared_ptr< rclcpp::SubscriptionBase > subscription, rclcpp::SubscriptionWaitSetMask mask={})
Add a subscription to this wait set.
void remove_subscription(std::shared_ptr< rclcpp::SubscriptionBase > subscription, rclcpp::SubscriptionWaitSetMask mask={})
Remove a subscription from this wait set.
RCUTILS_WARN_UNUSED WaitResult< WaitSetTemplate > wait(std::chrono::duration< Rep, Period > time_to_wait=std::chrono::duration< Rep, Period >(-1))
Wait for any of the entities in the wait set to be ready, or a period of time to pass.
const rcl_wait_set_t & get_rcl_wait_set() const
Return the internal rcl wait set object.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
bool wait_for_message(MsgT &out, std::shared_ptr< rclcpp::Subscription< MsgT >> subscription, std::shared_ptr< rclcpp::Context > context, std::chrono::duration< Rep, Period > time_to_wait=std::chrono::duration< Rep, Period >(-1))
Wait for the next incoming message.
const rcl_guard_condition_t ** guard_conditions
Storage for guard condition pointers.
Definition: wait.h:48