MAVLINK Message Set: slugs.xml
This is a human-readable form of the XML definition file: slugs.xml.
MAVLink 2 messages have an ID > 255 and are marked up using (MAVLink 2) in their description.
MAVLink 2 extension fields that have been added to MAVLink 1 messages are displayed in blue.
MAVLink Include Files: common.xml
MAVLink Type Enumerations
SLUGS_MODE
Slugs-specific navigation modes.
Value | Field Name | Description |
---|---|---|
0 | SLUGS_MODE_NONE | No change to SLUGS mode. |
1 | SLUGS_MODE_LIFTOFF | Vehicle is in liftoff mode. |
2 | SLUGS_MODE_PASSTHROUGH | Vehicle is in passthrough mode, being controlled by a pilot. |
3 | SLUGS_MODE_WAYPOINT | Vehicle is in waypoint mode, navigating to waypoints. |
4 | SLUGS_MODE_MID_LEVEL | Vehicle is executing mid-level commands. |
5 | SLUGS_MODE_RETURNING | Vehicle is returning to the home location. |
6 | SLUGS_MODE_LANDING | Vehicle is landing. |
7 | SLUGS_MODE_LOST | Lost connection with vehicle. |
8 | SLUGS_MODE_SELECTIVE_PASSTHROUGH | Vehicle is in selective passthrough mode, where selected surfaces are being manually controlled. |
9 | SLUGS_MODE_ISR | Vehicle is in ISR mode, performing reconaissance at a point specified by ISR_LOCATION message. |
10 | SLUGS_MODE_LINE_PATROL | Vehicle is patrolling along lines between waypoints. |
11 | SLUGS_MODE_GROUNDED | Vehicle is grounded or an error has occurred. |
CONTROL_SURFACE_FLAG
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.
Value | Field Name | Description |
---|---|---|
128 | CONTROL_SURFACE_FLAG_THROTTLE | 0b10000000 Throttle control passes through to pilot console. |
64 | CONTROL_SURFACE_FLAG_LEFT_AILERON | 0b01000000 Left aileron control passes through to pilot console. |
32 | CONTROL_SURFACE_FLAG_RIGHT_AILERON | 0b00100000 Right aileron control passes through to pilot console. |
16 | CONTROL_SURFACE_FLAG_RUDDER | 0b00010000 Rudder control passes through to pilot console. |
8 | CONTROL_SURFACE_FLAG_LEFT_ELEVATOR | 0b00001000 Left elevator control passes through to pilot console. |
4 | CONTROL_SURFACE_FLAG_RIGHT_ELEVATOR | 0b00000100 Right elevator control passes through to pilot console. |
2 | CONTROL_SURFACE_FLAG_LEFT_FLAP | 0b00000010 Left flap control passes through to pilot console. |
1 | CONTROL_SURFACE_FLAG_RIGHT_FLAP | 0b00000001 Right flap control passes through to pilot console. |
MAVLink Commands (MAV_CMD)
MAV_CMD_DO_NOTHING (10001 )
Does nothing.
Param | Description |
---|---|
1 | 1 to arm, 0 to disarm |
MAV_CMD_RETURN_TO_BASE (10011 )
Return vehicle to base.
Param | Description |
---|---|
1 | 0: return to base, 1: track mobile base |
MAV_CMD_STOP_RETURN_TO_BASE (10012 )
Stops the vehicle from returning to base and resumes flight.
Param | Description |
---|
MAV_CMD_TURN_LIGHT (10013 )
Turns the vehicle's visible or infrared lights on or off.
Param | Description |
---|---|
1 | 0: visible lights, 1: infrared lights |
2 | 0: turn on, 1: turn off |
MAV_CMD_GET_MID_LEVEL_COMMANDS (10014 )
Requests vehicle to send current mid-level commands to ground station.
Param | Description |
---|
MAV_CMD_MIDLEVEL_STORAGE (10015 )
Requests storage of mid-level commands.
Param | Description |
---|---|
1 | Mid-level command storage: 0: read from flash/EEPROM, 1: write to flash/EEPROM |
MAVLink Messages
CPU_LOAD ( #170 )
Sensor and DSC control loads.
Field Name | Type | Units | Description |
---|---|---|---|
sensLoad | uint8_t | Sensor DSC Load | |
ctrlLoad | uint8_t | Control DSC Load | |
batVolt | uint16_t | mV | Battery Voltage |
SENSOR_BIAS ( #172 )
Accelerometer and gyro biases.
Field Name | Type | Units | Description |
---|---|---|---|
axBias | float | m/s | Accelerometer X bias |
ayBias | float | m/s | Accelerometer Y bias |
azBias | float | m/s | Accelerometer Z bias |
gxBias | float | rad/s | Gyro X bias |
gyBias | float | rad/s | Gyro Y bias |
gzBias | float | rad/s | Gyro Z bias |
DIAGNOSTIC ( #173 )
Configurable diagnostic messages.
Field Name | Type | Description |
---|---|---|
diagFl1 | float | Diagnostic float 1 |
diagFl2 | float | Diagnostic float 2 |
diagFl3 | float | Diagnostic float 3 |
diagSh1 | int16_t | Diagnostic short 1 |
diagSh2 | int16_t | Diagnostic short 2 |
diagSh3 | int16_t | Diagnostic short 3 |
SLUGS_NAVIGATION ( #176 )
Data used in the navigation algorithm.
Field Name | Type | Units | Description |
---|---|---|---|
u_m | float | m/s | Measured Airspeed prior to the nav filter |
phi_c | float | Commanded Roll | |
theta_c | float | Commanded Pitch | |
psiDot_c | float | Commanded Turn rate | |
ay_body | float | Y component of the body acceleration | |
totalDist | float | Total Distance to Run on this leg of Navigation | |
dist2Go | float | Remaining distance to Run on this leg of Navigation | |
fromWP | uint8_t | Origin WP | |
toWP | uint8_t | Destination WP | |
h_c | uint16_t | dm | Commanded altitude (MSL) |
DATA_LOG ( #177 )
Configurable data log probes to be used inside Simulink
Field Name | Type | Description |
---|---|---|
fl_1 | float | Log value 1 |
fl_2 | float | Log value 2 |
fl_3 | float | Log value 3 |
fl_4 | float | Log value 4 |
fl_5 | float | Log value 5 |
fl_6 | float | Log value 6 |
GPS_DATE_TIME ( #179 )
Pilot console PWM messges.
Field Name | Type | Units | Description |
---|---|---|---|
year | uint8_t | Year reported by Gps | |
month | uint8_t | Month reported by Gps | |
day | uint8_t | Day reported by Gps | |
hour | uint8_t | Hour reported by Gps | |
min | uint8_t | Min reported by Gps | |
sec | uint8_t | Sec reported by Gps | |
clockStat | uint8_t | Clock Status. See table 47 page 211 OEMStar Manual | |
visSat | uint8_t | Visible satellites reported by Gps | |
useSat | uint8_t | Used satellites in Solution | |
GppGl | uint8_t | GPS+GLONASS satellites in Solution | |
sigUsedMask | uint8_t | GPS and GLONASS usage mask (bit 0 GPS_used? bit_4 GLONASS_used?) | |
percentUsed | uint8_t | % | Percent used GPS |
MID_LVL_CMDS ( #180 )
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.
Field Name | Type | Units | Description |
---|---|---|---|
target | uint8_t | The system setting the commands | |
hCommand | float | m | Commanded altitude (MSL) |
uCommand | float | m/s | Commanded Airspeed |
rCommand | float | rad/s | Commanded Turnrate |
CTRL_SRFC_PT ( #181 )
This message sets the control surfaces for selective passthrough mode.
Field Name | Type | Values | Description |
---|---|---|---|
target | uint8_t | The system setting the commands | |
bitfieldPt | uint16_t | CONTROL_SURFACE_FLAG | Bitfield containing the passthrough configuration, see CONTROL_SURFACE_FLAG ENUM. |
SLUGS_CAMERA_ORDER ( #184 )
Orders generated to the SLUGS camera mount.
Field Name | Type | Description |
---|---|---|
target | uint8_t | The system reporting the action |
pan | int8_t | Order the mount to pan: -1 left, 0 No pan motion, +1 right |
tilt | int8_t | Order the mount to tilt: -1 down, 0 No tilt motion, +1 up |
zoom | int8_t | Order the zoom values 0 to 10 |
moveHome | int8_t | Orders the camera mount to move home. The other fields are ignored when this field is set. 1: move home, 0 ignored |
CONTROL_SURFACE ( #185 )
Control for surface; pending and order to origin.
Field Name | Type | Description |
---|---|---|
target | uint8_t | The system setting the commands |
idSurface | uint8_t | ID control surface send 0: throttle 1: aileron 2: elevator 3: rudder |
mControl | float | Pending |
bControl | float | Order to origin |
SLUGS_MOBILE_LOCATION ( #186 )
Transmits the last known position of the mobile GS to the UAV. Very relevant when Track Mobile is enabled
Field Name | Type | Units | Description |
---|---|---|---|
target | uint8_t | The system reporting the action | |
latitude | float | deg | Mobile Latitude |
longitude | float | deg | Mobile Longitude |
SLUGS_CONFIGURATION_CAMERA ( #188 )
Control for camara.
Field Name | Type | Description |
---|---|---|
target | uint8_t | The system setting the commands |
idOrder | uint8_t | ID 0: brightness 1: aperture 2: iris 3: ICR 4: backlight |
order | uint8_t | 1: up/on 2: down/off 3: auto/reset/no action |
ISR_LOCATION ( #189 )
Transmits the position of watch
Field Name | Type | Units | Description |
---|---|---|---|
target | uint8_t | The system reporting the action | |
latitude | float | deg | ISR Latitude |
longitude | float | deg | ISR Longitude |
height | float | ISR Height | |
option1 | uint8_t | Option 1 | |
option2 | uint8_t | Option 2 | |
option3 | uint8_t | Option 3 |
VOLT_SENSOR ( #191 )
Transmits the readings from the voltage and current sensors
Field Name | Type | Description |
---|---|---|
r2Type | uint8_t | It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM |
voltage | uint16_t | Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V |
reading2 | uint16_t | 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 |
PTZ_STATUS ( #192 )
Transmits the actual Pan, Tilt and Zoom values of the camera unit
Field Name | Type | Description |
---|---|---|
zoom | uint8_t | The actual Zoom Value |
pan | int16_t | The Pan value in 10ths of degree |
tilt | int16_t | The Tilt value in 10ths of degree |
UAV_STATUS ( #193 )
Transmits the actual status values UAV in flight
Field Name | Type | Units | Description |
---|---|---|---|
target | uint8_t | The ID system reporting the action | |
latitude | float | deg | Latitude UAV |
longitude | float | deg | Longitude UAV |
altitude | float | m | Altitude UAV |
speed | float | m/s | Speed UAV |
course | float | Course UAV |
STATUS_GPS ( #194 )
This contains the status of the GPS readings
Field Name | Type | Units | Description |
---|---|---|---|
csFails | uint16_t | Number of times checksum has failed | |
gpsQuality | uint8_t | 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 | |
msgsType | uint8_t | Indicates if GN, GL or GP messages are being received | |
posStatus | uint8_t | A = data valid, V = data invalid | |
magVar | float | deg | Magnetic variation |
magDir | int8_t | Magnetic variation direction E/W. Easterly variation (E) subtracts from True course and Westerly variation (W) adds to True course | |
modeInd | uint8_t | Positioning system mode indicator. A - Autonomous;D-Differential; E-Estimated (dead reckoning) mode;M-Manual input; N-Data not valid |
NOVATEL_DIAG ( #195 )
Transmits the diagnostics data from the Novatel OEMStar GPS
Field Name | Type | Units | Description |
---|---|---|---|
timeStatus | uint8_t | The Time Status. See Table 8 page 27 Novatel OEMStar Manual | |
receiverStatus | uint32_t | Status Bitfield. See table 69 page 350 Novatel OEMstar Manual | |
solStatus | uint8_t | solution Status. See table 44 page 197 | |
posType | uint8_t | position type. See table 43 page 196 | |
velType | uint8_t | velocity type. See table 43 page 196 | |
posSolAge | float | s | Age of the position solution |
csFails | uint16_t | Times the CRC has failed since boot |
SENSOR_DIAG ( #196 )
Diagnostic data Sensor MCU
Field Name | Type | Description |
---|---|---|
float1 | float | Float field 1 |
float2 | float | Float field 2 |
int1 | int16_t | Int 16 field 1 |
char1 | int8_t | Int 8 field 1 |
BOOT ( #197 )
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.
Field Name | Type | Description |
---|---|---|
version | uint32_t | The onboard software version |