From bd9361b7011de401792fb949789edb4247911e8f Mon Sep 17 00:00:00 2001 From: Josh Henderson Date: Wed, 20 Oct 2021 04:32:20 -0400 Subject: [PATCH] AC_AutoTune: INAV rename for neu & cm/cms --- libraries/AC_AutoTune/AC_AutoTune.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_AutoTune/AC_AutoTune.cpp b/libraries/AC_AutoTune/AC_AutoTune.cpp index 750934e6fe..4e6ec92b31 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune.cpp @@ -1671,7 +1671,7 @@ void AC_AutoTune::get_poshold_attitude(float &roll_cd_out, float &pitch_cd_out, if (!have_position) { have_position = true; - start_position = inertial_nav->get_position(); + start_position = inertial_nav->get_position_neu_cm(); } // don't go past 10 degrees, as autotune result would deteriorate too much @@ -1684,7 +1684,7 @@ void AC_AutoTune::get_poshold_attitude(float &roll_cd_out, float &pitch_cd_out, // target position. That corresponds to a lean angle of 2.5 degrees const float yaw_dist_limit_cm = 500; - Vector3f pdiff = inertial_nav->get_position() - start_position; + Vector3f pdiff = inertial_nav->get_position_neu_cm() - start_position; pdiff.z = 0; float dist_cm = pdiff.length(); if (dist_cm < 10) {