Dialect: ASLUAV

This is a human-readable form of the XML definition file: ASLUAV.

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

[Enum]

ValueField NameDescription

GSM_MODEM_TYPE

[Enum]

ValueField NameDescription
0GSM_MODEM_TYPE_UNKNOWNnot specified
1GSM_MODEM_TYPE_HUAWEI_E3372HUAWEI LTE USB Stick E3372

MAVLink Commands (MAV_CMD)

MAVLink commands (MAV_CMD) and messages are different! These commands define the values of up to 7 parameters that are packaged INSIDE specific messages used in the Mission Protocol and Command Protocol. Use commands for actions in missions or if you need acknowledgment and/or retry logic from a request. Otherwise use messages.

MAV_CMD_RESET_MPPT (40001 )

[Command] Mission command to reset Maximum Power Point Tracker (MPPT)

Param (:Label)Description
1MPPT number
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_PAYLOAD_CONTROL (40002 )

[Command] Mission command to perform a power cycle on payload

Param (:Label)Description
1Complete power cycle
2VISensor power cycle
3Empty
4Empty
5Empty
6Empty
7Empty

MAVLink Messages

COMMAND_INT_STAMPED ( #223 )

[Message] Message encoding a command with parameters as scaled integers and additional metadata. Scaling depends on the actual command value.

Field NameTypeValuesDescription
utc_timeuint32_tUTC time, seconds elapsed since 01.01.1970
vehicle_timestampuint64_tMicroseconds elapsed since vehicle boot
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
frameuint8_tMAV_FRAMEThe coordinate system of the COMMAND, as defined by MAV_FRAME enum
commanduint16_tMAV_CMDThe scheduled action for the mission item, as defined by MAV_CMD enum
currentuint8_tfalse:0, true:1
autocontinueuint8_tautocontinue to next wp
param1floatPARAM1, see MAV_CMD enum
param2floatPARAM2, see MAV_CMD enum
param3floatPARAM3, see MAV_CMD enum
param4floatPARAM4, see MAV_CMD enum
xint32_tPARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
yint32_tPARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
zfloatPARAM7 / z position: global: altitude in meters (MSL, WGS84, AGL or relative to home - depending on frame).

COMMAND_LONG_STAMPED ( #224 )

[Message] Send a command with up to seven parameters to the MAV and additional metadata

Field NameTypeValuesDescription
utc_timeuint32_tUTC time, seconds elapsed since 01.01.1970
vehicle_timestampuint64_tMicroseconds elapsed since vehicle boot
target_systemuint8_tSystem which should execute the command
target_componentuint8_tComponent which should execute the command, 0 for all components
commanduint16_tMAV_CMDCommand ID, as defined by MAV_CMD enum.
confirmationuint8_t0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
param1floatParameter 1, as defined by MAV_CMD enum.
param2floatParameter 2, as defined by MAV_CMD enum.
param3floatParameter 3, as defined by MAV_CMD enum.
param4floatParameter 4, as defined by MAV_CMD enum.
param5floatParameter 5, as defined by MAV_CMD enum.
param6floatParameter 6, as defined by MAV_CMD enum.
param7floatParameter 7, as defined by MAV_CMD enum.

SENS_POWER ( #8002 )

[Message] (MAVLink 2) Voltage and current sensor data

Field NameTypeUnitsDescription
adc121_vspb_voltfloatVPower board voltage sensor reading
adc121_cspb_ampfloatAPower board current sensor reading
adc121_cs1_ampfloatABoard current sensor 1 reading
adc121_cs2_ampfloatABoard current sensor 2 reading

SENS_MPPT ( #8003 )

[Message] (MAVLink 2) Maximum Power Point Tracker (MPPT) sensor data for solar module power performance tracking

Field NameTypeUnitsDescription
mppt_timestampuint64_tusMPPT last timestamp
mppt1_voltfloatVMPPT1 voltage
mppt1_ampfloatAMPPT1 current
mppt1_pwmuint16_tusMPPT1 pwm
mppt1_statusuint8_tMPPT1 status
mppt2_voltfloatVMPPT2 voltage
mppt2_ampfloatAMPPT2 current
mppt2_pwmuint16_tusMPPT2 pwm
mppt2_statusuint8_tMPPT2 status
mppt3_voltfloatVMPPT3 voltage
mppt3_ampfloatAMPPT3 current
mppt3_pwmuint16_tusMPPT3 pwm
mppt3_statusuint8_tMPPT3 status

ASLCTRL_DATA ( #8004 )

[Message] (MAVLink 2) ASL-fixed-wing controller data

Field NameTypeUnitsDescription
timestampuint64_tusTimestamp
aslctrl_modeuint8_tASLCTRL control-mode (manual, stabilized, auto, etc...)
hfloatSee sourcecode for a description of these values...
hReffloat
hRef_tfloat
PitchAnglefloatdegPitch angle
PitchAngleReffloatdegPitch angle reference
qfloat
qReffloat
uElevfloat
uThrotfloat
uThrot2float
nZfloat
AirspeedReffloatm/sAirspeed reference
SpoilersEngageduint8_t
YawAnglefloatdegYaw angle
YawAngleReffloatdegYaw angle reference
RollAnglefloatdegRoll angle
RollAngleReffloatdegRoll angle reference
pfloat
pReffloat
rfloat
rReffloat
uAilfloat
uRudfloat

ASLCTRL_DEBUG ( #8005 )

[Message] (MAVLink 2) ASL-fixed-wing controller debug data

Field NameTypeDescription
i32_1uint32_tDebug data
i8_1uint8_tDebug data
i8_2uint8_tDebug data
f_1floatDebug data
f_2floatDebug data
f_3floatDebug data
f_4floatDebug data
f_5floatDebug data
f_6floatDebug data
f_7floatDebug data
f_8floatDebug data

ASLUAV_STATUS ( #8006 )

[Message] (MAVLink 2) Extended state information for ASLUAVs

Field NameTypeDescription
LED_statusuint8_tStatus of the position-indicator LEDs
SATCOM_statusuint8_tStatus of the IRIDIUM satellite communication system
Servo_statusuint8_t[8]Status vector for up to 8 servos
Motor_rpmfloatMotor RPM

EKF_EXT ( #8007 )

[Message] (MAVLink 2) Extended EKF state estimates for ASLUAVs

Field NameTypeUnitsDescription
timestampuint64_tusTime since system start
Windspeedfloatm/sMagnitude of wind velocity (in lateral inertial plane)
WindDirfloatradWind heading angle from North
WindZfloatm/sZ (Down) component of inertial wind velocity
Airspeedfloatm/sMagnitude of air velocity
betafloatradSideslip angle
alphafloatradAngle of attack

ASL_OBCTRL ( #8008 )

[Message] (MAVLink 2) Off-board controls/commands for ASLUAVs

Field NameTypeUnitsDescription
timestampuint64_tusTime since system start
uElevfloatElevator command [~]
uThrotfloatThrottle command [~]
uThrot2floatThrottle 2 command [~]
uAilLfloatLeft aileron command [~]
uAilRfloatRight aileron command [~]
uRudfloatRudder command [~]
obctrl_statusuint8_tOff-board computer status

SENS_ATMOS ( #8009 )

[Message] (MAVLink 2) Atmospheric sensors (temperature, humidity, ...)

Field NameTypeUnitsDescription
timestampuint64_tusTime since system boot
TempAmbientfloatdegCAmbient temperature
Humidityfloat%Relative humidity

SENS_BATMON ( #8010 )

[Message] (MAVLink 2) Battery pack monitoring data for Li-Ion batteries

Field NameTypeUnitsDescription
batmon_timestampuint64_tusTime since system start
temperaturefloatdegCBattery pack temperature
voltageuint16_tmVBattery pack voltage
currentint16_tmABattery pack current
SoCuint8_tBattery pack state-of-charge
batterystatusuint16_tBattery monitor status report bits in Hex
serialnumberuint16_tBattery monitor serial number in Hex
safetystatusuint32_tBattery monitor safetystatus report bits in Hex
operationstatusuint32_tBattery monitor operation status report bits in Hex
cellvoltage1uint16_tmVBattery pack cell 1 voltage
cellvoltage2uint16_tmVBattery pack cell 2 voltage
cellvoltage3uint16_tmVBattery pack cell 3 voltage
cellvoltage4uint16_tmVBattery pack cell 4 voltage
cellvoltage5uint16_tmVBattery pack cell 5 voltage
cellvoltage6uint16_tmVBattery pack cell 6 voltage

FW_SOARING_DATA ( #8011 )

[Message] (MAVLink 2) Fixed-wing soaring (i.e. thermal seeking) data

Field NameTypeUnitsDescription
timestampuint64_tmsTimestamp
timestampModeChangeduint64_tmsTimestamp since last mode change
xWfloatm/sThermal core updraft strength
xRfloatmThermal radius
xLatfloatdegThermal center latitude
xLonfloatdegThermal center longitude
VarWfloatVariance W
VarRfloatVariance R
VarLatfloatVariance Lat
VarLonfloatVariance Lon
LoiterRadiusfloatmSuggested loiter radius
LoiterDirectionfloatSuggested loiter direction
DistToSoarPointfloatmDistance to soar point
vSinkExpfloatm/sExpected sink rate at current airspeed, roll and throttle
z1_LocalUpdraftSpeedfloatm/sMeasurement / updraft speed at current/local airplane position
z2_DeltaRollfloatdegMeasurement / roll angle tracking error
z1_expfloatExpected measurement 1
z2_expfloatExpected measurement 2
ThermalGSNorthfloatm/sThermal drift (from estimator prediction step only)
ThermalGSEastfloatm/sThermal drift (from estimator prediction step only)
TSE_dotfloatm/sTotal specific energy change (filtered)
DebugVar1floatDebug variable 1
DebugVar2floatDebug variable 2
ControlModeuint8_tControl Mode [-]
validuint8_tData valid [-]

SENSORPOD_STATUS ( #8012 )

[Message] (MAVLink 2) Monitoring of sensorpod status

Field NameTypeUnitsDescription
timestampuint64_tmsTimestamp in linuxtime (since 1.1.1970)
visensor_rate_1uint8_tRate of ROS topic 1
visensor_rate_2uint8_tRate of ROS topic 2
visensor_rate_3uint8_tRate of ROS topic 3
visensor_rate_4uint8_tRate of ROS topic 4
recording_nodes_countuint8_tNumber of recording nodes
cpu_tempuint8_tdegCTemperature of sensorpod CPU in
free_spaceuint16_tFree space available in recordings directory in [Gb] * 1e2

SENS_POWER_BOARD ( #8013 )

[Message] (MAVLink 2) Monitoring of power board status

Field NameTypeUnitsDescription
timestampuint64_tusTimestamp
pwr_brd_statusuint8_tPower board status register
pwr_brd_led_statusuint8_tPower board leds status
pwr_brd_system_voltfloatVPower board system voltage
pwr_brd_servo_voltfloatVPower board servo voltage
pwr_brd_digital_voltfloatVPower board digital voltage
pwr_brd_mot_l_ampfloatAPower board left motor current sensor
pwr_brd_mot_r_ampfloatAPower board right motor current sensor
pwr_brd_analog_ampfloatAPower board analog current sensor
pwr_brd_digital_ampfloatAPower board digital current sensor
pwr_brd_ext_ampfloatAPower board extension current sensor
pwr_brd_aux_ampfloatAPower board aux current sensor

[Message] (MAVLink 2) Status of GSM modem (connected to onboard computer)

Field NameTypeUnitsValuesDescription
timestampuint64_tusTimestamp (of OBC)
gsm_modem_typeuint8_tGSM_MODEM_TYPEGSM modem used
gsm_link_typeuint8_tGSM_LINK_TYPEGSM link type
rssiuint8_tRSSI as reported by modem (unconverted)
rsrp_rscpuint8_tRSRP (LTE) or RSCP (WCDMA) as reported by modem (unconverted)
sinr_eciouint8_tSINR (LTE) or ECIO (WCDMA) as reported by modem (unconverted)
rsrquint8_tRSRQ (LTE only) as reported by modem (unconverted)

[Message] (MAVLink 2) Status of the SatCom link

Field NameTypeUnitsDescription
timestampuint64_tusTimestamp
last_heartbeatuint64_tusTimestamp of the last successful sbd session
failed_sessionsuint16_tNumber of failed sessions
successful_sessionsuint16_tNumber of successful sessions
signal_qualityuint8_tSignal quality
ring_pendinguint8_tRing call pending
tx_session_pendinguint8_tTransmission session pending
rx_session_pendinguint8_tReceiving session pending

SENSOR_AIRFLOW_ANGLES ( #8016 )

[Message] (MAVLink 2) Calibrated airflow angle measurements

Field NameTypeUnitsDescription
timestampuint64_tusTimestamp
angleofattackfloatdegAngle of attack
angleofattack_validuint8_tAngle of attack measurement valid
sideslipfloatdegSideslip angle
sideslip_validuint8_tSideslip angle measurement valid

results matching ""

    No results matching ""