mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
ArduPlane: move estop pre-arm to AP_Arming and add exception
This commit is contained in:
parent
1f94fd69f9
commit
c86c89f05c
@ -106,11 +106,6 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
|
|||||||
ret = false;
|
ret = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (SRV_Channels::get_emergency_stop()) {
|
|
||||||
check_failed(display_failure,"Motors Emergency Stopped");
|
|
||||||
ret = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (plane.g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM){
|
if (plane.g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM){
|
||||||
int16_t trim = plane.channel_throttle->get_radio_trim();
|
int16_t trim = plane.channel_throttle->get_radio_trim();
|
||||||
if (trim < 1250 || trim > 1750) {
|
if (trim < 1250 || trim > 1750) {
|
||||||
|
Loading…
Reference in New Issue
Block a user