From f61aa4d68c90219408f971378f7699da76b8f6e3 Mon Sep 17 00:00:00 2001 From: "tridge60@gmail.com" Date: Mon, 5 Sep 2011 06:19:39 +0000 Subject: [PATCH] updated XML MAVLink definitions git-svn-id: https://arducopter.googlecode.com/svn/trunk@3272 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- .../message_definitions/ardupilotmega.xml | 6 + .../message_definitions/common.xml | 144 +++--- .../message_definitions/pixhawk.xml | 475 ++++++++---------- 3 files changed, 306 insertions(+), 319 deletions(-) diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml index d7d6aaacd4..3ddd5a1e77 100644 --- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml +++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml @@ -35,5 +35,11 @@ magnetometer Z offset + + state of APM memory + heap top + free memory + + diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index 62de770bc7..dd4ea84430 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -261,22 +261,21 @@ Empty Empty - - - Sets the region of interest (ROI) for a sensor set or the + + Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various devices such as cameras. - Region of interest mode. (see MAV_ROI enum) - Waypoint index/ target ID. (see MAV_ROI enum) - ROI index (allows a vehicle to manage multiple cameras etc.) - Empty - x the location of the fixed ROI (see MAV_FRAME) - y - z - - + Region of interest mode. (see MAV_ROI enum) + Waypoint index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple cameras etc.) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + NOP - This command is only used to mark the upper limit of the DO commands in the enumeration Empty Empty @@ -340,28 +339,28 @@ Dependent on the autopilot - - The ROI (region of interest) for the vehicle. This can be + + The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI). - - No region of interest. - - - Point toward next waypoint. - - - Point toward given waypoint. - - - Point toward fixed location. - - - Point toward of given id. - - - + + No region of interest. + + + Point toward next waypoint. + + + Point toward given waypoint. + + + Point toward fixed location. + + + Point toward of given id. + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). @@ -746,7 +745,7 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se Setpoint in roll, pitch, yaw currently active on the system. - Timestamp in milliseconds since system boot + Timestamp in micro seconds since unix epoch Desired roll angle in radians Desired pitch angle in radians Desired yaw angle in radians @@ -754,7 +753,7 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system. - Timestamp in milliseconds since system boot + Timestamp in micro seconds since unix epoch Desired roll angular speed in rad/s Desired pitch angular speed in rad/s Desired yaw angular speed in rad/s @@ -802,38 +801,38 @@ of the controller before actual flight and to assist with tuning controller para Update rate in Hertz 1 to start sending, 0 to stop sending. - - This packet is useful for high throughput + + This packet is useful for high throughput applications such as hardware in the loop simulations. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Roll angle (rad) - Pitch angle (rad) - Yaw angle (rad) - Roll angular speed (rad/s) - Pitch angular speed (rad/s) - Yaw angular speed (rad/s) - Latitude, expressed as * 1E7 - Longitude, expressed as * 1E7 - Altitude in meters, expressed as * 1000 (millimeters) - Ground X Speed (Latitude), expressed as m/s * 100 - Ground Y Speed (Longitude), expressed as m/s * 100 - Ground Z Speed (Altitude), expressed as m/s * 100 - X acceleration (mg) - Y acceleration (mg) - Z acceleration (mg) - - - Hardware in the loop control outputs - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Control output -3 .. 1 - Control output -1 .. 1 - Control output -1 .. 1 - Throttle 0 .. 1 - System mode (MAV_MODE) - Navigation mode (MAV_NAV_MODE) - - + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + Hardware in the loop control outputs + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Control output -3 .. 1 + Control output -1 .. 1 + Control output -1 .. 1 + Throttle 0 .. 1 + System mode (MAV_MODE) + Navigation mode (MAV_NAV_MODE) + + The system to be controlled roll pitch @@ -891,6 +890,25 @@ of the controller before actual flight and to assist with tuning controller para Current airspeed in m/s 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + + Optical flow from a flow sensor (e.g. optical mouse sensor) + Timestamp (UNIX) + Sensor ID + Flow in pixels in x-sensor direction + Flow in pixels in y-sensor direction + Optical flow quality / confidence. 0: bad, 255: maximum quality + Ground distance in meters + + + Object has been detected + Timestamp in milliseconds since system boot + Object ID + Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal + Name of the object as defined by the detector + Detection quality / confidence. 0: bad, 255: maximum confidence + Angle of the object with respect to the body frame in NED coordinates in radians. 0: front + Ground distance in meters + Name diff --git a/libraries/GCS_MAVLink/message_definitions/pixhawk.xml b/libraries/GCS_MAVLink/message_definitions/pixhawk.xml index 51b7db1a3e..a9a51d6989 100644 --- a/libraries/GCS_MAVLink/message_definitions/pixhawk.xml +++ b/libraries/GCS_MAVLink/message_definitions/pixhawk.xml @@ -1,264 +1,227 @@ - + - common.xml - - - - Content Types for data transmission handshake - - - - - - - - - - - - The system to be controlled - roll - pitch - yaw - thrust - roll control enabled auto:0, manual:1 - pitch auto:0, manual:1 - yaw auto:0, manual:1 - thrust auto:0, manual:1 - - - - Camera id - Camera mode: 0 = auto, 1 = manual - Trigger pin, 0-3 for PtGrey FireFly - Shutter interval, in microseconds - Exposure time, in microseconds - Camera gain - - - - Timestamp - IMU seq - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - Local frame Z coordinate (height over ground) - GPS X coordinate - GPS Y coordinate - Global frame altitude - Ground truth X - Ground truth Y - Ground truth Z - - - - 0 to disable, 1 to enable - - - - Camera id - Camera # (starts with 0) - Timestamp - Until which timestamp this buffer will stay valid - The image sequence number - Position of the image in the buffer, starts with 0 - Image width - Image height - Image depth - Image channels - Shared memory area key - Exposure time, in microseconds - Camera gain - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - Local frame Z coordinate (height over ground) - GPS X coordinate - GPS Y coordinate - Global frame altitude - Ground truth X - Ground truth Y - Ground truth Z - - - - Timestamp (milliseconds) - Global X position - Global Y position - Global Z position - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - - - - Timestamp (milliseconds) - Global X position - Global Y position - Global Z position - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - - - - Timestamp (milliseconds) - Global X speed - Global Y speed - Global Z speed - - - - Message sent to the MAV to set a new position as reference for the controller - System ID - Component ID - ID of waypoint, 0 for plain position - x position - y position - z position - yaw orientation in radians, 0 = NORTH - - - - Message sent to the MAV to set a new offset from the currently controlled position - System ID - Component ID - x position offset - y position offset - z position offset - yaw orientation offset in radians, 0 = NORTH - - - - - ID of waypoint, 0 for plain position - x position - y position - z position - yaw orientation in radians, 0 = NORTH - - - - ID - x position - y position - z position - roll orientation - pitch orientation - yaw orientation - - - - ADC1 (J405 ADC3, LPC2148 AD0.6) - ADC2 (J405 ADC5, LPC2148 AD0.2) - ADC3 (J405 ADC6, LPC2148 AD0.1) - ADC4 (J405 ADC7, LPC2148 AD1.3) - Battery voltage - Temperature (degrees celcius) - Barometric pressure (hecto Pascal) - - - - Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - Number of I2C errors since startup - Number of I2C errors since startup - Number of I2C errors since startup - Number of I2C errors since startup - Number of I2C errors since startup - - - - Watchdog ID - Number of processes - - - - Watchdog ID - Process ID - Process name - Process arguments - Timeout (seconds) - - - - Watchdog ID - Process ID - Is running / finished / suspended / crashed - Is muted - PID - Number of crashes - - - - Target system ID - Watchdog ID - Process ID - Command ID - - - - 0: Pattern, 1: Letter - Confidence of detection - Pattern file name - Accepted as true detection, 0 no, 1 yes - - - - Notifies the operator about a point of interest (POI). This can be anything detected by the + common.xml + + + Content Types for data transmission handshake + + + + + + + + Camera id + Camera mode: 0 = auto, 1 = manual + Trigger pin, 0-3 for PtGrey FireFly + Shutter interval, in microseconds + Exposure time, in microseconds + Camera gain + + + Timestamp + IMU seq + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + Local frame Z coordinate (height over ground) + GPS X coordinate + GPS Y coordinate + Global frame altitude + Ground truth X + Ground truth Y + Ground truth Z + + + 0 to disable, 1 to enable + + + Camera id + Camera # (starts with 0) + Timestamp + Until which timestamp this buffer will stay valid + The image sequence number + Position of the image in the buffer, starts with 0 + Image width + Image height + Image depth + Image channels + Shared memory area key + Exposure time, in microseconds + Camera gain + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + Local frame Z coordinate (height over ground) + GPS X coordinate + GPS Y coordinate + Global frame altitude + Ground truth X + Ground truth Y + Ground truth Z + + + Timestamp (milliseconds) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + Timestamp (milliseconds) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + Timestamp (milliseconds) + Global X speed + Global Y speed + Global Z speed + + + Message sent to the MAV to set a new position as reference for the controller + System ID + Component ID + ID of waypoint, 0 for plain position + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + Message sent to the MAV to set a new offset from the currently controlled position + System ID + Component ID + x position offset + y position offset + z position offset + yaw orientation offset in radians, 0 = NORTH + + + + ID of waypoint, 0 for plain position + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + ID + x position + y position + z position + roll orientation + pitch orientation + yaw orientation + + + ADC1 (J405 ADC3, LPC2148 AD0.6) + ADC2 (J405 ADC5, LPC2148 AD0.2) + ADC3 (J405 ADC6, LPC2148 AD0.1) + ADC4 (J405 ADC7, LPC2148 AD1.3) + Battery voltage + Temperature (degrees celcius) + Barometric pressure (hecto Pascal) + + + Watchdog ID + Number of processes + + + Watchdog ID + Process ID + Process name + Process arguments + Timeout (seconds) + + + Watchdog ID + Process ID + Is running / finished / suspended / crashed + Is muted + PID + Number of crashes + + + Target system ID + Watchdog ID + Process ID + Command ID + + + 0: Pattern, 1: Letter + Confidence of detection + Pattern file name + Accepted as true detection, 0 no, 1 yes + + + Notifies the operator about a point of interest (POI). This can be anything detected by the system. This generic message is intented to help interfacing to generic visualizations and to display the POI on a map. - 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - 0: global, 1:local - 0: no timeout, >1: timeout in seconds - X Position - Y Position - Z Position - POI name - - - - Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the + 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + 0: global, 1:local + 0: no timeout, >1: timeout in seconds + X Position + Y Position + Z Position + POI name + + + Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the system. This generic message is intented to help interfacing to generic visualizations and to display the POI on a map. - 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - 0: global, 1:local - 0: no timeout, >1: timeout in seconds - X1 Position - Y1 Position - Z1 Position - X2 Position - Y2 Position - Z2 Position - POI connection name - - - - 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) - 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 - - - - x position in m - y position in m - z position in m - Orientation assignment 0: false, 1:true - Size in pixels - Orientation - Descriptor - Harris operator response at this location - - - + 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + 0: global, 1:local + 0: no timeout, >1: timeout in seconds + X1 Position + Y1 Position + Z1 Position + X2 Position + Y2 Position + Z2 Position + POI connection name + + + 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) + 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 + + + x position in m + y position in m + z position in m + Orientation assignment 0: false, 1:true + Size in pixels + Orientation + Descriptor + Harris operator response at this location + + + The system to be controlled + roll + pitch + yaw + thrust + roll control enabled auto:0, manual:1 + pitch auto:0, manual:1 + yaw auto:0, manual:1 + thrust auto:0, manual:1 + +