Template Function rclcpp::wait_for_message(MsgT&, rclcpp::Node::SharedPtr, const std::string&, std::chrono::duration<Rep, Period>)

Function Documentation

template<class MsgT, class Rep = int64_t, class Period = std::milli>
bool rclcpp::wait_for_message(MsgT &out, rclcpp::Node::SharedPtr node, const std::string &topic, std::chrono::duration<Rep, Period> time_to_wait = std::chrono::duration<Rep, Period>(-1))

Wait for the next incoming message.

Wait for the next incoming message to arrive on a specified topic before the specified timeout.

Parameters:
  • out[out] is the message to be filled when a new message is arriving.

  • node[in] the node pointer to initialize the subscription on.

  • topic[in] the topic to wait for messages.

  • time_to_wait[in] parameter specifying the timeout before returning.

Returns:

true if a message was successfully received, false if message could not be obtained or shutdown was triggered asynchronously on the context.