AC_PosControl: update init for guided

This commit is contained in:
Leonard Hall 2017-11-12 22:52:53 +10:30 committed by Randy Mackay
parent 85b7f06554
commit bd13704f6f
1 changed files with 3 additions and 0 deletions

View File

@ -842,6 +842,9 @@ void AC_PosControl::init_vel_controller_xyz()
const Vector3f& curr_vel = _inav.get_velocity();
set_desired_velocity(curr_vel);
// set vehicle acceleration to zero
set_desired_accel_xy(0.0f,0.0f);
// initialise ekf reset handlers
init_ekf_xy_reset();
init_ekf_z_reset();