Browse Source

Plane: setup immediate pitch limit on quadplane takeoff

this prevents a single loop with large pitch down demand
master
Andrew Tridgell 9 years ago
parent
commit
b1266603a6
  1. 1
      ArduPlane/quadplane.cpp

1
ArduPlane/quadplane.cpp

@ -1182,6 +1182,7 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd) @@ -1182,6 +1182,7 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd)
return false;
}
transition_state = TRANSITION_AIRSPEED_WAIT;
plane.TECS_controller.set_pitch_max_limit(transition_pitch_max);
return true;
}

Loading…
Cancel
Save