mirror of https://github.com/ArduPilot/ardupilot
Copter: add pre-arm check of PILOT_SPEED_UP param
This commit is contained in:
parent
3ebc69320c
commit
6e27d49f24
|
@ -172,6 +172,12 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
|||
}
|
||||
#endif
|
||||
|
||||
// pilot-speed-up parameter check
|
||||
if (copter.g.pilot_speed_up <= 0) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check PILOT_SPEED_UP");
|
||||
return false;
|
||||
}
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
if (copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD &&
|
||||
copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_DUAL &&
|
||||
|
|
Loading…
Reference in New Issue