Browse Source

Plane: set initial alt target on takeoff completion

this prevents a sudden motor spike at the start of the transition
master
Andrew Tridgell 9 years ago
parent
commit
6849f2223d
  1. 1
      ArduPlane/quadplane.cpp

1
ArduPlane/quadplane.cpp

@ -1754,6 +1754,7 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd) @@ -1754,6 +1754,7 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd)
}
transition_state = TRANSITION_AIRSPEED_WAIT;
plane.TECS_controller.set_pitch_max_limit(transition_pitch_max);
pos_control->set_alt_target(inertial_nav.get_altitude());
plane.complete_auto_takeoff();

Loading…
Cancel
Save