From 0f24c43b0c62e82a7f3f79309ce118e1b4b77017 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 24 Jul 2014 20:25:44 +1000 Subject: [PATCH] GCS_MAVLink: merged latest changes from upstream --- .../message_definitions/ardupilotmega.xml | 10 - .../message_definitions/common.xml | 146 ++++++ .../GCS_MAVLink/message_definitions/slugs.xml | 445 +++++++++++++----- 3 files changed, 466 insertions(+), 135 deletions(-) mode change 100644 => 100755 libraries/GCS_MAVLink/message_definitions/slugs.xml diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml index befb1bebcb..3665c7014d 100644 --- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml +++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml @@ -13,16 +13,6 @@ - - Pass control to an external controller. - Timeout in seconds. The maximum amount of time that the external controller will be allowed to control the vehicle. 0 means no timeout - Altitude min. If vehicle moves below this altitude the command will be aborted and the mission will continue. 0 for no lower alt limit - Altitude max. If vehicle moves above this altitude the command will be aborted and the mission will continue. 0 for no upper alt limit - Horizontal move limit. If vehicle moves more than this distance from it's location at the moment the command was begun, the command will be aborted and the mission will continue. 0 for no horizontal movement limit - Empty - Empty - Empty - Navigate at the specified velocity coordinate_frame - see MAV_FRAME enum diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index b7776306dd..6166ca806d 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -396,6 +396,9 @@ 0x200000 AHRS subsystem health + + 0x400000 Terrain subsystem health + @@ -419,6 +422,15 @@ 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. + + + Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. + + + 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. + @@ -581,6 +593,36 @@ Longitude/Y of goal Altitude/Z of goal + + 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 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 + Empty + Empty + Empty + + + set id of master controller + System ID + Component ID + Empty + Empty + Empty + Empty + Empty + + + hand control over to an external controller + On / Off (> 0.5f on) + Empty + Empty + Empty + Empty + Empty + Empty + NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration Empty @@ -731,6 +773,36 @@ Empty Empty + + Terminate flight immediately + Flight termination activated if > 0.5 + Empty + Empty + Empty + Empty + Empty + Empty + + + Mission command to perform a landing from a rally point. + Break altitude (meters) + Landing speed (m/s) + Empty + Empty + Empty + Empty + Empty + + + Mission command to safely abort an autonmous landing. + Altitude (meters) + Empty + Empty + Empty + Empty + Empty + Empty + Control onboard camera system. Camera ID (-1 for all) @@ -1772,6 +1844,51 @@ 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 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 + 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 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 + 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 + 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 + 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 + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) Timestamp (milliseconds since system boot) @@ -2169,6 +2286,35 @@ Direction the sensor faces from FIXME enum. Measurement covariance in centimeters, 0 for unknown / invalid readings + + Request for terrain data and terrain status + Latitude of SW corner of first grid (degrees *10^7) + Longitude of SW corner of first grid (in degrees *10^7) + Grid spacing in meters + Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + + + Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST + Latitude of SW corner of first grid (degrees *10^7) + Longitude of SW corner of first grid (in degrees *10^7) + Grid spacing in meters + bit within the terrain request mask + Terrain data in meters AMSL + + + Request that the vehicle report terrain height at the given location. Used by GCS to check if vehicle has all terrain data needed for a mission. + Latitude (degrees *10^7) + Longitude (degrees *10^7) + + + Response from a TERRAIN_CHECK request + Latitude (degrees *10^7) + Longitude (degrees *10^7) + grid spacing (zero if terrain at this location unavailable) + Terrain height in meters AMSL (-32767 if unavailable) + 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 diff --git a/libraries/GCS_MAVLink/message_definitions/slugs.xml b/libraries/GCS_MAVLink/message_definitions/slugs.xml old mode 100644 new mode 100755 index 621183072d..a985eab385 --- a/libraries/GCS_MAVLink/message_definitions/slugs.xml +++ b/libraries/GCS_MAVLink/message_definitions/slugs.xml @@ -1,26 +1,125 @@ common.xml - - + + Does nothing. + 1 to arm, 0 to disarm + + + + + + Return vehicle to base. + 0: return to base, 1: track mobile base + + + Stops the vehicle from returning to base and resumes flight. + + + Turns the vehicle's visible or infrared lights on or off. + 0: visible lights, 1: infrared lights + 0: turn on, 1: turn off + + + Requests vehicle to send current mid-level commands to ground station. + + + Requests storage of mid-level commands. + Mid-level command storage: 0: read from flash/EEPROM, 1: write to flash/EEPROM + + + + + + Slugs-specific navigation modes. + + No change to SLUGS mode. + + + Vehicle is in liftoff mode. + + + Vehicle is in passthrough mode, being controlled by a pilot. + + + Vehicle is in waypoint mode, navigating to waypoints. + + + Vehicle is executing mid-level commands. + + + Vehicle is returning to the home location. + + + Vehicle is landing. + + + Lost connection with vehicle. + + + Vehicle is in selective passthrough mode, where selected surfaces are being manually controlled. + + + Vehicle is in ISR mode, performing reconaissance at a point specified by ISR_LOCATION message. + + + Vehicle is patrolling along lines between waypoints. + + + Vehicle is grounded or an error has occurred. + + + + + These flags encode the control surfaces for selective passthrough mode. If a bit is set then the pilot console + has control of the surface, and if not then the autopilot has control of the surface. + + 0b10000000 Throttle control passes through to pilot console. + + + 0b01000000 Left aileron control passes through to pilot console. + + + 0b00100000 Right aileron control passes through to pilot console. + + + 0b00010000 Rudder control passes through to pilot console. + + + 0b00001000 Left elevator control passes through to pilot console. + + + 0b00000100 Right elevator control passes through to pilot console. + + + 0b00000010 Left flap control passes through to pilot console. + + + 0b00000001 Right flap control passes through to pilot console. + + + + - --> - - - - Sensor and DSC control loads. - Sensor DSC Load - Control DSC Load - Battery Voltage in millivolts + + Sensor and DSC control loads. + Sensor DSC Load + Control DSC Load + Battery Voltage in millivolts + + + + Accelerometer and gyro biases. + Accelerometer X bias (m/s) + Accelerometer Y bias (m/s) + Accelerometer Z bias (m/s) + Gyro X bias (rad/s) + Gyro Y bias (rad/s) + Gyro Z bias (rad/s) + + + + Configurable diagnostic messages. + Diagnostic float 1 + Diagnostic float 2 + Diagnostic float 3 + Diagnostic short 1 + Diagnostic short 2 + Diagnostic short 3 + + + + Data used in the navigation algorithm. + Measured Airspeed prior to the nav filter in m/s + Commanded Roll + Commanded Pitch + Commanded Turn rate + Y component of the body acceleration + Total Distance to Run on this leg of Navigation + Remaining distance to Run on this leg of Navigation + Origin WP + Destination WP + Commanded altitude in 0.1 m + + + + Configurable data log probes to be used inside Simulink + Log value 1 + Log value 2 + Log value 3 + Log value 4 + Log value 5 + Log value 6 + + + + Pilot console PWM messges. + Year reported by Gps + Month reported by Gps + Day reported by Gps + Hour reported by Gps + Min reported by Gps + Sec reported by Gps + Clock Status. See table 47 page 211 OEMStar Manual + Visible satellites reported by Gps + Used satellites in Solution + GPS+GLONASS satellites in Solution + GPS and GLONASS usage mask (bit 0 GPS_used? bit_4 GLONASS_used?) + Percent used GPS - - Air data for altitude and airspeed computation. - Dynamic pressure (Pa) - Static pressure (Pa) - Board temperature - - - - Accelerometer and gyro biases. - Accelerometer X bias (m/s) - Accelerometer Y bias (m/s) - Accelerometer Z bias (m/s) - Gyro X bias (rad/s) - Gyro Y bias (rad/s) - Gyro Z bias (rad/s) - - - - Configurable diagnostic messages. - Diagnostic float 1 - Diagnostic float 2 - Diagnostic float 3 - Diagnostic short 1 - Diagnostic short 2 - Diagnostic short 3 - - - - Data used in the navigation algorithm. - Measured Airspeed prior to the Nav Filter - Commanded Roll - Commanded Pitch - Commanded Turn rate - Y component of the body acceleration - Total Distance to Run on this leg of Navigation - Remaining distance to Run on this leg of Navigation - Origin WP - Destination WP - - - - Configurable data log probes to be used inside Simulink. - Log value 1 - Log value 2 - Log value 3 - Log value 4 - Log value 5 - Log value 6 - - - - Pilot console PWM messges. - Year reported by Gps - Month reported by Gps - Day reported by Gps - Hour reported by Gps - Min reported by Gps - Sec reported by Gps - Visible sattelites reported by Gps - - - - Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX. - The system setting the commands - Commanded Airspeed - Log value 2 - Log value 3 - - - - - This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows: - Position Bit Code - ================================= - 15-8 Reserved - 7 dt_pass 128 - 6 dla_pass 64 - 5 dra_pass 32 - 4 dr_pass 16 - 3 dle_pass 8 - 2 dre_pass 4 - 1 dlf_pass 2 - 0 drf_pass 1 - Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface. - The system setting the commands - Bitfield containing the PT configuration - - - - - - Action messages focused on the SLUGS AP. - The system reporting the action - Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names - Value associated with the action - - - + + Mid Level commands sent from the GS to the autopilot. These are only sent when being operated in mid-level commands mode from the ground. + The system setting the commands + Commanded Altitude in meters + Commanded Airspeed in m/s + Commanded Turnrate in rad/s + + + + This message sets the control surfaces for selective passthrough mode. + The system setting the commands + Bitfield containing the passthrough configuration, see CONTROL_SURFACE_FLAG ENUM. + + + + Orders generated to the SLUGS camera mount. + The system reporting the action + Order the mount to pan: -1 left, 0 No pan motion, +1 right + Order the mount to tilt: -1 down, 0 No tilt motion, +1 up + Order the zoom values 0 to 10 + Orders the camera mount to move home. The other fields are ignored when this field is set. 1: move home, 0 ignored + + + + Control for surface; pending and order to origin. + The system setting the commands + ID control surface send 0: throttle 1: aileron 2: elevator 3: rudder + Pending + Order to origin + + + + + + + Transmits the last known position of the mobile GS to the UAV. Very relevant when Track Mobile is enabled + The system reporting the action + Mobile Latitude + Mobile Longitude + + + + Control for camara. + The system setting the commands + ID 0: brightness 1: aperture 2: iris 3: ICR 4: backlight + 1: up/on 2: down/off 3: auto/reset/no action + + + + Transmits the position of watch + The system reporting the action + ISR Latitude + ISR Longitude + ISR Height + Option 1 + Option 2 + Option 3 + + + + + + + Transmits the readings from the voltage and current sensors + It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM + Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V + Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value + + + + Transmits the actual Pan, Tilt and Zoom values of the camera unit + The actual Zoom Value + The Pan value in 10ths of degree + The Tilt value in 10ths of degree + + + + Transmits the actual status values UAV in flight + The ID system reporting the action + Latitude UAV + Longitude UAV + Altitude UAV + Speed UAV + Course UAV + + + + This contains the status of the GPS readings + Number of times checksum has failed + The quality indicator, 0=fix not available or invalid, 1=GPS fix, 2=C/A differential GPS, 6=Dead reckoning mode, 7=Manual input mode (fixed position), 8=Simulator mode, 9= WAAS a + Indicates if GN, GL or GP messages are being received + A = data valid, V = data invalid + Magnetic variation, degrees + Magnetic variation direction E/W. Easterly variation (E) subtracts from True course and Westerly variation (W) adds to True course + Positioning system mode indicator. A - Autonomous;D-Differential; E-Estimated (dead reckoning) mode;M-Manual input; N-Data not valid + + + + Transmits the diagnostics data from the Novatel OEMStar GPS + The Time Status. See Table 8 page 27 Novatel OEMStar Manual + Status Bitfield. See table 69 page 350 Novatel OEMstar Manual + solution Status. See table 44 page 197 + position type. See table 43 page 196 + velocity type. See table 43 page 196 + Age of the position solution in seconds + Times the CRC has failed since boot + + + + Diagnostic data Sensor MCU + Float field 1 + Float field 2 + Int 16 field 1 + Int 8 field 1 + + + + + The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. This message allows the sensor and control MCUs to communicate version numbers on startup. + The onboard software version + +