Browse Source

Copter: don't disable e-stop if there is no swtich

gps-1.3.1
Iampete1 3 years ago committed by Randy Mackay
parent
commit
4014ec055f
  1. 8
      ArduCopter/AP_Arming.cpp

8
ArduCopter/AP_Arming.cpp

@ -642,12 +642,8 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) @@ -642,12 +642,8 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
return false;
}
// if we are not using Emergency Stop switch option, force Estop false to ensure motors
// can run normally
if (!rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP)){
SRV_Channels::set_emergency_stop(false);
// if we are using motor Estop switch, it must not be in Estop position
} else if (SRV_Channels::get_emergency_stop()){
// if we are using motor Estop switch, it must not be in Estop position
if (SRV_Channels::get_emergency_stop()){
check_failed(true, "Motor Emergency Stopped");
return false;
}

Loading…
Cancel
Save