mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: Add arming check for incompatible Q_VFWD_GAIN and Q_FWD_THR_USE
This commit is contained in:
parent
daea00168b
commit
6ad7588857
@ -223,6 +223,11 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure)
|
|||||||
ret = false;
|
ret = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if ((plane.quadplane.vel_forward.gain > 0) && (plane.quadplane.q_fwd_thr_use != plane.quadplane.Q_FWD_THR_USE_OFF)) {
|
||||||
|
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "set either Q_VFWD_GAIN or Q_FWD_THR_USE to 0");
|
||||||
|
ret = false;
|
||||||
|
}
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
#endif // HAL_QUADPLANE_ENABLED
|
#endif // HAL_QUADPLANE_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user