Browse Source

Copter: allow arming, disarming in Hybrid mode

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
d36f137bf8
  1. 4
      ArduCopter/motors.pde

4
ArduCopter/motors.pde

@ -24,7 +24,7 @@ static void arm_motors_check() @@ -24,7 +24,7 @@ static void arm_motors_check()
}
// allow arming/disarming in Loiter and AltHold if landed
if (ap.land_complete && (control_mode == LOITER || control_mode == ALT_HOLD)) {
if (ap.land_complete && (control_mode == LOITER || control_mode == ALT_HOLD || control_mode == HYBRID)) {
allow_arming = true;
}
@ -103,7 +103,7 @@ static void auto_disarm_check() @@ -103,7 +103,7 @@ static void auto_disarm_check()
}
// allow auto disarm in manual flight modes or Loiter/AltHold if we're landed
if(manual_flight_mode(control_mode) || (ap.land_complete && (control_mode == LOITER || control_mode == ALT_HOLD))) {
if(manual_flight_mode(control_mode) || (ap.land_complete && (control_mode == LOITER || control_mode == ALT_HOLD || control_mode == HYBRID))) {
auto_disarming_counter++;
if(auto_disarming_counter >= AUTO_DISARMING_DELAY) {

Loading…
Cancel
Save