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

SLUGS_MODE

Slugs-specific navigation modes.

ValueField NameDescription
0SLUGS_MODE_NONENo change to SLUGS mode.
1SLUGS_MODE_LIFTOFFVehicle is in liftoff mode.
2SLUGS_MODE_PASSTHROUGHVehicle is in passthrough mode, being controlled by a pilot.
3SLUGS_MODE_WAYPOINTVehicle is in waypoint mode, navigating to waypoints.
4SLUGS_MODE_MID_LEVELVehicle is executing mid-level commands.
5SLUGS_MODE_RETURNINGVehicle is returning to the home location.
6SLUGS_MODE_LANDINGVehicle is landing.
7SLUGS_MODE_LOSTLost connection with vehicle.
8SLUGS_MODE_SELECTIVE_PASSTHROUGHVehicle is in selective passthrough mode, where selected surfaces are being manually controlled.
9SLUGS_MODE_ISRVehicle is in ISR mode, performing reconaissance at a point specified by ISR_LOCATION message.
10SLUGS_MODE_LINE_PATROLVehicle is patrolling along lines between waypoints.
11SLUGS_MODE_GROUNDEDVehicle 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.

ValueField NameDescription
128CONTROL_SURFACE_FLAG_THROTTLE0b10000000 Throttle control passes through to pilot console.
64CONTROL_SURFACE_FLAG_LEFT_AILERON0b01000000 Left aileron control passes through to pilot console.
32CONTROL_SURFACE_FLAG_RIGHT_AILERON0b00100000 Right aileron control passes through to pilot console.
16CONTROL_SURFACE_FLAG_RUDDER0b00010000 Rudder control passes through to pilot console.
8CONTROL_SURFACE_FLAG_LEFT_ELEVATOR0b00001000 Left elevator control passes through to pilot console.
4CONTROL_SURFACE_FLAG_RIGHT_ELEVATOR0b00000100 Right elevator control passes through to pilot console.
2CONTROL_SURFACE_FLAG_LEFT_FLAP0b00000010 Left flap control passes through to pilot console.
1CONTROL_SURFACE_FLAG_RIGHT_FLAP0b00000001 Right flap control passes through to pilot console.

MAV_CMD_DO_NOTHING (10001 )

Does nothing.

ParamDescription
11 to arm, 0 to disarm

MAV_CMD_RETURN_TO_BASE (10011 )

Return vehicle to base.

ParamDescription
10: return to base, 1: track mobile base

MAV_CMD_STOP_RETURN_TO_BASE (10012 )

Stops the vehicle from returning to base and resumes flight.

ParamDescription

MAV_CMD_TURN_LIGHT (10013 )

Turns the vehicle's visible or infrared lights on or off.

ParamDescription
10: visible lights, 1: infrared lights
20: turn on, 1: turn off

MAV_CMD_GET_MID_LEVEL_COMMANDS (10014 )

Requests vehicle to send current mid-level commands to ground station.

ParamDescription

MAV_CMD_MIDLEVEL_STORAGE (10015 )

Requests storage of mid-level commands.

ParamDescription
1Mid-level command storage: 0: read from flash/EEPROM, 1: write to flash/EEPROM

