forked from mavlink/mavlink
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmatrixpilot.xml
349 lines (348 loc) · 26.6 KB
/
matrixpilot.xml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
<?xml version="1.0"?>
<mavlink>
<include>common.xml</include>
<!-- note that UDB specific messages should use the command id
range from 150 to 250, to leave plenty of room for growth
of common.xml
If you prototype a message here, then you should consider if it
is general enough to move into common.xml later
-->
<enums>
<enum name="MAV_PREFLIGHT_STORAGE_ACTION">
<description>Action required when performing CMD_PREFLIGHT_STORAGE</description>
<entry value="0" name="MAV_PFS_CMD_READ_ALL">
<description>Read all parameters from storage</description>
</entry>
<entry value="1" name="MAV_PFS_CMD_WRITE_ALL">
<description>Write all parameters to storage</description>
</entry>
<entry value="2" name="MAV_PFS_CMD_CLEAR_ALL">
<description>Clear all parameters in storage</description>
</entry>
<entry value="3" name="MAV_PFS_CMD_READ_SPECIFIC">
<description>Read specific parameters from storage</description>
</entry>
<entry value="4" name="MAV_PFS_CMD_WRITE_SPECIFIC">
<description>Write specific parameters to storage</description>
</entry>
<entry value="5" name="MAV_PFS_CMD_CLEAR_SPECIFIC">
<description>Clear specific parameters in storage</description>
</entry>
<entry value="6" name="MAV_PFS_CMD_DO_NOTHING">
<description>do nothing</description>
</entry>
</enum>
<enum name="MAV_CMD">
<entry value="0" name="MAV_CMD_PREFLIGHT_STORAGE_ADVANCED">
<description>Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.</description>
<param index="1">Storage action: Action defined by MAV_PREFLIGHT_STORAGE_ACTION_ADVANCED</param>
<param index="2">Storage area as defined by parameter database</param>
<param index="3">Storage flags as defined by parameter database</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
</enum>
</enums>
<messages>
<message id="150" name="FLEXIFUNCTION_SET">
<description>Depreciated but used as a compiler flag. Do not remove</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
</message>
<message id="151" name="FLEXIFUNCTION_READ_REQ">
<description>Request reading of flexifunction data</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="int16_t" name="read_req_type">Type of flexifunction data requested</field>
<field type="int16_t" name="data_index">index into data where needed</field>
</message>
<message id="152" name="FLEXIFUNCTION_BUFFER_FUNCTION">
<description>Flexifunction type and parameters for component at function index from buffer</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="func_index">Function index</field>
<field type="uint16_t" name="func_count">Total count of functions</field>
<field type="uint16_t" name="data_address">Address in the flexifunction data, Set to 0xFFFF to use address in target memory</field>
<field type="uint16_t" name="data_size">Size of the </field>
<field type="int8_t[48]" name="data">Settings data</field>
</message>
<message id="153" name="FLEXIFUNCTION_BUFFER_FUNCTION_ACK">
<description>Flexifunction type and parameters for component at function index from buffer</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="func_index">Function index</field>
<field type="uint16_t" name="result">result of acknowledge, 0=fail, 1=good</field>
</message>
<message id="155" name="FLEXIFUNCTION_DIRECTORY">
<description>Acknowldge success or failure of a flexifunction command</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="directory_type">0=inputs, 1=outputs</field>
<field type="uint8_t" name="start_index">index of first directory entry to write</field>
<field type="uint8_t" name="count">count of directory entries to write</field>
<field type="int8_t[48]" name="directory_data">Settings data</field>
</message>
<message id="156" name="FLEXIFUNCTION_DIRECTORY_ACK">
<description>Acknowldge success or failure of a flexifunction command</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="directory_type">0=inputs, 1=outputs</field>
<field type="uint8_t" name="start_index">index of first directory entry to write</field>
<field type="uint8_t" name="count">count of directory entries to write</field>
<field type="uint16_t" name="result">result of acknowledge, 0=fail, 1=good</field>
</message>
<message id="157" name="FLEXIFUNCTION_COMMAND">
<description>Acknowldge success or failure of a flexifunction command</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="command_type">Flexifunction command type</field>
</message>
<message id="158" name="FLEXIFUNCTION_COMMAND_ACK">
<description>Acknowldge success or failure of a flexifunction command</description>
<field type="uint16_t" name="command_type">Command acknowledged</field>
<field type="uint16_t" name="result">result of acknowledge</field>
</message>
<message id="170" name="SERIAL_UDB_EXTRA_F2_A">
<description>Backwards compatible MAVLink version of SERIAL_UDB_EXTRA - F2: Format Part A</description>
<field type="uint32_t" name="sue_time">Serial UDB Extra Time</field>
<field type="uint8_t" name="sue_status">Serial UDB Extra Status</field>
<field type="int32_t" name="sue_latitude">Serial UDB Extra Latitude</field>
<field type="int32_t" name="sue_longitude">Serial UDB Extra Longitude</field>
<field type="int32_t" name="sue_altitude">Serial UDB Extra Altitude</field>
<field type="uint16_t" name="sue_waypoint_index">Serial UDB Extra Waypoint Index</field>
<field type="int16_t" name="sue_rmat0">Serial UDB Extra Rmat 0</field>
<field type="int16_t" name="sue_rmat1">Serial UDB Extra Rmat 1</field>
<field type="int16_t" name="sue_rmat2">Serial UDB Extra Rmat 2</field>
<field type="int16_t" name="sue_rmat3">Serial UDB Extra Rmat 3</field>
<field type="int16_t" name="sue_rmat4">Serial UDB Extra Rmat 4</field>
<field type="int16_t" name="sue_rmat5">Serial UDB Extra Rmat 5</field>
<field type="int16_t" name="sue_rmat6">Serial UDB Extra Rmat 6</field>
<field type="int16_t" name="sue_rmat7">Serial UDB Extra Rmat 7</field>
<field type="int16_t" name="sue_rmat8">Serial UDB Extra Rmat 8</field>
<field type="uint16_t" name="sue_cog">Serial UDB Extra GPS Course Over Ground</field>
<field type="int16_t" name="sue_sog">Serial UDB Extra Speed Over Ground</field>
<field type="uint16_t" name="sue_cpu_load">Serial UDB Extra CPU Load</field>
<field type="uint16_t" name="sue_air_speed_3DIMU">Serial UDB Extra 3D IMU Air Speed</field>
<field type="int16_t" name="sue_estimated_wind_0">Serial UDB Extra Estimated Wind 0</field>
<field type="int16_t" name="sue_estimated_wind_1">Serial UDB Extra Estimated Wind 1</field>
<field type="int16_t" name="sue_estimated_wind_2">Serial UDB Extra Estimated Wind 2</field>
<field type="int16_t" name="sue_magFieldEarth0">Serial UDB Extra Magnetic Field Earth 0 </field>
<field type="int16_t" name="sue_magFieldEarth1">Serial UDB Extra Magnetic Field Earth 1 </field>
<field type="int16_t" name="sue_magFieldEarth2">Serial UDB Extra Magnetic Field Earth 2 </field>
<field type="int16_t" name="sue_svs">Serial UDB Extra Number of Satellites in View</field>
<field type="int16_t" name="sue_hdop">Serial UDB Extra GPS Horizontal Dilution of Precision</field>
</message>
<message id="171" name="SERIAL_UDB_EXTRA_F2_B">
<description>Backwards compatible version of SERIAL_UDB_EXTRA - F2: Part B</description>
<field type="uint32_t" name="sue_time">Serial UDB Extra Time</field>
<field type="int16_t" name="sue_pwm_input_1">Serial UDB Extra PWM Input Channel 1</field>
<field type="int16_t" name="sue_pwm_input_2">Serial UDB Extra PWM Input Channel 2</field>
<field type="int16_t" name="sue_pwm_input_3">Serial UDB Extra PWM Input Channel 3</field>
<field type="int16_t" name="sue_pwm_input_4">Serial UDB Extra PWM Input Channel 4</field>
<field type="int16_t" name="sue_pwm_input_5">Serial UDB Extra PWM Input Channel 5</field>
<field type="int16_t" name="sue_pwm_input_6">Serial UDB Extra PWM Input Channel 6</field>
<field type="int16_t" name="sue_pwm_input_7">Serial UDB Extra PWM Input Channel 7</field>
<field type="int16_t" name="sue_pwm_input_8">Serial UDB Extra PWM Input Channel 8</field>
<field type="int16_t" name="sue_pwm_input_9">Serial UDB Extra PWM Input Channel 9</field>
<field type="int16_t" name="sue_pwm_input_10">Serial UDB Extra PWM Input Channel 10</field>
<field type="int16_t" name="sue_pwm_input_11">Serial UDB Extra PWM Input Channel 11</field>
<field type="int16_t" name="sue_pwm_input_12">Serial UDB Extra PWM Input Channel 12</field>
<field type="int16_t" name="sue_pwm_output_1">Serial UDB Extra PWM Output Channel 1</field>
<field type="int16_t" name="sue_pwm_output_2">Serial UDB Extra PWM Output Channel 2</field>
<field type="int16_t" name="sue_pwm_output_3">Serial UDB Extra PWM Output Channel 3</field>
<field type="int16_t" name="sue_pwm_output_4">Serial UDB Extra PWM Output Channel 4</field>
<field type="int16_t" name="sue_pwm_output_5">Serial UDB Extra PWM Output Channel 5</field>
<field type="int16_t" name="sue_pwm_output_6">Serial UDB Extra PWM Output Channel 6</field>
<field type="int16_t" name="sue_pwm_output_7">Serial UDB Extra PWM Output Channel 7</field>
<field type="int16_t" name="sue_pwm_output_8">Serial UDB Extra PWM Output Channel 8</field>
<field type="int16_t" name="sue_pwm_output_9">Serial UDB Extra PWM Output Channel 9</field>
<field type="int16_t" name="sue_pwm_output_10">Serial UDB Extra PWM Output Channel 10</field>
<field type="int16_t" name="sue_pwm_output_11">Serial UDB Extra PWM Output Channel 11</field>
<field type="int16_t" name="sue_pwm_output_12">Serial UDB Extra PWM Output Channel 12</field>
<field type="int16_t" name="sue_imu_location_x">Serial UDB Extra IMU Location X</field>
<field type="int16_t" name="sue_imu_location_y">Serial UDB Extra IMU Location Y</field>
<field type="int16_t" name="sue_imu_location_z">Serial UDB Extra IMU Location Z</field>
<field type="int16_t" name="sue_location_error_earth_x">Serial UDB Location Error Earth X</field>
<field type="int16_t" name="sue_location_error_earth_y">Serial UDB Location Error Earth Y</field>
<field type="int16_t" name="sue_location_error_earth_z">Serial UDB Location Error Earth Z</field>
<field type="uint32_t" name="sue_flags">Serial UDB Extra Status Flags</field>
<field type="int16_t" name="sue_osc_fails">Serial UDB Extra Oscillator Failure Count</field>
<field type="int16_t" name="sue_imu_velocity_x">Serial UDB Extra IMU Velocity X</field>
<field type="int16_t" name="sue_imu_velocity_y">Serial UDB Extra IMU Velocity Y</field>
<field type="int16_t" name="sue_imu_velocity_z">Serial UDB Extra IMU Velocity Z</field>
<field type="int16_t" name="sue_waypoint_goal_x">Serial UDB Extra Current Waypoint Goal X</field>
<field type="int16_t" name="sue_waypoint_goal_y">Serial UDB Extra Current Waypoint Goal Y</field>
<field type="int16_t" name="sue_waypoint_goal_z">Serial UDB Extra Current Waypoint Goal Z</field>
<field type="int16_t" name="sue_aero_x">Aeroforce in UDB X Axis</field>
<field type="int16_t" name="sue_aero_y">Aeroforce in UDB Y Axis</field>
<field type="int16_t" name="sue_aero_z">Aeroforce in UDB Z axis</field>
<field type="int16_t" name="sue_barom_temp">SUE barometer temperature</field>
<field type="int32_t" name="sue_barom_press">SUE barometer pressure</field>
<field type="int32_t" name="sue_barom_alt">SUE barometer altitude</field>
<field type="int16_t" name="sue_bat_volt">SUE battery voltage</field>
<field type="int16_t" name="sue_bat_amp">SUE battery current</field>
<field type="int16_t" name="sue_bat_amp_hours">SUE battery milli amp hours used</field>
<field type="int16_t" name="sue_desired_height">Sue autopilot desired height</field>
<field type="int16_t" name="sue_memory_stack_free">Serial UDB Extra Stack Memory Free</field>
</message>
<message id="172" name="SERIAL_UDB_EXTRA_F4">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F4: format</description>
<field type="uint8_t" name="sue_ROLL_STABILIZATION_AILERONS">Serial UDB Extra Roll Stabilization with Ailerons Enabled</field>
<field type="uint8_t" name="sue_ROLL_STABILIZATION_RUDDER">Serial UDB Extra Roll Stabilization with Rudder Enabled</field>
<field type="uint8_t" name="sue_PITCH_STABILIZATION">Serial UDB Extra Pitch Stabilization Enabled</field>
<field type="uint8_t" name="sue_YAW_STABILIZATION_RUDDER">Serial UDB Extra Yaw Stabilization using Rudder Enabled</field>
<field type="uint8_t" name="sue_YAW_STABILIZATION_AILERON">Serial UDB Extra Yaw Stabilization using Ailerons Enabled</field>
<field type="uint8_t" name="sue_AILERON_NAVIGATION">Serial UDB Extra Navigation with Ailerons Enabled</field>
<field type="uint8_t" name="sue_RUDDER_NAVIGATION">Serial UDB Extra Navigation with Rudder Enabled</field>
<field type="uint8_t" name="sue_ALTITUDEHOLD_STABILIZED">Serial UDB Extra Type of Alitude Hold when in Stabilized Mode</field>
<field type="uint8_t" name="sue_ALTITUDEHOLD_WAYPOINT">Serial UDB Extra Type of Alitude Hold when in Waypoint Mode</field>
<field type="uint8_t" name="sue_RACING_MODE">Serial UDB Extra Firmware racing mode enabled</field>
</message>
<message id="173" name="SERIAL_UDB_EXTRA_F5">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F5: format</description>
<field type="float" name="sue_YAWKP_AILERON">Serial UDB YAWKP_AILERON Gain for Proporional control of navigation</field>
<field type="float" name="sue_YAWKD_AILERON">Serial UDB YAWKD_AILERON Gain for Rate control of navigation</field>
<field type="float" name="sue_ROLLKP">Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization</field>
<field type="float" name="sue_ROLLKD">Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization</field>
</message>
<message id="174" name="SERIAL_UDB_EXTRA_F6">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F6: format</description>
<field type="float" name="sue_PITCHGAIN">Serial UDB Extra PITCHGAIN Proportional Control</field>
<field type="float" name="sue_PITCHKD">Serial UDB Extra Pitch Rate Control</field>
<field type="float" name="sue_RUDDER_ELEV_MIX">Serial UDB Extra Rudder to Elevator Mix</field>
<field type="float" name="sue_ROLL_ELEV_MIX">Serial UDB Extra Roll to Elevator Mix</field>
<field type="float" name="sue_ELEVATOR_BOOST">Gain For Boosting Manual Elevator control When Plane Stabilized</field>
</message>
<message id="175" name="SERIAL_UDB_EXTRA_F7">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F7: format</description>
<field type="float" name="sue_YAWKP_RUDDER">Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation</field>
<field type="float" name="sue_YAWKD_RUDDER">Serial UDB YAWKD_RUDDER Gain for Rate control of navigation</field>
<field type="float" name="sue_ROLLKP_RUDDER">Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization</field>
<field type="float" name="sue_ROLLKD_RUDDER">Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization</field>
<field type="float" name="sue_RUDDER_BOOST">SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized</field>
<field type="float" name="sue_RTL_PITCH_DOWN">Serial UDB Extra Return To Landing - Angle to Pitch Plane Down</field>
</message>
<message id="176" name="SERIAL_UDB_EXTRA_F8">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F8: format</description>
<field type="float" name="sue_HEIGHT_TARGET_MAX">Serial UDB Extra HEIGHT_TARGET_MAX</field>
<field type="float" name="sue_HEIGHT_TARGET_MIN">Serial UDB Extra HEIGHT_TARGET_MIN</field>
<field type="float" name="sue_ALT_HOLD_THROTTLE_MIN">Serial UDB Extra ALT_HOLD_THROTTLE_MIN</field>
<field type="float" name="sue_ALT_HOLD_THROTTLE_MAX">Serial UDB Extra ALT_HOLD_THROTTLE_MAX</field>
<field type="float" name="sue_ALT_HOLD_PITCH_MIN">Serial UDB Extra ALT_HOLD_PITCH_MIN</field>
<field type="float" name="sue_ALT_HOLD_PITCH_MAX">Serial UDB Extra ALT_HOLD_PITCH_MAX</field>
<field type="float" name="sue_ALT_HOLD_PITCH_HIGH">Serial UDB Extra ALT_HOLD_PITCH_HIGH</field>
</message>
<message id="177" name="SERIAL_UDB_EXTRA_F13">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F13: format</description>
<field type="int16_t" name="sue_week_no">Serial UDB Extra GPS Week Number</field>
<field type="int32_t" name="sue_lat_origin">Serial UDB Extra MP Origin Latitude</field>
<field type="int32_t" name="sue_lon_origin">Serial UDB Extra MP Origin Longitude</field>
<field type="int32_t" name="sue_alt_origin">Serial UDB Extra MP Origin Altitude Above Sea Level</field>
</message>
<message id="178" name="SERIAL_UDB_EXTRA_F14">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F14: format</description>
<field type="uint8_t" name="sue_WIND_ESTIMATION">Serial UDB Extra Wind Estimation Enabled</field>
<field type="uint8_t" name="sue_GPS_TYPE">Serial UDB Extra Type of GPS Unit</field>
<field type="uint8_t" name="sue_DR">Serial UDB Extra Dead Reckoning Enabled</field>
<field type="uint8_t" name="sue_BOARD_TYPE">Serial UDB Extra Type of UDB Hardware</field>
<field type="uint8_t" name="sue_AIRFRAME">Serial UDB Extra Type of Airframe</field>
<field type="int16_t" name="sue_RCON">Serial UDB Extra Reboot Register of DSPIC</field>
<field type="int16_t" name="sue_TRAP_FLAGS">Serial UDB Extra Last dspic Trap Flags</field>
<field type="uint32_t" name="sue_TRAP_SOURCE">Serial UDB Extra Type Program Address of Last Trap</field>
<field type="int16_t" name="sue_osc_fail_count">Serial UDB Extra Number of Ocillator Failures</field>
<field type="uint8_t" name="sue_CLOCK_CONFIG">Serial UDB Extra UDB Internal Clock Configuration</field>
<field type="uint8_t" name="sue_FLIGHT_PLAN_TYPE">Serial UDB Extra Type of Flight Plan</field>
</message>
<message id="179" name="SERIAL_UDB_EXTRA_F15">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F15 format</description>
<field type="uint8_t[40]" name="sue_ID_VEHICLE_MODEL_NAME">Serial UDB Extra Model Name Of Vehicle</field>
<field type="uint8_t[20]" name="sue_ID_VEHICLE_REGISTRATION">Serial UDB Extra Registraton Number of Vehicle</field>
</message>
<message id="180" name="SERIAL_UDB_EXTRA_F16">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F16 format</description>
<field type="uint8_t[40]" name="sue_ID_LEAD_PILOT">Serial UDB Extra Name of Expected Lead Pilot</field>
<field type="uint8_t[70]" name="sue_ID_DIY_DRONES_URL">Serial UDB Extra URL of Lead Pilot or Team</field>
</message>
<message id="181" name="ALTITUDES">
<description>The altitude measured by sensors and IMU</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="int32_t" name="alt_gps">GPS altitude (MSL) in meters, expressed as * 1000 (millimeters)</field>
<field type="int32_t" name="alt_imu">IMU altitude above ground in meters, expressed as * 1000 (millimeters)</field>
<field type="int32_t" name="alt_barometric">barometeric altitude above ground in meters, expressed as * 1000 (millimeters)</field>
<field type="int32_t" name="alt_optical_flow">Optical flow altitude above ground in meters, expressed as * 1000 (millimeters)</field>
<field type="int32_t" name="alt_range_finder">Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters)</field>
<field type="int32_t" name="alt_extra">Extra altitude above ground in meters, expressed as * 1000 (millimeters)</field>
</message>
<message id="182" name="AIRSPEEDS">
<description>The airspeed measured by sensors and IMU</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="int16_t" name="airspeed_imu">Airspeed estimate from IMU, cm/s</field>
<field type="int16_t" name="airspeed_pitot">Pitot measured forward airpseed, cm/s</field>
<field type="int16_t" name="airspeed_hot_wire">Hot wire anenometer measured airspeed, cm/s</field>
<field type="int16_t" name="airspeed_ultrasonic">Ultrasonic measured airspeed, cm/s</field>
<field type="int16_t" name="aoa">Angle of attack sensor, degrees * 10</field>
<field type="int16_t" name="aoy">Yaw angle sensor, degrees * 10</field>
</message>
<message id="183" name="SERIAL_UDB_EXTRA_F17">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F17 format</description>
<field type="float" name="sue_feed_forward">SUE Feed Forward Gain</field>
<field type="float" name="sue_turn_rate_nav">SUE Max Turn Rate when Navigating</field>
<field type="float" name="sue_turn_rate_fbw">SUE Max Turn Rate in Fly By Wire Mode</field>
</message>
<message id="184" name="SERIAL_UDB_EXTRA_F18">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F18 format</description>
<field type="float" name="angle_of_attack_normal">SUE Angle of Attack Normal</field>
<field type="float" name="angle_of_attack_inverted">SUE Angle of Attack Inverted</field>
<field type="float" name="elevator_trim_normal">SUE Elevator Trim Normal</field>
<field type="float" name="elevator_trim_inverted">SUE Elevator Trim Inverted</field>
<field type="float" name="reference_speed">SUE reference_speed</field>
</message>
<message id="185" name="SERIAL_UDB_EXTRA_F19">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F19 format</description>
<field type="uint8_t" name="sue_aileron_output_channel">SUE aileron output channel</field>
<field type="uint8_t" name="sue_aileron_reversed">SUE aileron reversed</field>
<field type="uint8_t" name="sue_elevator_output_channel">SUE elevator output channel</field>
<field type="uint8_t" name="sue_elevator_reversed">SUE elevator reversed</field>
<field type="uint8_t" name="sue_throttle_output_channel">SUE throttle output channel</field>
<field type="uint8_t" name="sue_throttle_reversed">SUE throttle reversed</field>
<field type="uint8_t" name="sue_rudder_output_channel">SUE rudder output channel</field>
<field type="uint8_t" name="sue_rudder_reversed">SUE rudder reversed</field>
</message>
<message id="186" name="SERIAL_UDB_EXTRA_F20">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F20 format</description>
<field type="uint8_t" name="sue_number_of_inputs">SUE Number of Input Channels</field>
<field type="int16_t" name="sue_trim_value_input_1">SUE UDB PWM Trim Value on Input 1</field>
<field type="int16_t" name="sue_trim_value_input_2">SUE UDB PWM Trim Value on Input 2</field>
<field type="int16_t" name="sue_trim_value_input_3">SUE UDB PWM Trim Value on Input 3</field>
<field type="int16_t" name="sue_trim_value_input_4">SUE UDB PWM Trim Value on Input 4</field>
<field type="int16_t" name="sue_trim_value_input_5">SUE UDB PWM Trim Value on Input 5</field>
<field type="int16_t" name="sue_trim_value_input_6">SUE UDB PWM Trim Value on Input 6</field>
<field type="int16_t" name="sue_trim_value_input_7">SUE UDB PWM Trim Value on Input 7</field>
<field type="int16_t" name="sue_trim_value_input_8">SUE UDB PWM Trim Value on Input 8</field>
<field type="int16_t" name="sue_trim_value_input_9">SUE UDB PWM Trim Value on Input 9</field>
<field type="int16_t" name="sue_trim_value_input_10">SUE UDB PWM Trim Value on Input 10</field>
<field type="int16_t" name="sue_trim_value_input_11">SUE UDB PWM Trim Value on Input 11</field>
<field type="int16_t" name="sue_trim_value_input_12">SUE UDB PWM Trim Value on Input 12</field>
</message>
<message id="187" name="SERIAL_UDB_EXTRA_F21">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F21 format</description>
<field type="int16_t" name="sue_accel_x_offset">SUE X accelerometer offset</field>
<field type="int16_t" name="sue_accel_y_offset">SUE Y accelerometer offset</field>
<field type="int16_t" name="sue_accel_z_offset">SUE Z accelerometer offset</field>
<field type="int16_t" name="sue_gyro_x_offset">SUE X gyro offset</field>
<field type="int16_t" name="sue_gyro_y_offset">SUE Y gyro offset</field>
<field type="int16_t" name="sue_gyro_z_offset">SUE Z gyro offset</field>
</message>
<message id="188" name="SERIAL_UDB_EXTRA_F22">
<description>Backwards compatible version of SERIAL_UDB_EXTRA F22 format</description>
<field type="int16_t" name="sue_accel_x_at_calibration">SUE X accelerometer at calibration time</field>
<field type="int16_t" name="sue_accel_y_at_calibration">SUE Y accelerometer at calibration time</field>
<field type="int16_t" name="sue_accel_z_at_calibration">SUE Z accelerometer at calibration time</field>
<field type="int16_t" name="sue_gyro_x_at_calibration">SUE X gyro at calibration time</field>
<field type="int16_t" name="sue_gyro_y_at_calibration">SUE Y gyro at calibration time</field>
<field type="int16_t" name="sue_gyro_z_at_calibration">SUE Z gyro at calibration time</field>
</message>
</messages>
</mavlink>