mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: remove thr check during init_arm_motors
This check is redundant now that we have a check within the arm_check() function. Removing this check does raise a slight danger that someone could raise the throttle after arming but before the gyro and baro calibration has completed but the delay has been greatly shortened from what it once was so there is much less danger that someone could approach the vehicle during the short arming delay.
This commit is contained in:
parent
5720bff29f
commit
a12d9109e0
@ -182,16 +182,6 @@ static void init_arm_motors()
|
||||
// set hover throttle
|
||||
motors.set_mid_throttle(g.throttle_mid);
|
||||
|
||||
// Cancel arming if throttle is raised too high so that copter does not suddenly take off
|
||||
read_radio();
|
||||
if (g.rc_3.control_in > g.throttle_cruise && g.throttle_cruise > 100) {
|
||||
motors.output_min();
|
||||
failsafe_enable();
|
||||
AP_Notify::flags.armed = false;
|
||||
AP_Notify::flags.arming_failed = false;
|
||||
return;
|
||||
}
|
||||
|
||||
#if SPRAYER == ENABLED
|
||||
// turn off sprayer's test if on
|
||||
sprayer.test_pump(false);
|
||||
|
Loading…
Reference in New Issue
Block a user