Browse Source

Copter: fix Helicopter no-build issue

Conflict with another recent change to disarm counter
master
Robert Lefebvre 9 years ago committed by Randy Mackay
parent
commit
2b111c2bd6
  1. 2
      ArduCopter/motors.cpp

2
ArduCopter/motors.cpp

@ -85,7 +85,7 @@ void Copter::auto_disarm_check()
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
// if the rotor is still spinning, don't initiate auto disarm // if the rotor is still spinning, don't initiate auto disarm
if (motors.rotor_speed_above_critical()) { if (motors.rotor_speed_above_critical()) {
auto_disarming_counter = 0; auto_disarm_begin = tnow_ms;
return; return;
} }
#endif #endif

Loading…
Cancel
Save