1515#ifndef RCLCPP__WAIT_FOR_MESSAGE_HPP_
1616#define RCLCPP__WAIT_FOR_MESSAGE_HPP_
1717
18+ #include < future>
1819#include < memory>
1920#include < string>
2021
2324#include " rclcpp/node.hpp"
2425#include " rclcpp/visibility_control.hpp"
2526#include " rclcpp/wait_set.hpp"
27+ #include " rclcpp/qos.hpp"
2628
2729namespace rclcpp
2830{
@@ -79,10 +81,11 @@ bool wait_for_message(
7981/* *
8082 * Wait for the next incoming message to arrive on a specified topic before the specified timeout.
8183 *
82- * \param[out] out is the message to be filled when a new message is arriving.
84+ * \param[out] out is the message to be filled when a new message is arriving
8385 * \param[in] node the node pointer to initialize the subscription on.
8486 * \param[in] topic the topic to wait for messages.
8587 * \param[in] time_to_wait parameter specifying the timeout before returning.
88+ * \param[in] qos parameter specifying QoS settings for the subscription.
8689 * \return true if a message was successfully received, false if message could not
8790 * be obtained or shutdown was triggered asynchronously on the context.
8891 */
@@ -91,9 +94,10 @@ bool wait_for_message(
9194 MsgT & out,
9295 rclcpp::Node::SharedPtr node,
9396 const std::string & topic,
94- std::chrono::duration<Rep, Period> time_to_wait = std::chrono::duration<Rep, Period>(-1 ))
97+ std::chrono::duration<Rep, Period> time_to_wait = std::chrono::duration<Rep, Period>(-1 ),
98+ const rclcpp::QoS & qos = rclcpp::SystemDefaultsQoS())
9599{
96- auto sub = node->create_subscription <MsgT>(topic, 1 , [](const std::shared_ptr<const MsgT>) {});
100+ auto sub = node->create_subscription <MsgT>(topic, qos , [](const std::shared_ptr<const MsgT>) {});
97101 return wait_for_message<MsgT, Rep, Period>(
98102 out, sub, node->get_node_options ().context (), time_to_wait);
99103}
0 commit comments