mirror of https://github.com/ArduPilot/ardupilot
Copter: Pre-arm check for mot_pwm
This commit is contained in:
parent
5a78cd44bd
commit
83828e2e06
|
@ -144,6 +144,14 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
|||
// check various parameter values
|
||||
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_PARAMETERS)) {
|
||||
|
||||
// checks MOT_PWM_MIN/MAX for acceptable values
|
||||
#if (FRAME_CONFIG != HELI_FRAME)
|
||||
if (copter.motors->check_mot_pwm_params()) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check MOT_PWM_MAX/MIN");
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
// ensure all rc channels have different functions
|
||||
if (rc().duplicate_options_exist()) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Duplicate Aux Switch Options");
|
||||
|
|
Loading…
Reference in New Issue