From 66098988f8534cbdecf84d0c713cc66203667da9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=B8ren=20Friis?= Date: Thu, 23 Sep 2021 02:19:06 +0300 Subject: [PATCH] Update OpenDroneID messages to be compliant with ASTM v1.1 (#1701) The ASTM F3411 Specification for Remote ID and Tracking has been updated to version 1.1. Change the related MAVLink messages to be compliant. - Add new Basic ID type for Specific Session ID - Support using 0xFFFF as indicator of invalid timestamp value - Support new System field for Operator Geometric Altitude - Support new Authentication features - Add new authentication type for specific authentication - Allow up to 16 pages of authentication data - Rename PageCount to LastPageIndex - Decrease maximum message pack size Signed-off-by: Soren Friis --- message_definitions/v1.0/common.xml | 20 ++++++++++++++------ 1 file changed, 14 insertions(+), 6 deletions(-) diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index aad61ca72a..8bea141bd7 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -3675,6 +3675,9 @@ UTM (Unmanned Traffic Management) assigned UUID (RFC4122). + + A 20 byte ID for a specific flight/session. The exact ID type is indicated by the first byte of uas_id and these type values are managed by ICAO. + @@ -3895,6 +3898,9 @@ Authentication is provided by Network Remote ID. + + The exact authentication type is indicated by the first byte of authentication_data and these type values are managed by ICAO. + @@ -6700,7 +6706,7 @@ The accuracy of the vertical position. The accuracy of the barometric altitude. The accuracy of the horizontal and vertical speed. - Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. + Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF. The accuracy of the timestamps. @@ -6711,9 +6717,9 @@ Component ID (0 for broadcast). Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. Indicates the type of authentication. - Allowed range is 0 - 4. - This field is only present for page 0. Allowed range is 0 - 5. - This field is only present for page 0. Total bytes of authentication_data from all data pages. Allowed range is 0 - 109 (17 + 23*4). + Allowed range is 0 - 15. + This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. + This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field. @@ -6744,6 +6750,7 @@ Area Operations Floor relative to WGS84. If unknown: -1000 m. When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA. When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA. + Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. @@ -6762,9 +6769,10 @@ An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above messages descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking. System ID (0 for broadcast). Component ID (0 for broadcast). + Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specificed to have this length. - Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 10. - Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field. + Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9. + Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field. Temperature and humidity from hygrometer.