From 031be010accbaf615d0fa037875f18aa1239c282 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 4 Jan 2021 11:57:14 +0900 Subject: [PATCH] AC_AttitudeControl: tailsitter sets target rates more efficiently --- libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp index 4b1dfdecd9..ee192eb40f 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp @@ -120,8 +120,8 @@ void AC_AttitudeControl_TS::input_euler_rate_yaw_euler_angle_pitch_bf_roll(bool // _attitude_target_euler_angle.y = euler_pitch; // Set rate feedforward requests to zero - _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f); - _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f); + _attitude_target_euler_rate.zero(); + _attitude_target_ang_vel.zero(); // Compute attitude error error_quat = attitude_vehicle_quat.inverse() * _attitude_target_quat;