AC_Loiter: optimise get-posvelaccel-target usage

This commit is contained in:
Randy Mackay 2024-09-17 13:49:10 +09:00
parent 2753b7030b
commit e20c7edf68
1 changed files with 1 additions and 2 deletions

View File

@ -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;