mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Arming: add pre-arm check for VTOL manual forward throttle
This commit is contained in:
parent
2af6e255d1
commit
285f16e829
@ -578,13 +578,22 @@ bool AP_Arming::rc_arm_checks(AP_Arming::Method method)
|
||||
}
|
||||
|
||||
if (rc().arming_check_throttle()) {
|
||||
const RC_Channel *c = rc().channel(rcmap->throttle() - 1);
|
||||
RC_Channel *c = rc().channel(rcmap->throttle() - 1);
|
||||
if (c != nullptr) {
|
||||
if (c->get_control_in() != 0) {
|
||||
check_failed(ARMING_CHECK_RC, true, "Throttle (RC%d) is not neutral", rcmap->throttle());
|
||||
check_passed = false;
|
||||
}
|
||||
}
|
||||
c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FWD_THR);
|
||||
if (c != nullptr) {
|
||||
uint8_t fwd_thr = c->percent_input();
|
||||
// require channel input within 2% of minimum
|
||||
if (fwd_thr > 2) {
|
||||
check_failed(ARMING_CHECK_RC, true, "VTOL Fwd Throttle is not zero");
|
||||
check_passed = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return check_passed;
|
||||
|
Loading…
Reference in New Issue
Block a user