Browse Source

Plane: unlock roll and pitch when we enter ACRO mode

master
Andrew Tridgell 12 years ago
parent
commit
826ad6c086
  1. 6
      ArduPlane/system.pde

6
ArduPlane/system.pde

@ -340,10 +340,14 @@ static void set_mode(enum FlightMode mode) @@ -340,10 +340,14 @@ static void set_mode(enum FlightMode mode)
case MANUAL:
case STABILIZE:
case TRAINING:
case ACRO:
case FLY_BY_WIRE_A:
break;
case ACRO:
acro_state.locked_roll = false;
acro_state.locked_pitch = false;
break;
case FLY_BY_WIRE_B:
target_altitude_cm = current_loc.alt;
break;

Loading…
Cancel
Save