From 05eb72342999a0ffa2db4f51f754033eeb128576 Mon Sep 17 00:00:00 2001
From: Jonathan Challinger <mr.challinger@gmail.com>
Date: Thu, 10 Dec 2015 14:06:37 -0800
Subject: [PATCH] Plane: reflect renamed function in AP_AHRS

---
 ArduPlane/altitude.cpp   | 2 +-
 ArduPlane/navigation.cpp | 2 +-
 ArduPlane/test.cpp       | 2 +-
 3 files changed, 3 insertions(+), 3 deletions(-)

diff --git a/ArduPlane/altitude.cpp b/ArduPlane/altitude.cpp
index 1e7c68d762..2b517def70 100644
--- a/ArduPlane/altitude.cpp
+++ b/ArduPlane/altitude.cpp
@@ -561,7 +561,7 @@ void Plane::rangefinder_height_update(void)
         }
         // correct the range for attitude (multiply by DCM.c.z, which
         // is cos(roll)*cos(pitch))
-        height_estimate = distance * ahrs.get_dcm_matrix().c.z;
+        height_estimate = distance * ahrs.get_rotation_body_to_ned().c.z;
 
         // we consider ourselves to be fully in range when we have 10
         // good samples (0.2s) that are different by 5% of the maximum
diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp
index a4fce858f4..2bffc9060b 100644
--- a/ArduPlane/navigation.cpp
+++ b/ArduPlane/navigation.cpp
@@ -118,7 +118,7 @@ void Plane::calc_gndspeed_undershoot()
 	// This prevents flyaway if wind takes plane backwards
     if (gps.status() >= AP_GPS::GPS_OK_FIX_2D) {
 	    Vector2f gndVel = ahrs.groundspeed_vector();
-		const Matrix3f &rotMat = ahrs.get_dcm_matrix();
+		const Matrix3f &rotMat = ahrs.get_rotation_body_to_ned();
 		Vector2f yawVect = Vector2f(rotMat.a.x,rotMat.b.x);
 		yawVect.normalize();
 		float gndSpdFwd = yawVect * gndVel;
diff --git a/ArduPlane/test.cpp b/ArduPlane/test.cpp
index 9dfbdfcc91..fb9dc3af0a 100644
--- a/ArduPlane/test.cpp
+++ b/ArduPlane/test.cpp
@@ -431,7 +431,7 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
             if(counter % 5 == 0) {
                 if (compass.read()) {
                     // Calculate heading
-                    const Matrix3f &m = ahrs.get_dcm_matrix();
+                    const Matrix3f &m = ahrs.get_rotation_body_to_ned();
                     heading = compass.calculate_heading(m);
                     compass.learn_offsets();
                 }