Skip to content

Commit

Permalink
AC_AttitudeControl: fix reset_target_and_rate method
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and rmackay9 committed Feb 19, 2024
1 parent 303c334 commit 6c4c7a2
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AC_AttitudeControl/AC_AttitudeControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
}

Expand Down

0 comments on commit 6c4c7a2

Please sign in to comment.