Copter: remove pointless clause in motor_checks
check_failed doesn't make any state changes and we return true in either case
This commit is contained in:
parent
a5dadd2694
commit
a54321ad12
@ -288,10 +288,6 @@ bool AP_Arming_Copter::motor_checks(bool display_failure)
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
// further checks enabled with parameters
|
||||
if (!check_enabled(ARMING_CHECK_PARAMETERS)) {
|
||||
return true;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user