From 86bb03aa79f93256e5c8bb68116c1c3cc08170fe Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 21 Dec 2015 14:47:27 +0900 Subject: [PATCH] AC_AttControl: use ahrs get_rotation_body_to_ned ahrs.get_dcm_matrix renamed to ahrs.get_rotation_body_to_ned --- libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index 1f81423862..430c22a15b 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -654,7 +654,7 @@ float AC_AttitudeControl::sqrt_controller(float error, float p, float second_ord void AC_AttitudeControl::get_rotation_vehicle_to_ned(Matrix3f& m) { - m = _ahrs.get_dcm_matrix(); + m = _ahrs.get_rotation_body_to_ned(); } void AC_AttitudeControl::get_rotation_ned_to_vehicle(Matrix3f& m)