mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_AttitudeControl: remove duplicate _attitude_target.normalize()
This commit is contained in:
parent
d398e567a3
commit
14a786bdfa
@ -726,7 +726,6 @@ void AC_AttitudeControl::attitude_controller_run_quat()
|
||||
Quaternion attitude_target_update;
|
||||
attitude_target_update.from_axis_angle(Vector3f{_ang_vel_target.x * _dt, _ang_vel_target.y * _dt, _ang_vel_target.z * _dt});
|
||||
_attitude_target = _attitude_target * attitude_target_update;
|
||||
_attitude_target.normalize();
|
||||
}
|
||||
|
||||
// ensure Quaternion stay normalised
|
||||
|
Loading…
Reference in New Issue
Block a user