From 983ac9cbf498dd2e470702c6e3991b2d2c23926c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 15 May 2014 17:09:45 +1000 Subject: [PATCH] GCS_MAVLink: merge in latest upstream XML changes --- .../message_definitions/ardupilotmega.xml | 161 +++--------------- .../message_definitions/common.xml | 156 +++++++++++++++-- 2 files changed, 167 insertions(+), 150 deletions(-) diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml index 7149894d6b..3e5bd7c395 100644 --- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml +++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml @@ -10,139 +10,20 @@ --> - - - Enumeration of possible mount operation modes - Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization - Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. - Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization - Load neutral position and start RC Roll,Pitch,Yaw control with stabilization - Load neutral position and start to point to Lat,Lon,Alt - - - - - - Mission command to configure an on-board camera controller system. - Modes: P, TV, AV, M, Etc - Shutter speed: Divisor number for one second - Aperture: F stop number - ISO number e.g. 80, 100, 200, Etc - Exposure type enumerator - Command Identity - Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) - - - - Mission command to control an on-board camera controller system. - Session control e.g. show/hide lens - Zoom's absolute position - Zooming step value to offset zoom from the current position - Focus Locking, Unlocking or Re-locking - Shooting Command - Command Identity - Empty - - - - - Mission command to configure a camera or antenna mount - Mount operation mode (see MAV_MOUNT_MODE enum) - stabilize roll? (1 = yes, 0 = no) - stabilize pitch? (1 = yes, 0 = no) - stabilize yaw? (1 = yes, 0 = no) - Empty - Empty - Empty - - - - Mission command to control a camera or antenna mount - pitch(deg*100) or lat, depending on mount mode. - roll(deg*100) or lon depending on mount mode - yaw(deg*100) or alt (in cm) depending on mount mode - Empty - Empty - Empty - Empty - - - - Mission command to set CAM_TRIGG_DIST for this flight - Camera trigger distance (meters) - Empty - Empty - Empty - Empty - Empty - Empty - - - - Mission command to enable the geofence - enable? (0=disable, 1=enable) - Empty - Empty - Empty - Empty - Empty - Empty - - - - Mission command to trigger a parachute - action (0=disable, 1=enable, 2=release, See PARACHUTE_ACTION enum) - Empty - Empty - Empty - Empty - Empty - Empty - - - - Mission command to perform motor test - motor sequence number (a number from 1 to max number of motors on the vehicle) - throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) - throttle - timeout (in seconds) - Empty - Empty - Empty - - - - - - - Disable fenced mode - - - Switched to guided mode to return point (fence point 0) - - - Report fence breach, but don't take action - - - Switched to guided mode to return point (fence point 0) with manual throttle control + + + + Mission command to perform motor test + motor sequence number (a number from 1 to max number of motors on the vehicle) + throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) + throttle + timeout (in seconds) + Empty + Empty + Empty - - - - - No last fence breach - - - Breached minimum altitude - - - Breached maximum altitude - - - Breached fence boundary - - + @@ -183,15 +64,15 @@ - + throttle as a percentage from 0 ~ 100 - - + + throttle as an absolute PWM value (normally in range of 1000~2000) - - + + throttle pass-through from pilot's transmitter - + @@ -274,7 +155,7 @@ Message to configure a camera mount, directional antenna, etc. System ID Component ID - mount operating mode (see MAV_MOUNT_MODE enum) + mount operating mode (see MAV_MOUNT_MODE enum) (1 = yes, 0 = no) (1 = yes, 0 = no) (1 = yes, 0 = no) @@ -323,7 +204,7 @@ status stream when fencing enabled 0 if currently inside fence, 1 if outside number of fence breaches - last breach type (see FENCE_BREACH_* enum) + last breach type (see FENCE_BREACH_* enum) time of last breach in milliseconds since boot @@ -375,7 +256,7 @@ Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled - state of AP_Limits, (see enum LimitState, LIMITS_STATE) + state of AP_Limits, (see enum LimitState, LIMITS_STATE) time of last breach in milliseconds since boot time of last recovery action in milliseconds since boot time of last successful recovery in milliseconds since boot diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index 29b3473bee..eec4d5b7ab 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -410,6 +410,12 @@ 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. + @@ -431,6 +437,45 @@ + + + + Disable fenced mode + + + Switched to guided mode to return point (fence point 0) + + + Report fence breach, but don't take action + + + Switched to guided mode to return point (fence point 0) with manual throttle control + + + + + + No last fence breach + + + Breached minimum altitude + + + Breached maximum altitude + + + Breached fence boundary + + + + + Enumeration of possible mount operation modes + Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization + Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. + Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization + Load neutral position and start RC Roll,Pitch,Yaw control with stabilization + Load neutral position and start to point to Lat,Lon,Alt + Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. @@ -703,6 +748,97 @@ y z + + + + Mission command to configure an on-board camera controller system. + Modes: P, TV, AV, M, Etc + Shutter speed: Divisor number for one second + Aperture: F stop number + ISO number e.g. 80, 100, 200, Etc + Exposure type enumerator + Command Identity + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + + + + Mission command to control an on-board camera controller system. + Session control e.g. show/hide lens + Zoom's absolute position + Zooming step value to offset zoom from the current position + Focus Locking, Unlocking or Re-locking + Shooting Command + Command Identity + Empty + + + + + Mission command to configure a camera or antenna mount + Mount operation mode (see MAV_MOUNT_MODE enum) + stabilize roll? (1 = yes, 0 = no) + stabilize pitch? (1 = yes, 0 = no) + stabilize yaw? (1 = yes, 0 = no) + Empty + Empty + Empty + + + + Mission command to control a camera or antenna mount + pitch or lat in degrees, depending on mount mode. + roll or lon in degrees depending on mount mode + yaw or alt (in meters) depending on mount mode + reserved + reserved + reserved + MAV_MOUNT_MODE enum value + + + + Mission command to set CAM_TRIGG_DIST for this flight + Camera trigger distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to enable the geofence + enable? (0=disable, 1=enable) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to trigger a parachute + action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to control a camera or antenna mount, using a quaternion as reference. + q1 - quaternion param #1 + q2 - quaternion param #2 + q3 - quaternion param #3 + q4 - quaternion param #4 + Empty + Empty + Empty + + NOP - This command is only used to mark the upper limit of the DO commands in the enumeration Empty @@ -1046,7 +1182,7 @@ 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). Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) Autopilot type / class. defined in MAV_AUTOPILOT ENUM - System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h A bitfield for use for autopilot-specific flags. System status flag, see MAV_STATE ENUM MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version @@ -1100,7 +1236,7 @@ Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. The system setting the mode - The new base mode + The new base mode The new autopilot-specific mode. This field can be ignored by an autopilot. @@ -1119,7 +1255,7 @@ Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. 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 Onboard parameter value - Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. Total number of onboard parameters Index of this onboard parameter @@ -1129,7 +1265,7 @@ 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 Onboard parameter value - Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. The global position, as returned by the Global Positioning System (GPS). This is @@ -1352,7 +1488,7 @@ Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). System ID Component ID - See MAV_MISSION_RESULT enum + See MAV_MISSION_RESULT enum As local waypoints exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. @@ -1405,7 +1541,7 @@ 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 Component ID - Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. x position 1 / Latitude 1 y position 1 / Longitude 1 z position 1 / Altitude 1 @@ -1415,7 +1551,7 @@ Read out the safety zone the MAV currently assumes. - Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. x position 1 / Latitude 1 y position 1 / Longitude 1 z position 1 / Altitude 1 @@ -1580,7 +1716,7 @@ Send a command with up to seven parameters to the MAV System which should execute the command Component which should execute the command, 0 for all components - Command ID, as defined by MAV_CMD enum. + Command ID, as defined by MAV_CMD enum. 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) Parameter 1, as defined by MAV_CMD enum. Parameter 2, as defined by MAV_CMD enum. @@ -1592,7 +1728,7 @@ Report status of a command. Includes feedback wether the command was executed. - Command ID, as defined by MAV_CMD enum. + Command ID, as defined by MAV_CMD enum. See MAV_RESULT enum @@ -2033,7 +2169,7 @@ Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). - Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. Status text message, without null termination character