From 47ead18607871b6bb0ba2e89d987c7efe72bf6ae Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Mon, 4 Nov 2019 09:40:51 +1100 Subject: [PATCH] Clarify target address for requested message/stream (#1249) --- message_definitions/v1.0/common.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index 8ff64735d0..24d7eb6305 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -1831,11 +1831,13 @@ Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM. The MAVLink message ID The interval between two messages. Set to -1 to disable and 0 to request default rate. + Target address of message stream (if message has target address fields). 0: Flight-stack default (recommended), 1: address of requestor, 2: broadcast. Request the target system(s) emit a single instance of a specified message (i.e. a "one-shot" version of MAV_CMD_SET_MESSAGE_INTERVAL). The MAVLink message ID of the requested message. Index id (if appropriate). The use of this parameter (if any), must be defined in the requested message. + Target address for requested message (if message has target address fields). 0: Flight-stack default, 1: address of requestor, 2: broadcast. Request MAVLink protocol version compatibility