From e20c7edf685e63000b7836c0c8cd65f569a36cca Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 17 Sep 2024 13:49:10 +0900 Subject: [PATCH] AC_Loiter: optimise get-posvelaccel-target usage --- libraries/AC_WPNav/AC_Loiter.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AC_WPNav/AC_Loiter.cpp b/libraries/AC_WPNav/AC_Loiter.cpp index aab6fa27f3..6e00781855 100644 --- a/libraries/AC_WPNav/AC_Loiter.cpp +++ b/libraries/AC_WPNav/AC_Loiter.cpp @@ -123,8 +123,7 @@ void AC_Loiter::init_target() _pos_control.relax_velocity_controller_xy(); // initialise predicted acceleration and angles from the position controller - _predicted_accel.x = _pos_control.get_accel_target_cmss().x; - _predicted_accel.y = _pos_control.get_accel_target_cmss().y; + _predicted_accel = _pos_control.get_accel_target_cmss().xy(); _predicted_euler_angle.x = radians(_pos_control.get_roll_cd()*0.01f); _predicted_euler_angle.y = radians(_pos_control.get_pitch_cd()*0.01f); _brake_accel = 0.0f;