15 #ifndef RCLCPP__WAIT_FOR_MESSAGE_HPP_
16 #define RCLCPP__WAIT_FOR_MESSAGE_HPP_
22 #include "rcpputils/scope_exit.hpp"
24 #include "rclcpp/node.hpp"
25 #include "rclcpp/visibility_control.hpp"
26 #include "rclcpp/wait_set.hpp"
27 #include "rclcpp/qos.hpp"
43 template<
class MsgT,
class Rep =
int64_t,
class Period = std::milli>
47 std::shared_ptr<rclcpp::Context> context,
48 std::chrono::duration<Rep, Period> time_to_wait = std::chrono::duration<Rep, Period>(-1))
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();
63 auto ret = wait_set.
wait(time_to_wait);
64 if (ret.kind() != rclcpp::WaitResultKind::Ready) {
73 if (!subscription->take(out, info)) {
92 template<
class MsgT,
class Rep =
int64_t,
class Period = std::milli>
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),
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);
Additional meta data about messages taken from subscriptions.
Encapsulation of Quality of Service settings.
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.