Browse Source

Plane: make CIRCLE mode hold altitude

this will prevent us losing a lot of altitude during the initial
failsafe phase
master
Andrew Tridgell 12 years ago
parent
commit
9f70c6c70d
  1. 12
      ArduPlane/ArduPlane.pde
  2. 6
      ArduPlane/system.pde

12
ArduPlane/ArduPlane.pde

@ -1194,14 +1194,12 @@ static void update_current_flight_mode(void)
case CIRCLE: case CIRCLE:
// we have no GPS installed and have lost radio contact // we have no GPS installed and have lost radio contact
// or we just want to fly around in a gentle circle w/o GPS // or we just want to fly around in a gentle circle w/o GPS,
// ---------------------------------------------------- // holding altitude at the altitude we set when we
// switched into the mode
nav_roll_cd = g.roll_limit_cd / 3; nav_roll_cd = g.roll_limit_cd / 3;
nav_pitch_cd = 0; calc_nav_pitch();
calc_throttle();
if (failsafe != FAILSAFE_NONE) {
g.channel_throttle.servo_out = g.throttle_cruise;
}
break; break;
case MANUAL: case MANUAL:

6
ArduPlane/system.pde

@ -337,13 +337,17 @@ static void set_mode(enum FlightMode mode)
{ {
case INITIALISING: case INITIALISING:
case MANUAL: case MANUAL:
case CIRCLE:
case STABILIZE: case STABILIZE:
case TRAINING: case TRAINING:
case FLY_BY_WIRE_A: case FLY_BY_WIRE_A:
case FLY_BY_WIRE_B: case FLY_BY_WIRE_B:
break; break;
case CIRCLE:
// the altitude to circle at is taken from the current altitude
next_WP.alt = current_loc.alt;
break;
case AUTO: case AUTO:
update_auto(); update_auto();
break; break;

Loading…
Cancel
Save