3 ### MSP2_INAV_MC_BRAKING / MSP2_INAV_SET_MC_BRAKING
5 New MSP frames used to setup mixer properties.
9 * MSP2_INAV_MC_BRAKING, Frame ID _0x200B_
10 * MSP2_INAV_SET_MC_BRAKING, Frame ID _0x200C_
12 | Length | Setting | Notes |
13 | ----- | ----- | ----- |
14 | 2 | `nav_mc_braking_speed_threshold` | |
15 | 2 | `nav_mc_braking_disengage_speed` | |
16 | 2 | `nav_mc_braking_timeout` | |
17 | 1 | `nav_mc_braking_boost_factor` | |
18 | 2 | `nav_mc_braking_boost_timeout` | |
19 | 2 | `nav_mc_braking_boost_speed_threshold` | |
20 | 2 | `nav_mc_braking_boost_disengage_speed` | |
21 | 1 | `nav_mc_braking_bank_angle` | |
24 ## MSP API Version 2.2
26 Since `mixerMode` is no longer used, legacy MSP frames will return always **mixer mode** *3 (QuadX)* and attempt to set mixer mode via MSP will be ignored. This affects following MSP frames:
34 ### MSP2_INAV_MIXER / MSP2_INAV_SET_MIXER
36 New MSP frames used to setup mixer properties.
40 * MSP2_INAV_MIXER, Frame ID _0x2010_
41 * MSP2_INAV_SET_MIXER, Frame ID _0x2011_
43 | Length | Setting | Notes |
44 | ----- | ----- | ----- |
45 | 1 | `yaw_motor_direction` | |
46 | 2 | `yaw_jump_prevention_limit` | |
47 | 1 | `platform_type` | |
50 ## INAV 1.9 MSP Version 2.1
52 ### MSP2_COMMON_MOTOR_MIXER / MSP2_COMMON_SET_MOTOR_MIXER
56 * MMSP2_COMMON_MOTOR_MIXER, Frame ID _0x1005_
57 * MSP2_COMMON_SET_MOTOR_MIXER, Frame ID _0x1006_
59 ## INAV 1.7.1 MSP API Version 1.26
61 ### MSP_FW_CONFIG / MSP_SET_FW_CONFIG
63 Get and set Fixed Wing options
67 * MSP_FW_CONFIG, Frame ID _23_
68 * MSP_SET_FW_CONFIG, Frame ID _24_
70 | Length | Setting | Notes |
71 | ----- | ----- | ----- |
72 | 2 | `nav_fw_cruise_thr` | |
73 | 2 | `nav_fw_min_thr` | |
74 | 2 | `nav_fw_max_thr` | |
75 | 1 | `nav_fw_bank_angle` | |
76 | 1 | `nav_fw_climb_angle` | |
77 | 1 | `nav_fw_dive_angle` | |
78 | 1 | `nav_fw_pitch2thr` | |
79 | 2 | `nav_fw_loiter_radius` | |
81 ### MSP_RTH_AND_LAND_CONFIG / MSP_SET_RTH_AND_LAND_CONFIG
83 Get and set Return-To-Home and Land options
87 * MSP_RTH_AND_LAND_CONFIG, Frame ID _21_
88 * MSP_SET_RTH_AND_LAND_CONFIG, Frame ID _22_
90 | Length | Setting | Notes |
91 | ----- | ----- | ----- |
92 | 2 | `nav_min_rth_distance` | |
93 | 1 | `nav_rth_climb_first` | _boolean_ |
94 | 1 | `nav_rth_climb_ignore_emerg` | _boolean_ |
95 | 1 | `nav_rth_tail_first` | _boolean_ |
96 | 1 | `nav_rth_allow_landing` | _boolean_ |
97 | 1 | `nav_rth_alt_mode` | _dictionary_ |
98 | 2 | `nav_rth_abort_threshold` | |
99 | 2 | `nav_rth_altitude` | |
100 | 2 | `nav_landing_speed` | |
101 | 2 | `nav_land_slowdown_minalt` | |
102 | 2 | `nav_land_slowdown_maxalt` | |
103 | 2 | `nav_emerg_landing_speed` | |
105 ## INAV 1.6 MSP API Version 1.24
107 ### MSP_WP_MISSION_LOAD / MSP_WP_MISSION_SAVE
109 Load/save waypoint mission to non-volatile storage
113 * MSP_WP_MISSION_LOAD, Frame ID _18_
114 * MSP_WP_MISSION_SAVE, Frame ID _19_
118 | 1 | Mission ID (reserved) |
121 ### MSP_POSITION_ESTIMATION_CONFIG
125 * MSP_POSITION_ESTIMATION_CONFIG, Frame ID _16_
126 * MSP_SET_POSITION_ESTIMATION_CONFIG, Frame ID _17_
128 | Length | Setting | Notes |
129 | ----- | ----- | ----- |
130 | 2 | `inav_w_z_baro_p` | float as `value * 100` |
131 | 2 | `inav_w_z_gps_p` | float as `value * 100` |
132 | 2 | `inav_w_z_gps_v` | float as `value * 100` |
133 | 2 | `inav_w_xy_gps_p` | float as `value * 100` |
134 | 2 | `inav_w_xy_gps_v` | float as `value * 100` |
135 | 1 | `inav_gps_min_sats` | |
136 | 1 | `inav_use_gps_velned` | ON/OFF |
140 ### MSP_CALIBRATION_DATA
142 Sensors calibration data
144 | Length | Setting | Notes |
145 | ----- | ----- | ----- |
146 | 2 | `acczero_x` | |
147 | 2 | `acczero_y` | |
148 | 2 | `acczero_z` | |
149 | 2 | `accgain_x` | |
150 | 2 | `accgain_y` | |
151 | 2 | `accgain_z` | |
152 | 2 | `magzero_x` | |
153 | 2 | `magzero_y` | |
154 | 2 | `magzero_z` | |
159 * MSP_CALIBRATION_DATA, Frame ID _14_
160 * MSP_SET_CALIBRATION_DATA, Frame ID _15_
164 Basic position hold settings. Mostly, but not only, for multirotor
168 * MSP_NAV_POSHOLD, Frame ID _12_
169 * MSP_SET_NAV_POSHOLD, Frame ID _13_
171 | Length | Setting | Notes |
172 | ----- | ----- | ----- |
173 | 1 | `nav_user_control_mode` | dictionary |
174 | 2 | `nav_max_speed` | |
175 | 2 | `nav_max_climb_rate` | |
176 | 2 | `nav_manual_speed` | |
177 | 2 | `nav_manual_climb_rate` | |
178 | 1 | `nav_mc_bank_angle` | |
179 | 1 | `nav_use_midthr_for_althold` | ON/OFF |
180 | 2 | `nav_mc_hover_thr` | |
183 ## INAV 1.5 MSP API Version 1.23
185 For INAV 1.5 and later, the MSP_STATUS/sensor field reports sensor failure. This updates MSP_SENSOR (see http://www.multiwii.com/wiki/index.php?title=Multiwii_Serial_Protocol) in a backwards compatible manner to report additional sensors and sensor health. The sensor field is reported as:
189 | 0 | Set if ACC present |
190 | 1 | Set if BARO present |
191 | 2 | Set if MAG present |
192 | 3 | Set if GPS present |
193 | 4 | Set if SONAR present |
194 | 5 | Reserved for OPFLOW (not implemented) |
195 | 6 | Set if PITOT present |
196 | 15 | Set on sensor failure |
198 The sensor hardware failure indication is backwards compatible with versions prior to 1.5 (and other Multiwii / Cleanflight derivatives).
200 ### MSP_SENSOR_CONFIG
204 * MSP_SENSOR_CONFIG, Frame ID _96_
205 * MSP_SET_SENSOR_CONFIG, Frame ID _97_
207 | length | setting | Notes |
208 | ---- | ---- | ---- |
209 | 1 | `acc_hardware` | |
210 | 1 | `baro_hardware` | |
211 | 1 | `mag_hardware` | |
212 | 1 | `pitot_hardware` | |
213 | 1 | Reserved for rangefinder | not yet implemented |
214 | 1 | Reserved for OpFlow | not yet implemented |
216 ## INAV 1.4 MSP API Version 1.22
222 * MSP_INAV_PID, Frame ID _6_
223 * MSP_SET_INAV_PID, Frame ID _7_
225 | length | setting | Notes |
226 | ---- | ---- | ---- |
227 | 1 | `async_mode` | |
228 | 2 | `acc_task_frequency` | |
229 | 2 | `attitude_task_frequency` | |
230 | 1 | `mag_hold_rate_limit` | |
231 | 1 | MAG_HOLD_ERROR_LPF_FREQ | not implemented yet as configurable |
232 | 2 | `yaw_jump_prevention_limit` | |
234 | 1 | `acc_soft_lpf_hz` | |
235 | 4 | _reserved_ | reserved for further usage |
239 Compatible with Betaflight
243 * MSP_FILTER_CONFIG Frame ID _92_
244 * MSP_SET_FILTER_CONFIG Frame ID _93_
246 | length | setting | Notes |
247 | ---- | ---- | ---- |
248 | 1 | `gyro_soft_lpf_hz` | |
249 | 2 | `dterm_lpf_hz` | |
250 | 2 | `yaw_lpf_hz` | |
251 | 2 | `gyro_soft_notch_hz_1` | Since INAV 1.6 |
252 | 2 | `gyro_soft_notch_cutoff_1` | Since INAV 1.6 |
253 | 2 | `dterm_soft_notch_hz` | Since INAV 1.6 |
254 | 2 | `dterm_soft_notch_cutoff` | Since INAV 1.6 |
255 | 2 | `gyro_soft_notch_hz_2` | Since INAV 1.6 |
256 | 2 | `gyro_soft_notch_cutoff_2` | Since INAV 1.6 |
260 Compatible with Betaflight
264 * MSP_PID_ADVANCED Frame ID _94_
265 * MSP_SET_PID_ADVANCED Frame ID _95_
267 | length | setting | Notes |
268 | ---- | ---- | ---- |
269 | 2 | `rollPitchItermIgnoreRate` | |
270 | 2 | `yawItermIgnoreRate` | |
271 | 2 | `yaw_p_limit` | |
272 | 1 | _not used_ | Betaflight `deltaMethod` |
273 | 1 | _not used_ | Betaflight `vbatPidCompensation` |
274 | 1 | _not used_ | Betaflight `setpointRelaxRatio` |
275 | 1 | `dterm_setpoint_weight` | Since INAV 1.6 |
276 | 2 | `pidsum_limit` | Since INAV 1.6 |
277 | 1 | _not used_ | Betaflight `itermThrottleGain` |
278 | 2 | `rate_accel_limit_roll_pitch` | divided by `10` |
279 | 2 | `rate_accel_limit_yaw` | divided by `10` |
281 ## INAV 1.3 MSP API 1.21
283 ### case MSP_ADVANCED_CONFIG:
287 * MSP_ADVANCED_CONFIG, Frame ID _90_
288 * MSP_SET_ADVANCED_CONFIG, Frame ID _91_
290 | length | setting | Notes |
291 | ---- | ---- | ---- |
292 | 1 | `gyro_sync_denom` | |
293 | 1 | _not used_ | Betaflight `masterConfig.pid_process_denom` |
294 | 1 | _not used_ | Betaflight `masterConfig.motorConfig.useUnsyncedPwm` |
295 | 1 | `motor_pwm_protocol` | _dictionary_ |
296 | 2 | `motor_pwm_rate` | |
297 | 2 | `servo_pwm_rate` | |
298 | 1 | `gyro_sync` | _boolean_ |
302 * 2016-11-20 - scaling of `rate_accel_limit_roll_pitch` and `rate_accel_limit_yaw` in **MSP_PID_ADVANCED** changed from 1000 to 10
303 * 2016-12-11 - added MSP_STATUS update for INAV 1.5
304 * 2017-01-15 - added dterm_setpoint_weight added to MSP_PID_ADVANCED frame
305 * 2017-01-15 - MSP_CALIBRATION_DATA
306 * 2017-01-18 - `pidsum_limit` in `MSP_PID_ADVANCED`
307 * 2017-01-23 - MSP_POSITION_ESTIMATOR