CPU_LOAD ( #170 )

Sensor and DSC control loads.

Field NameTypeUnitsDescription
sensLoaduint8_tSensor DSC Load
ctrlLoaduint8_tControl DSC Load
batVoltuint16_tmVBattery Voltage

SENSOR_BIAS ( #172 )

Accelerometer and gyro biases.

Field NameTypeUnitsDescription
axBiasfloatm/sAccelerometer X bias
ayBiasfloatm/sAccelerometer Y bias
azBiasfloatm/sAccelerometer Z bias
gxBiasfloatrad/sGyro X bias
gyBiasfloatrad/sGyro Y bias
gzBiasfloatrad/sGyro Z bias

DIAGNOSTIC ( #173 )

Configurable diagnostic messages.

Field NameTypeDescription
diagFl1floatDiagnostic float 1
diagFl2floatDiagnostic float 2
diagFl3floatDiagnostic float 3
diagSh1int16_tDiagnostic short 1
diagSh2int16_tDiagnostic short 2
diagSh3int16_tDiagnostic short 3

SLUGS_NAVIGATION ( #176 )

Data used in the navigation algorithm.

Field NameTypeUnitsDescription
u_mfloatm/sMeasured Airspeed prior to the nav filter
phi_cfloatCommanded Roll
theta_cfloatCommanded Pitch
psiDot_cfloatCommanded Turn rate
ay_bodyfloatY component of the body acceleration
totalDistfloatTotal Distance to Run on this leg of Navigation
dist2GofloatRemaining distance to Run on this leg of Navigation
fromWPuint8_tOrigin WP
toWPuint8_tDestination WP
h_cuint16_tdmCommanded altitude (MSL)

DATA_LOG ( #177 )

Configurable data log probes to be used inside Simulink

Field NameTypeDescription
fl_1floatLog value 1
fl_2floatLog value 2
fl_3floatLog value 3
fl_4floatLog value 4
fl_5floatLog value 5
fl_6floatLog value 6

GPS_DATE_TIME ( #179 )

Pilot console PWM messges.

Field NameTypeUnitsDescription
yearuint8_tYear reported by Gps
monthuint8_tMonth reported by Gps
dayuint8_tDay reported by Gps
houruint8_tHour reported by Gps
minuint8_tMin reported by Gps
secuint8_tSec reported by Gps
clockStatuint8_tClock Status. See table 47 page 211 OEMStar Manual
visSatuint8_tVisible satellites reported by Gps
useSatuint8_tUsed satellites in Solution
GppGluint8_tGPS+GLONASS satellites in Solution
sigUsedMaskuint8_tGPS and GLONASS usage mask (bit 0 GPS_used? bit_4 GLONASS_used?)
percentUseduint8_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 NameTypeUnitsDescription
targetuint8_tThe system setting the commands
hCommandfloatmCommanded altitude (MSL)
uCommandfloatm/sCommanded Airspeed
rCommandfloatrad/sCommanded Turnrate

CTRL_SRFC_PT ( #181 )

This message sets the control surfaces for selective passthrough mode.

Field NameTypeValuesDescription
targetuint8_tThe system setting the commands
bitfieldPtuint16_tCONTROL_SURFACE_FLAGBitfield containing the passthrough configuration, see CONTROL_SURFACE_FLAG ENUM.

SLUGS_CAMERA_ORDER ( #184 )

Orders generated to the SLUGS camera mount.

Field NameTypeDescription
targetuint8_tThe system reporting the action
panint8_tOrder the mount to pan: -1 left, 0 No pan motion, +1 right
tiltint8_tOrder the mount to tilt: -1 down, 0 No tilt motion, +1 up
zoomint8_tOrder the zoom values 0 to 10
moveHomeint8_tOrders 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 NameTypeDescription
targetuint8_tThe system setting the commands
idSurfaceuint8_tID control surface send 0: throttle 1: aileron 2: elevator 3: rudder
mControlfloatPending
bControlfloatOrder 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 NameTypeUnitsDescription
targetuint8_tThe system reporting the action
latitudefloatdegMobile Latitude
longitudefloatdegMobile Longitude

SLUGS_CONFIGURATION_CAMERA ( #188 )

Control for camara.

Field NameTypeDescription
targetuint8_tThe system setting the commands
idOrderuint8_tID 0: brightness 1: aperture 2: iris 3: ICR 4: backlight
orderuint8_t1: up/on 2: down/off 3: auto/reset/no action

ISR_LOCATION ( #189 )

Transmits the position of watch

Field NameTypeUnitsDescription
targetuint8_tThe system reporting the action
latitudefloatdegISR Latitude
longitudefloatdegISR Longitude
heightfloatISR Height
option1uint8_tOption 1
option2uint8_tOption 2
option3uint8_tOption 3

VOLT_SENSOR ( #191 )

Transmits the readings from the voltage and current sensors

Field NameTypeDescription
r2Typeuint8_tIt is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM
voltageuint16_tVoltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V
reading2uint16_tDepends 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 NameTypeDescription
zoomuint8_tThe actual Zoom Value
panint16_tThe Pan value in 10ths of degree
tiltint16_tThe Tilt value in 10ths of degree

UAV_STATUS ( #193 )

Transmits the actual status values UAV in flight

Field NameTypeUnitsDescription
targetuint8_tThe ID system reporting the action
latitudefloatdegLatitude UAV
longitudefloatdegLongitude UAV
altitudefloatmAltitude UAV
speedfloatm/sSpeed UAV
coursefloatCourse UAV

STATUS_GPS ( #194 )

This contains the status of the GPS readings

Field NameTypeUnitsDescription
csFailsuint16_tNumber of times checksum has failed
gpsQualityuint8_tThe 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
msgsTypeuint8_tIndicates if GN, GL or GP messages are being received
posStatusuint8_tA = data valid, V = data invalid
magVarfloatdegMagnetic variation
magDirint8_tMagnetic variation direction E/W. Easterly variation (E) subtracts from True course and Westerly variation (W) adds to True course
modeInduint8_tPositioning 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 NameTypeUnitsDescription
timeStatusuint8_tThe Time Status. See Table 8 page 27 Novatel OEMStar Manual
receiverStatusuint32_tStatus Bitfield. See table 69 page 350 Novatel OEMstar Manual
solStatusuint8_tsolution Status. See table 44 page 197
posTypeuint8_tposition type. See table 43 page 196
velTypeuint8_tvelocity type. See table 43 page 196
posSolAgefloatsAge of the position solution
csFailsuint16_tTimes the CRC has failed since boot

SENSOR_DIAG ( #196 )

Diagnostic data Sensor MCU

Field NameTypeDescription
float1floatFloat field 1
float2floatFloat field 2
int1int16_tInt 16 field 1
char1int8_tInt 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 NameTypeDescription
versionuint32_tThe onboard software version

results matching ""

    No results matching ""