Browse Source

Copter: Cancel arming if throttle input above cruise_throttle.

mission-4.1.18
Jonathan Challinger 12 years ago committed by Randy Mackay
parent
commit
9f51a4a4f7
  1. 8
      ArduCopter/motors.pde

8
ArduCopter/motors.pde

@ -181,6 +181,14 @@ static void init_arm_motors() @@ -181,6 +181,14 @@ static void init_arm_motors()
piezo_beep_twice();
#endif
// 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();
return;
}
// finally actually arm the motors
motors.armed(true);

Loading…
Cancel
Save