AC_AttitudeControl: use vector.xy().length() instead of norm(x,y)

This commit is contained in:
Josh Henderson 2021-09-11 06:28:01 -04:00 committed by Andrew Tridgell
parent d6d9577f27
commit a3e475822b

View File

@ -312,7 +312,7 @@ void AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(float roll_pass
// add desired target to yaw // add desired target to yaw
_ang_vel_body.z += _ang_vel_target.z; _ang_vel_body.z += _ang_vel_target.z;
_thrust_error_angle = norm(_att_error_rot_vec_rad.x, _att_error_rot_vec_rad.y); _thrust_error_angle = _att_error_rot_vec_rad.xy().length();
} }
void AC_AttitudeControl_Heli::integrate_bf_rate_error_to_angle_errors() void AC_AttitudeControl_Heli::integrate_bf_rate_error_to_angle_errors()