Plane: Smoother transition to QLOITER and QLAND

Use estimated stopping position
This commit is contained in:
Ferruccio Vicari 2017-09-19 09:28:45 +02:00 committed by Andrew Tridgell
parent 1a724ded2a
commit 85ab3edc5f

View File

@ -832,8 +832,9 @@ void QuadPlane::control_hover(void)
void QuadPlane::init_loiter(void)
{
// set target to current position
wp_nav->init_loiter_target();
Vector3f stopping_point;
wp_nav->get_loiter_stopping_point_xy(stopping_point);
wp_nav->init_loiter_target(stopping_point);
// initialize vertical speed and acceleration
pos_control->set_speed_z(-pilot_velocity_z_max, pilot_velocity_z_max);