rclpy.wait_for_message module

rclpy.wait_for_message.wait_for_message(msg_type: Type[MsgT], node: Node, topic: str, *, qos_profile: rclpy.qos.QoSProfile | int = 1, time_to_wait: int | float = -1) Tuple[Literal[True], MsgT] | Tuple[Literal[False], None]

Wait for the next incoming message.

Parameters:
  • msg_type – message type

  • node – node to initialize the subscription on

  • topic – topic name to wait for message

  • qos_profile – QoS profile to use for the subscription

  • time_to_wait – seconds to wait before returning

Returns:

(True, msg) if a message was successfully received, (False, None) if message could not be obtained or shutdown was triggered asynchronously on the context.