Dialect: matrixpilot

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

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

MAV_PREFLIGHT_STORAGE_ACTION

[Enum] Action required when performing CMD_PREFLIGHT_STORAGE

ValueField NameDescription
0MAV_PFS_CMD_READ_ALLRead all parameters from storage
1MAV_PFS_CMD_WRITE_ALLWrite all parameters to storage
2MAV_PFS_CMD_CLEAR_ALLClear all parameters in storage
3MAV_PFS_CMD_READ_SPECIFICRead specific parameters from storage
4MAV_PFS_CMD_WRITE_SPECIFICWrite specific parameters to storage
5MAV_PFS_CMD_CLEAR_SPECIFICClear specific parameters in storage
6MAV_PFS_CMD_DO_NOTHINGdo nothing

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_PREFLIGHT_STORAGE_ADVANCED (0 )

[Command] Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.

Param (:Label)Description
1Storage action: Action defined by MAV_PREFLIGHT_STORAGE_ACTION_ADVANCED
2Storage area as defined by parameter database
3Storage flags as defined by parameter database
4Empty
5Empty
6Empty
7Empty

MAVLink Messages

FLEXIFUNCTION_SET ( #150 )

[Message] Depreciated but used as a compiler flag. Do not remove

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID

FLEXIFUNCTION_READ_REQ ( #151 )

[Message] Request reading of flexifunction data

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
read_req_typeint16_tType of flexifunction data requested
data_indexint16_tindex into data where needed

FLEXIFUNCTION_BUFFER_FUNCTION ( #152 )

[Message] Flexifunction type and parameters for component at function index from buffer

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
func_indexuint16_tFunction index
func_countuint16_tTotal count of functions
data_addressuint16_tAddress in the flexifunction data, Set to 0xFFFF to use address in target memory
data_sizeuint16_tSize of the
dataint8_t[48]Settings data

FLEXIFUNCTION_BUFFER_FUNCTION_ACK ( #153 )

[Message] Flexifunction type and parameters for component at function index from buffer

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
func_indexuint16_tFunction index
resultuint16_tresult of acknowledge, 0=fail, 1=good

FLEXIFUNCTION_DIRECTORY ( #155 )

[Message] Acknowldge success or failure of a flexifunction command

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
directory_typeuint8_t0=inputs, 1=outputs
start_indexuint8_tindex of first directory entry to write
countuint8_tcount of directory entries to write
directory_dataint8_t[48]Settings data

FLEXIFUNCTION_DIRECTORY_ACK ( #156 )

[Message] Acknowldge success or failure of a flexifunction command

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
directory_typeuint8_t0=inputs, 1=outputs
start_indexuint8_tindex of first directory entry to write
countuint8_tcount of directory entries to write
resultuint16_tresult of acknowledge, 0=fail, 1=good

FLEXIFUNCTION_COMMAND ( #157 )

[Message] Acknowldge success or failure of a flexifunction command

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
command_typeuint8_tFlexifunction command type

FLEXIFUNCTION_COMMAND_ACK ( #158 )

[Message] Acknowldge success or failure of a flexifunction command

Field NameTypeDescription
command_typeuint16_tCommand acknowledged
resultuint16_tresult of acknowledge

SERIAL_UDB_EXTRA_F2_A ( #170 )

[Message] Backwards compatible MAVLink version of SERIAL_UDB_EXTRA - F2: Format Part A

Field NameTypeDescription
sue_timeuint32_tSerial UDB Extra Time
sue_statusuint8_tSerial UDB Extra Status
sue_latitudeint32_tSerial UDB Extra Latitude
sue_longitudeint32_tSerial UDB Extra Longitude
sue_altitudeint32_tSerial UDB Extra Altitude
sue_waypoint_indexuint16_tSerial UDB Extra Waypoint Index
sue_rmat0int16_tSerial UDB Extra Rmat 0
sue_rmat1int16_tSerial UDB Extra Rmat 1
sue_rmat2int16_tSerial UDB Extra Rmat 2
sue_rmat3int16_tSerial UDB Extra Rmat 3
sue_rmat4int16_tSerial UDB Extra Rmat 4
sue_rmat5int16_tSerial UDB Extra Rmat 5
sue_rmat6int16_tSerial UDB Extra Rmat 6
sue_rmat7int16_tSerial UDB Extra Rmat 7
sue_rmat8int16_tSerial UDB Extra Rmat 8
sue_coguint16_tSerial UDB Extra GPS Course Over Ground
sue_sogint16_tSerial UDB Extra Speed Over Ground
sue_cpu_loaduint16_tSerial UDB Extra CPU Load
sue_air_speed_3DIMUuint16_tSerial UDB Extra 3D IMU Air Speed
sue_estimated_wind_0int16_tSerial UDB Extra Estimated Wind 0
sue_estimated_wind_1int16_tSerial UDB Extra Estimated Wind 1
sue_estimated_wind_2int16_tSerial UDB Extra Estimated Wind 2
sue_magFieldEarth0int16_tSerial UDB Extra Magnetic Field Earth 0
sue_magFieldEarth1int16_tSerial UDB Extra Magnetic Field Earth 1
sue_magFieldEarth2int16_tSerial UDB Extra Magnetic Field Earth 2
sue_svsint16_tSerial UDB Extra Number of Satellites in View
sue_hdopint16_tSerial UDB Extra GPS Horizontal Dilution of Precision

SERIAL_UDB_EXTRA_F2_B ( #171 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA - F2: Part B

Field NameTypeDescription
sue_timeuint32_tSerial UDB Extra Time
sue_pwm_input_1int16_tSerial UDB Extra PWM Input Channel 1
sue_pwm_input_2int16_tSerial UDB Extra PWM Input Channel 2
sue_pwm_input_3int16_tSerial UDB Extra PWM Input Channel 3
sue_pwm_input_4int16_tSerial UDB Extra PWM Input Channel 4
sue_pwm_input_5int16_tSerial UDB Extra PWM Input Channel 5
sue_pwm_input_6int16_tSerial UDB Extra PWM Input Channel 6
sue_pwm_input_7int16_tSerial UDB Extra PWM Input Channel 7
sue_pwm_input_8int16_tSerial UDB Extra PWM Input Channel 8
sue_pwm_input_9int16_tSerial UDB Extra PWM Input Channel 9
sue_pwm_input_10int16_tSerial UDB Extra PWM Input Channel 10
sue_pwm_input_11int16_tSerial UDB Extra PWM Input Channel 11
sue_pwm_input_12int16_tSerial UDB Extra PWM Input Channel 12
sue_pwm_output_1int16_tSerial UDB Extra PWM Output Channel 1
sue_pwm_output_2int16_tSerial UDB Extra PWM Output Channel 2
sue_pwm_output_3int16_tSerial UDB Extra PWM Output Channel 3
sue_pwm_output_4int16_tSerial UDB Extra PWM Output Channel 4
sue_pwm_output_5int16_tSerial UDB Extra PWM Output Channel 5
sue_pwm_output_6int16_tSerial UDB Extra PWM Output Channel 6
sue_pwm_output_7int16_tSerial UDB Extra PWM Output Channel 7
sue_pwm_output_8int16_tSerial UDB Extra PWM Output Channel 8
sue_pwm_output_9int16_tSerial UDB Extra PWM Output Channel 9
sue_pwm_output_10int16_tSerial UDB Extra PWM Output Channel 10
sue_pwm_output_11int16_tSerial UDB Extra PWM Output Channel 11
sue_pwm_output_12int16_tSerial UDB Extra PWM Output Channel 12
sue_imu_location_xint16_tSerial UDB Extra IMU Location X
sue_imu_location_yint16_tSerial UDB Extra IMU Location Y
sue_imu_location_zint16_tSerial UDB Extra IMU Location Z
sue_location_error_earth_xint16_tSerial UDB Location Error Earth X
sue_location_error_earth_yint16_tSerial UDB Location Error Earth Y
sue_location_error_earth_zint16_tSerial UDB Location Error Earth Z
sue_flagsuint32_tSerial UDB Extra Status Flags
sue_osc_failsint16_tSerial UDB Extra Oscillator Failure Count
sue_imu_velocity_xint16_tSerial UDB Extra IMU Velocity X
sue_imu_velocity_yint16_tSerial UDB Extra IMU Velocity Y
sue_imu_velocity_zint16_tSerial UDB Extra IMU Velocity Z
sue_waypoint_goal_xint16_tSerial UDB Extra Current Waypoint Goal X
sue_waypoint_goal_yint16_tSerial UDB Extra Current Waypoint Goal Y
sue_waypoint_goal_zint16_tSerial UDB Extra Current Waypoint Goal Z
sue_aero_xint16_tAeroforce in UDB X Axis
sue_aero_yint16_tAeroforce in UDB Y Axis
sue_aero_zint16_tAeroforce in UDB Z axis
sue_barom_tempint16_tSUE barometer temperature
sue_barom_pressint32_tSUE barometer pressure
sue_barom_altint32_tSUE barometer altitude
sue_bat_voltint16_tSUE battery voltage
sue_bat_ampint16_tSUE battery current
sue_bat_amp_hoursint16_tSUE battery milli amp hours used
sue_desired_heightint16_tSue autopilot desired height
sue_memory_stack_freeint16_tSerial UDB Extra Stack Memory Free

SERIAL_UDB_EXTRA_F4 ( #172 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F4: format

Field NameTypeDescription
sue_ROLL_STABILIZATION_AILERONSuint8_tSerial UDB Extra Roll Stabilization with Ailerons Enabled
sue_ROLL_STABILIZATION_RUDDERuint8_tSerial UDB Extra Roll Stabilization with Rudder Enabled
sue_PITCH_STABILIZATIONuint8_tSerial UDB Extra Pitch Stabilization Enabled
sue_YAW_STABILIZATION_RUDDERuint8_tSerial UDB Extra Yaw Stabilization using Rudder Enabled
sue_YAW_STABILIZATION_AILERONuint8_tSerial UDB Extra Yaw Stabilization using Ailerons Enabled
sue_AILERON_NAVIGATIONuint8_tSerial UDB Extra Navigation with Ailerons Enabled
sue_RUDDER_NAVIGATIONuint8_tSerial UDB Extra Navigation with Rudder Enabled
sue_ALTITUDEHOLD_STABILIZEDuint8_tSerial UDB Extra Type of Alitude Hold when in Stabilized Mode
sue_ALTITUDEHOLD_WAYPOINTuint8_tSerial UDB Extra Type of Alitude Hold when in Waypoint Mode
sue_RACING_MODEuint8_tSerial UDB Extra Firmware racing mode enabled

SERIAL_UDB_EXTRA_F5 ( #173 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F5: format

Field NameTypeDescription
sue_YAWKP_AILERONfloatSerial UDB YAWKP_AILERON Gain for Proporional control of navigation
sue_YAWKD_AILERONfloatSerial UDB YAWKD_AILERON Gain for Rate control of navigation
sue_ROLLKPfloatSerial UDB Extra ROLLKP Gain for Proportional control of roll stabilization
sue_ROLLKDfloatSerial UDB Extra ROLLKD Gain for Rate control of roll stabilization

SERIAL_UDB_EXTRA_F6 ( #174 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F6: format

Field NameTypeDescription
sue_PITCHGAINfloatSerial UDB Extra PITCHGAIN Proportional Control
sue_PITCHKDfloatSerial UDB Extra Pitch Rate Control
sue_RUDDER_ELEV_MIXfloatSerial UDB Extra Rudder to Elevator Mix
sue_ROLL_ELEV_MIXfloatSerial UDB Extra Roll to Elevator Mix
sue_ELEVATOR_BOOSTfloatGain For Boosting Manual Elevator control When Plane Stabilized

SERIAL_UDB_EXTRA_F7 ( #175 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F7: format

Field NameTypeDescription
sue_YAWKP_RUDDERfloatSerial UDB YAWKP_RUDDER Gain for Proporional control of navigation
sue_YAWKD_RUDDERfloatSerial UDB YAWKD_RUDDER Gain for Rate control of navigation
sue_ROLLKP_RUDDERfloatSerial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization
sue_ROLLKD_RUDDERfloatSerial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization
sue_RUDDER_BOOSTfloatSERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized
sue_RTL_PITCH_DOWNfloatSerial UDB Extra Return To Landing - Angle to Pitch Plane Down

SERIAL_UDB_EXTRA_F8 ( #176 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F8: format

Field NameTypeDescription
sue_HEIGHT_TARGET_MAXfloatSerial UDB Extra HEIGHT_TARGET_MAX
sue_HEIGHT_TARGET_MINfloatSerial UDB Extra HEIGHT_TARGET_MIN
sue_ALT_HOLD_THROTTLE_MINfloatSerial UDB Extra ALT_HOLD_THROTTLE_MIN
sue_ALT_HOLD_THROTTLE_MAXfloatSerial UDB Extra ALT_HOLD_THROTTLE_MAX
sue_ALT_HOLD_PITCH_MINfloatSerial UDB Extra ALT_HOLD_PITCH_MIN
sue_ALT_HOLD_PITCH_MAXfloatSerial UDB Extra ALT_HOLD_PITCH_MAX
sue_ALT_HOLD_PITCH_HIGHfloatSerial UDB Extra ALT_HOLD_PITCH_HIGH

SERIAL_UDB_EXTRA_F13 ( #177 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F13: format

Field NameTypeDescription
sue_week_noint16_tSerial UDB Extra GPS Week Number
sue_lat_originint32_tSerial UDB Extra MP Origin Latitude
sue_lon_originint32_tSerial UDB Extra MP Origin Longitude
sue_alt_originint32_tSerial UDB Extra MP Origin Altitude Above Sea Level

SERIAL_UDB_EXTRA_F14 ( #178 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F14: format

Field NameTypeDescription
sue_WIND_ESTIMATIONuint8_tSerial UDB Extra Wind Estimation Enabled
sue_GPS_TYPEuint8_tSerial UDB Extra Type of GPS Unit
sue_DRuint8_tSerial UDB Extra Dead Reckoning Enabled
sue_BOARD_TYPEuint8_tSerial UDB Extra Type of UDB Hardware
sue_AIRFRAMEuint8_tSerial UDB Extra Type of Airframe
sue_RCONint16_tSerial UDB Extra Reboot Register of DSPIC
sue_TRAP_FLAGSint16_tSerial UDB Extra Last dspic Trap Flags
sue_TRAP_SOURCEuint32_tSerial UDB Extra Type Program Address of Last Trap
sue_osc_fail_countint16_tSerial UDB Extra Number of Ocillator Failures
sue_CLOCK_CONFIGuint8_tSerial UDB Extra UDB Internal Clock Configuration
sue_FLIGHT_PLAN_TYPEuint8_tSerial UDB Extra Type of Flight Plan

SERIAL_UDB_EXTRA_F15 ( #179 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F15 format

Field NameTypeDescription
sue_ID_VEHICLE_MODEL_NAMEuint8_t[40]Serial UDB Extra Model Name Of Vehicle
sue_ID_VEHICLE_REGISTRATIONuint8_t[20]Serial UDB Extra Registraton Number of Vehicle

SERIAL_UDB_EXTRA_F16 ( #180 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F16 format

Field NameTypeDescription
sue_ID_LEAD_PILOTuint8_t[40]Serial UDB Extra Name of Expected Lead Pilot
sue_ID_DIY_DRONES_URLuint8_t[70]Serial UDB Extra URL of Lead Pilot or Team

ALTITUDES ( #181 )

[Message] The altitude measured by sensors and IMU

Field NameTypeDescription
time_boot_msuint32_tTimestamp (milliseconds since system boot)
alt_gpsint32_tGPS altitude (MSL) in meters, expressed as * 1000 (millimeters)
alt_imuint32_tIMU altitude above ground in meters, expressed as * 1000 (millimeters)
alt_barometricint32_tbarometeric altitude above ground in meters, expressed as * 1000 (millimeters)
alt_optical_flowint32_tOptical flow altitude above ground in meters, expressed as * 1000 (millimeters)
alt_range_finderint32_tRangefinder Altitude above ground in meters, expressed as * 1000 (millimeters)
alt_extraint32_tExtra altitude above ground in meters, expressed as * 1000 (millimeters)

AIRSPEEDS ( #182 )

[Message] The airspeed measured by sensors and IMU

Field NameTypeDescription
time_boot_msuint32_tTimestamp (milliseconds since system boot)
airspeed_imuint16_tAirspeed estimate from IMU, cm/s
airspeed_pitotint16_tPitot measured forward airpseed, cm/s
airspeed_hot_wireint16_tHot wire anenometer measured airspeed, cm/s
airspeed_ultrasonicint16_tUltrasonic measured airspeed, cm/s
aoaint16_tAngle of attack sensor, degrees * 10
aoyint16_tYaw angle sensor, degrees * 10

SERIAL_UDB_EXTRA_F17 ( #183 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F17 format

Field NameTypeDescription
sue_feed_forwardfloatSUE Feed Forward Gain
sue_turn_rate_navfloatSUE Max Turn Rate when Navigating
sue_turn_rate_fbwfloatSUE Max Turn Rate in Fly By Wire Mode

SERIAL_UDB_EXTRA_F18 ( #184 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F18 format

Field NameTypeDescription
angle_of_attack_normalfloatSUE Angle of Attack Normal
angle_of_attack_invertedfloatSUE Angle of Attack Inverted
elevator_trim_normalfloatSUE Elevator Trim Normal
elevator_trim_invertedfloatSUE Elevator Trim Inverted
reference_speedfloatSUE reference_speed

SERIAL_UDB_EXTRA_F19 ( #185 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F19 format

Field NameTypeDescription
sue_aileron_output_channeluint8_tSUE aileron output channel
sue_aileron_reverseduint8_tSUE aileron reversed
sue_elevator_output_channeluint8_tSUE elevator output channel
sue_elevator_reverseduint8_tSUE elevator reversed
sue_throttle_output_channeluint8_tSUE throttle output channel
sue_throttle_reverseduint8_tSUE throttle reversed
sue_rudder_output_channeluint8_tSUE rudder output channel
sue_rudder_reverseduint8_tSUE rudder reversed

SERIAL_UDB_EXTRA_F20 ( #186 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F20 format

Field NameTypeDescription
sue_number_of_inputsuint8_tSUE Number of Input Channels
sue_trim_value_input_1int16_tSUE UDB PWM Trim Value on Input 1
sue_trim_value_input_2int16_tSUE UDB PWM Trim Value on Input 2
sue_trim_value_input_3int16_tSUE UDB PWM Trim Value on Input 3
sue_trim_value_input_4int16_tSUE UDB PWM Trim Value on Input 4
sue_trim_value_input_5int16_tSUE UDB PWM Trim Value on Input 5
sue_trim_value_input_6int16_tSUE UDB PWM Trim Value on Input 6
sue_trim_value_input_7int16_tSUE UDB PWM Trim Value on Input 7
sue_trim_value_input_8int16_tSUE UDB PWM Trim Value on Input 8
sue_trim_value_input_9int16_tSUE UDB PWM Trim Value on Input 9
sue_trim_value_input_10int16_tSUE UDB PWM Trim Value on Input 10
sue_trim_value_input_11int16_tSUE UDB PWM Trim Value on Input 11
sue_trim_value_input_12int16_tSUE UDB PWM Trim Value on Input 12

SERIAL_UDB_EXTRA_F21 ( #187 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F21 format

Field NameTypeDescription
sue_accel_x_offsetint16_tSUE X accelerometer offset
sue_accel_y_offsetint16_tSUE Y accelerometer offset
sue_accel_z_offsetint16_tSUE Z accelerometer offset
sue_gyro_x_offsetint16_tSUE X gyro offset
sue_gyro_y_offsetint16_tSUE Y gyro offset
sue_gyro_z_offsetint16_tSUE Z gyro offset

SERIAL_UDB_EXTRA_F22 ( #188 )

[Message] Backwards compatible version of SERIAL_UDB_EXTRA F22 format

Field NameTypeDescription
sue_accel_x_at_calibrationint16_tSUE X accelerometer at calibration time
sue_accel_y_at_calibrationint16_tSUE Y accelerometer at calibration time
sue_accel_z_at_calibrationint16_tSUE Z accelerometer at calibration time
sue_gyro_x_at_calibrationint16_tSUE X gyro at calibration time
sue_gyro_y_at_calibrationint16_tSUE Y gyro at calibration time
sue_gyro_z_at_calibrationint16_tSUE Z gyro at calibration time

results matching ""

    No results matching ""