From f9d5715754f8a6b5889c9a6e5dd92a71c5f3cf86 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 14 Aug 2014 11:01:41 +1000 Subject: [PATCH] GCS_MAVLink: merged latest upstream common.xml --- .../message_definitions/common.xml | 508 +++++++++++------- 1 file changed, 309 insertions(+), 199 deletions(-) diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index 3e2e136de7..e88891efa1 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -416,12 +416,6 @@ Local coordinate frame, Z-down (x: east, y: north, z: up) - - Global coordinate frame with some fields as scaled integers, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL). Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations. - - - Global coordinate frame with some fields as scaled integers, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations. - Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. @@ -432,7 +426,7 @@ Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. - 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, second value / y: longitude, third value / z: positive altitude 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, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. @@ -1010,6 +1004,62 @@ 0:Spektrum 0:Spektrum DSM2, 1:Spektrum DSMX + + Start image capture sequence + Duration between two consecutive pictures (in seconds) + Number of images to capture total - 0 for unlimited capture + Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc) + + + + Stop image capture sequence + Reserved + Reserved + + + + Starts video capture + Camera ID (0 for all cameras), 1 for first, 2 for second, etc. + Frames per second + Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc) + + + + Stop the current video capture + Reserved + Reserved + + + + Create a panorama at the current position + Viewing angle horizontal of the panorama + Viewing angle vertical of panorama + + + + + + + Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. + Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list. + Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will. + Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will. + 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 + + + Control the payload deployment. + Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + Data stream IDs. A data stream is not a fixed set of messages, but rather a @@ -1282,6 +1332,93 @@ Ultrasound altimeter, e.g. MaxBotix units + + Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. + + Autopilot supports MISSION float message type. + + + Autopilot supports the new param float message type. + + + Autopilot supports MISSION_INT scaled integer message type. + + + Autopilot supports COMMAND_INT scaled integer message type. + + + Autopilot supports the new param union message type. + + + Autopilot supports the new param union message type. + + + Autopilot supports commanding attitude offboard. + + + Autopilot supports commanding position and velocity targets in local NED frame. + + + Autopilot supports commanding position and velocity targets in global scaled integers. + + + Autopilot supports terrain protocol / data handling. + + + + Enumeration of estimator types + + This is a naive estimator without any real covariance feedback. + + + Computer vision based estimate. Might be up to scale. + + + Visual-inertial estimate. + + + Plain GPS estimate. + + + Estimator integrating GPS and inertial sensing. + + + + Enumeration of battery types + + Not specified. + + + Lithium polymere battery + + + Lithium ferrite battery + + + Lithium-ION battery + + + Nickel metal hydride battery + + + + Enumeration of battery functions + + Lithium polymere battery + + + Battery supports all flight systems + + + Battery for the propulsion system + + + Avionics battery + + + Payload battery + + @@ -1345,6 +1482,7 @@ The new base mode The new autopilot-specific mode. This field can be ignored by an autopilot. + Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. System ID @@ -1448,7 +1586,7 @@ Yaw angular speed (rad/s) - The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). Timestamp (milliseconds since system boot) Quaternion component 1, w (1 in null-rotation) Quaternion component 2, x (0 in null-rotation) @@ -1609,40 +1747,6 @@ Longitude (WGS84), in degrees * 1E7 Altitude (WGS84), in meters * 1000 (positive for up) - - Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/MISSION planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message. - System ID - Component ID - Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU - x position - y position - z position - Desired yaw angle - - - Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS. - Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU - x position - y position - z position - Desired yaw angle - - - Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS. - Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - Altitude (WGS84), in meters * 1000 (positive for up) - Desired yaw angle in degrees * 100 - - - Set the current global position setpoint. - Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - Altitude (WGS84), in meters * 1000 (positive for up) - Desired yaw angle in degrees * 100 - 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. System ID @@ -1665,56 +1769,14 @@ y position 2 / Longitude 2 z position 2 / Altitude 2 - - Set roll, pitch and yaw. - System ID - Component ID - Desired roll angle in radians - Desired pitch angle in radians - Desired yaw angle in radians - Collective thrust, normalized to 0 .. 1 - - - Set roll, pitch and yaw. - System ID - Component ID - Desired roll angular speed in rad/s - Desired pitch angular speed in rad/s - Desired yaw angular speed in rad/s - Collective thrust, normalized to 0 .. 1 - - - Setpoint in roll, pitch, yaw currently active on the system. - Timestamp in milliseconds since system boot - Desired roll angle in radians - Desired pitch angle in radians - Desired yaw angle in radians - Collective thrust, normalized to 0 .. 1 - - - Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system. - Timestamp in milliseconds since system boot - Desired roll angular speed in rad/s - Desired pitch angular speed in rad/s - Desired yaw angular speed in rad/s - Collective thrust, normalized to 0 .. 1 - - - Setpoint in the four motor speeds - System ID of the system that should set these motor commands - Front motor in + configuration, front left motor in x configuration - Right motor in + configuration, front right motor in x configuration - Back motor in + configuration, back right motor in x configuration - Left motor in + configuration, back left motor in x configuration - - - Setpoint for up to four quadrotors in a group / wing - ID of the quadrotor group (0 - 255, up to 256 groups supported) - ID of the flight mode (0 - 255, up to 256 modes supported) - Desired roll angle in radians +-PI (+-INT16_MAX) - Desired pitch angle in radians +-PI (+-INT16_MAX) - Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) - Collective thrust, scaled to uint16 (0..UINT16_MAX) + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + Timestamp (milliseconds since system boot) + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + Attitude covariance Outputs of the APM navigation controller. The primary use of this message is to check the response and signs of the controller before actual flight and to assist with tuning controller parameters. @@ -1727,29 +1789,32 @@ Current airspeed error in meters/second Current crosstrack error on x-y plane in meters - - Setpoint for up to four quadrotors in a group / wing - ID of the quadrotor group (0 - 255, up to 256 groups supported) - ID of the flight mode (0 - 255, up to 256 modes supported) - RGB red channel (0-255) - RGB green channel (0-255) - RGB blue channel (0-255) - Desired roll angle in radians +-PI (+-INT16_MAX) - Desired pitch angle in radians +-PI (+-INT16_MAX) - Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) - Collective thrust, scaled to uint16 (0..UINT16_MAX) - - - Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle. - x position error - y position error - z position error - roll error (radians) - pitch error (radians) - yaw error (radians) - x velocity - y velocity - z velocity + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset. + Timestamp (milliseconds since system boot) + Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + Class id of the estimator this estimate originated from. + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Altitude in meters, expressed as * 1000 (millimeters), above MSL + Altitude above ground in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s + Ground Y Speed (Longitude), expressed as m/s + Ground Z Speed (Altitude), expressed as m/s + Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot) + Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + Class id of the estimator this estimate originated from. + X Position + Y Position + Z Position + X Speed + Y Speed + Z Speed + Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. @@ -1809,6 +1874,24 @@ RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See alsohttp://qgroundcontrol.org/mavlink/waypoint_protocol. + System ID + Component ID + Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + Metrics typically displayed on a HUD for fixed wing aircraft Current airspeed in m/s @@ -1818,6 +1901,22 @@ Current altitude (MSL), in meters Current climb rate in meters/second + + Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value. + System ID + Component ID + The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + Send a command with up to seven parameters to the MAV System which should execute the command @@ -1837,14 +1936,6 @@ Command ID, as defined by MAV_CMD enum. See MAV_RESULT enum - - Setpoint in roll, pitch, yaw rates and thrust currently active on the system. - Timestamp in milliseconds since system boot - Desired roll rate in radians per second - Desired pitch rate in radians per second - Desired yaw rate in radians per second - Collective thrust, normalized to 0 .. 1 - Setpoint in roll, pitch, yaw and thrust from the operator Timestamp in milliseconds since system boot @@ -1855,11 +1946,21 @@ Flight mode switch position, 0.. 255 Override mode switch position, 0.. 255 - + Set the vehicle attitude and body angular rates. Timestamp in milliseconds since system boot System ID Component ID + Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + Body roll rate in radians per second + Body roll rate in radians per second + Body roll rate in radians per second + Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + + + Set the vehicle attitude and body angular rates. + Timestamp in milliseconds since system boot Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) Body roll rate in radians per second @@ -1867,12 +1968,12 @@ Body roll rate in radians per second Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - + Set vehicle position, velocity and acceleration setpoint in local frame. Timestamp in milliseconds since system boot System ID Component ID - Valid options are: MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_OFFSET_NED = 5, MAV_FRAME_BODY_NED = 6, MAV_FRAME_BODY_OFFSET_NED = 7 + Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 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 X Position in NED frame in meters Y Position in NED frame in meters @@ -1884,15 +1985,46 @@ Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - + + Set vehicle position, velocity and acceleration setpoint in local frame. + Timestamp in milliseconds since system boot + Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + 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 + X Position in NED frame in meters + Y Position in NED frame in meters + Z Position in NED frame in meters (note, altitude is negative in NED) + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + + Set vehicle position, velocity and acceleration setpoint in the WGS84 coordinate system. Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. System ID Component ID + Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + 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 + 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 + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + + + Set vehicle position, velocity and acceleration setpoint in the WGS84 coordinate system. + Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 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 X Position in WGS84 frame in 1e7 * meters Y Position in WGS84 frame in 1e7 * meters - Altitude in WGS84, not AMSL + Altitude in meters in WGS84 altitude, not AMSL 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 @@ -2086,25 +2218,13 @@ count of error corrected packets - - Begin file transfer - Unique transfer ID - Destination path - Transfer direction: 0: from requester, 1: to requester - File size in bytes - RESERVED - - - Get directory listing - Unique transfer ID - Directory path to list - RESERVED - - - File transfer result - Unique transfer ID - 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device - + + File transfer message + Network ID (0 for broadcast) + System ID (0 for broadcast) + Component ID (0 for broadcast) + Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + 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). @@ -2205,7 +2325,7 @@ System ID Component ID - + data for injecting into the onboard GPS (used for DGPS) System ID Component ID @@ -2273,20 +2393,20 @@ 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 - Height of a matrix or image - number of packets beeing sent (set on ACK only) - payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - JPEG quality out of [1,100] - - - sequence number (starting with 0 on every transmission) - image data bytes - + + + 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 + Height of a matrix or image + number of packets beeing sent (set on ACK only) + payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + JPEG quality out of [1,100] + + + sequence number (starting with 0 on every transmission) + image data bytes + Time since system boot Minimum distance the sensor can measure in centimeters @@ -2327,43 +2447,33 @@ Number of 4x4 terrain blocks waiting to be received or read from disk Number of 4x4 terrain blocks in memory - - Transmitte battery informations for a accu pack. - Accupack ID - Battery voltage of cell 1, in millivolts (1 = 1 millivolt) - Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell - Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell - Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell - Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell - Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell - Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - - - Set the 8 DOF setpoint for a controller. - System ID - Value 1 - Value 2 - Value 3 - Value 4 - Value 5 - Value 6 - Value 7 - Value 8 - - - Set the 6 DOF setpoint for a attitude and position controller. - System ID - Translational Component in x - Translational Component in y - Translational Component in z - Rotational Component in x - Rotational Component in y - Rotational Component in z - - + + Battery information + Battery ID + Function of the battery + Type (chemistry) of the battery + Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + Battery voltage of cells, in millivolts (1 = 1 millivolt) + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + + + 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. + + + + Message implementing parts of the V2 payload specs in V1 frames for transitional support. + Network ID (0 for broadcast) + System ID (0 for broadcast) + Component ID (0 for broadcast) + A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. Starting address of the debug variables