Plane: set initial alt target on takeoff completion

this prevents a sudden motor spike at the start of the transition
This commit is contained in:
Andrew Tridgell 2016-09-02 11:09:42 +10:00
parent 232347569f
commit 6849f2223d
1 changed files with 1 additions and 0 deletions

View File

@ -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();