From 14b3696959876b34e890ec22886d917559ebaeeb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 4 Apr 2014 13:54:41 +1100 Subject: [PATCH] GCS_MAVLink: added SERIAL_CONTROL message definition will be used for on-board radio and GPS firmware update and control over USB --- .../message_definitions/common.xml | 42 +++++++++++++++++++ 1 file changed, 42 insertions(+) diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index 09a704da22..29b3473bee 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -1007,6 +1007,39 @@ Power status has changed since boot + + SERIAL_CONTROL device types + + First telemetry port + + + Second telemetry port + + + First GPS port + + + Second GPS port + + + + SERIAL_CONTROL flags (bitmask) + + Set if this is a reply + + + Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message + + + Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set + + + Block on writes to the serial port + + + Send multiple replies until port is drained + + @@ -1913,6 +1946,15 @@ servo rail voltage in millivolts power supply status flags (see MAV_POWER_STATUS enum) + + Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate. + See SERIAL_CONTROL_DEV enum + See SERIAL_CONTROL_FLAG enum + Timeout for reply data in milliseconds + Baudrate of transfer. Zero means no change. + how many bytes in this transfer + serial data + type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) total data size in bytes (set on ACK only)