mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Arming: default throttle pre-arm check to enabled
This commit is contained in:
parent
ad435dcdbb
commit
58463e67c5
@ -545,7 +545,7 @@ bool AP_Arming::rc_arm_checks(AP_Arming::Method method)
|
||||
return true;
|
||||
}
|
||||
|
||||
// only check if we've recieved some form of input within the last second
|
||||
// only check if we've received some form of input within the last second
|
||||
// this is a protection against a vehicle having never enabled an input
|
||||
uint32_t last_input_ms = rc().last_input_ms();
|
||||
if ((last_input_ms == 0) || ((AP_HAL::millis() - last_input_ms) > 1000)) {
|
||||
@ -577,6 +577,7 @@ bool AP_Arming::rc_arm_checks(AP_Arming::Method method)
|
||||
}
|
||||
}
|
||||
|
||||
// if throttle check is enabled, require zero input
|
||||
if (rc().arming_check_throttle()) {
|
||||
RC_Channel *c = rc().channel(rcmap->throttle() - 1);
|
||||
if (c != nullptr) {
|
||||
|
Loading…
Reference in New Issue
Block a user