Template Function rclcpp::wait_for_message(MsgT&, std::shared_ptr<rclcpp::Subscription<MsgT>>, std::shared_ptr<rclcpp::Context>, 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, 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.

Given an already initialized subscription, wait for the next incoming message to arrive before the specified timeout.

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

  • subscription[in] shared pointer to a previously initialized subscription.

  • context[in] shared pointer to a context to watch for SIGINT requests.

  • 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.