AC_AttitudeControl: fix reset_target_and_rate method

This commit is contained in:
Iampete1 2024-02-18 13:00:31 +00:00 committed by Randy Mackay
parent 303c33411f
commit 6c4c7a2130
1 changed files with 2 additions and 2 deletions

View File

@ -934,11 +934,11 @@ void AC_AttitudeControl::reset_target_and_rate(bool reset_rate)
{
// move attitude target to current attitude
_ahrs.get_quat_body_to_ned(_attitude_target);
_attitude_target.to_euler(_euler_angle_target);
if (reset_rate) {
// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
_ang_vel_target.zero();
_euler_angle_target.zero();
_euler_rate_target.zero();
}
}