diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index d492cf3c21..cab77fd1b0 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -1294,7 +1294,7 @@ The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). Timestamp (microseconds since UNIX epoch or microseconds since system boot) - 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. Latitude (WGS84), in degrees * 1E7 Longitude (WGS84), in degrees * 1E7 Altitude (WGS84), in meters * 1000 (positive for up) @@ -2087,7 +2087,7 @@ Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS frame). Timestamp (microseconds since UNIX epoch or microseconds since system boot) - 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. Latitude (WGS84), in degrees * 1E7 Longitude (WGS84), in degrees * 1E7 Altitude (WGS84), in meters * 1000 (positive for up) @@ -2114,7 +2114,39 @@ how many bytes in this transfer serial data - + + RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting + Time since boot of last baseline message received in ms. + Identification of connected RTK receiver. + GPS Week Number of last baseline + GPS Time of Week of last baseline + GPS-specific health report for RTK data. + Rate of baseline messages being received by GPS, in HZ + Current number of sats used for RTK calculation. + Coordinate system of baseline. 0 == ECEF, 1 == NED + Current baseline in ECEF x or NED north component in mm. + Current baseline in ECEF y or NED east component in mm. + Current baseline in ECEF z or NED down component in mm. + Current estimate of baseline accuracy. + Current number of integer ambiguity hypotheses. + + + RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting + Time since boot of last baseline message received in ms. + Identification of connected RTK receiver. + GPS Week Number of last baseline + GPS Time of Week of last baseline + GPS-specific health report for RTK data. + Rate of baseline messages being received by GPS, in HZ + Current number of sats used for RTK calculation. + Coordinate system of baseline. 0 == ECEF, 1 == NED + Current baseline in ECEF x or NED north component in mm. + Current baseline in ECEF y or NED east component in mm. + Current baseline in ECEF z or NED down component in mm. + Current estimate of baseline accuracy. + Current number of integer ambiguity hypotheses. + + 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) Width of a matrix or image