From b0c5d9efd0dabcaed278b00b7a996c41bb9cc2b1 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Sat, 20 Jul 2013 18:00:36 +0900
Subject: [PATCH] AP_AHRS: use rotateXY for speed

Saves 0.1ms at 100hz
---
 libraries/AP_AHRS/AP_AHRS_DCM.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp
index c9f085d63..c51a71c87 100644
--- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp
+++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp
@@ -420,7 +420,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
     drift_correction_yaw();
 
     // apply trim
-    temp_dcm.rotate(_trim);
+    temp_dcm.rotateXY(_trim);
 
     // rotate accelerometer values into the earth frame
     _accel_ef = temp_dcm * _accel_vector;
-- 
GitLab