From 0997ab23a4f72e7759d185ea746143b28aa83fbe Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 20 Jan 2015 17:12:44 -0800 Subject: [PATCH] GCS_MAVLink: merge upstream changes to common.xml --- .../message_definitions/ardupilotmega.xml | 14 +++++ .../message_definitions/common.xml | 58 +++++++++++++------ 2 files changed, 53 insertions(+), 19 deletions(-) diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml index 255fdb82da..d6789700f0 100644 --- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml +++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml @@ -465,5 +465,19 @@ Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + + Status of third AHRS filter if available. This is for ANU research group (Ali and Sean) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Altitude (MSL) + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + test variable1 + test variable2 + test variable3 + test variable4 + + diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index a0aee14429..b83ace62ea 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -429,8 +429,8 @@ Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) - - Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. + + Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. @@ -444,7 +444,7 @@ Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. - + Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. @@ -578,7 +578,7 @@ Latitude Longitude Altitude - + Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. Empty @@ -804,7 +804,7 @@ Latitude Longitude Empty - + Mission command to perform a landing from a rally point. Break altitude (meters) @@ -961,9 +961,9 @@ set limits for external control timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout - absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit + absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit - horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit + horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit Empty Empty Empty @@ -1088,7 +1088,7 @@ Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will. Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT - Altitude, in meters WGS84 + Altitude, in meters AMSL Control the payload deployment. @@ -1554,12 +1554,12 @@ 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). + NOT the global position estimate of the system, 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, 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) + Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX @@ -1653,7 +1653,7 @@ Timestamp (milliseconds since system boot) Latitude, expressed as * 1E7 Longitude, expressed as * 1E7 - Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL) + Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) Altitude above ground in meters, expressed as * 1000 (millimeters) Ground X Speed (Latitude), expressed as m/s * 100 Ground Y Speed (Longitude), expressed as m/s * 100 @@ -1780,13 +1780,25 @@ System ID Latitude (WGS84), in degrees * 1E7 Longitude (WGS84, in degrees * 1E7 - Altitude (WGS84), in meters * 1000 (positive for up) + Altitude (AMSL), in meters * 1000 (positive for up) Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position Latitude (WGS84), in degrees * 1E7 Longitude (WGS84), in degrees * 1E7 - Altitude (WGS84), in meters * 1000 (positive for up) + Altitude (AMSL), in meters * 1000 (positive for up) + + + Bind a RC channel to a parameter. The parameter should change accoding to the RC channel value. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + Initial parameter value + Scale, maps the RC range [-1, 1] to a parameter value + Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations. @@ -2054,7 +2066,7 @@ Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate X Position in WGS84 frame in 1e7 * meters Y Position in WGS84 frame in 1e7 * meters - Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT X velocity in NED frame in meter / s Y velocity in NED frame in meter / s Z velocity in NED frame in meter / s @@ -2071,7 +2083,7 @@ Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate X Position in WGS84 frame in 1e7 * meters Y Position in WGS84 frame in 1e7 * meters - Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT X velocity in NED frame in meter / s Y velocity in NED frame in meter / s Z velocity in NED frame in meter / s @@ -2292,7 +2304,7 @@ 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. Latitude (WGS84), in degrees * 1E7 Longitude (WGS84), in degrees * 1E7 - Altitude (WGS84), in meters * 1000 (positive for up) + Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 GPS ground speed (m/s * 100). If unknown, set to: 65535 @@ -2402,7 +2414,7 @@ 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) + Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX @@ -2533,8 +2545,16 @@ Version and capability of autopilot software bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - Firmware version number - Custom version field, commonly the first 8 bytes (16 characters) of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + Firmware version number + Middleware version number + Operating system version number + HW / board version (last 8 bytes should be silicon ID, if any) + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + ID of the board vendor + ID of the product + UID if provided by hardware