mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 22:18:28 -04:00
AC_WPNav: AC_Loiter: Fix loiter level bug
This commit is contained in:
parent
67fd2b6856
commit
af54acd202
@ -118,8 +118,8 @@ void AC_Loiter::init_target()
|
|||||||
_pos_control.set_correction_speed_accel_xy(LOITER_VEL_CORRECTION_MAX, _accel_cmss);
|
_pos_control.set_correction_speed_accel_xy(LOITER_VEL_CORRECTION_MAX, _accel_cmss);
|
||||||
_pos_control.set_pos_error_max_xy_cm(LOITER_POS_CORRECTION_MAX);
|
_pos_control.set_pos_error_max_xy_cm(LOITER_POS_CORRECTION_MAX);
|
||||||
|
|
||||||
// initialise position controller
|
// initialise position controller and move target accelerations smoothly towards zero
|
||||||
_pos_control.init_xy_controller();
|
_pos_control.relax_velocity_controller_xy();
|
||||||
|
|
||||||
// initialise predicted acceleration and angles from the position controller
|
// initialise predicted acceleration and angles from the position controller
|
||||||
_predicted_accel.x = _pos_control.get_accel_target_cmss().x;
|
_predicted_accel.x = _pos_control.get_accel_target_cmss().x;
|
||||||
|
Loading…
Reference in New Issue
Block a user