AC_WPNav: WPNAV_LOIT_SPEED WPNAV_LOIT_MAXA take effect immediately

This commit is contained in:
Jonathan Challinger 2015-04-29 17:23:45 -07:00 committed by Randy Mackay
parent 674bedd867
commit f9c7f15052

View File

@ -330,6 +330,11 @@ void AC_WPNav::update_loiter(float ekfGndSpdLimit, float ekfNavVelGainScaler)
// initialise ekf position reset check
check_for_ekf_position_reset();
// initialise pos controller speed and acceleration
_pos_control.set_speed_xy(_loiter_speed_cms);
_pos_control.set_accel_xy(_loiter_accel_cmss);
_pos_control.set_jerk_xy(_loiter_jerk_max_cmsss);
calc_loiter_desired_velocity(dt,ekfGndSpdLimit);
_pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_LIMITED_AND_VEL_FF, ekfNavVelGainScaler, true);
}