ArduPlane: move estop pre-arm to AP_Arming and add exception

This commit is contained in:
Henry Wurzburg 2023-04-10 07:08:01 -05:00 committed by Andrew Tridgell
parent 1f94fd69f9
commit c86c89f05c
1 changed files with 0 additions and 5 deletions

View File

@ -106,11 +106,6 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
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){
int16_t trim = plane.channel_throttle->get_radio_trim();
if (trim < 1250 || trim > 1750) {