From 9a453bfc82554e62b2686752efe5caca0c7a310f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 27 Jul 2022 10:21:30 +1000 Subject: [PATCH] APM_Control: removed use of "blended" earth frame accel --- libraries/APM_Control/AR_PosControl.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/APM_Control/AR_PosControl.cpp b/libraries/APM_Control/AR_PosControl.cpp index fad162d756..07b7754108 100644 --- a/libraries/APM_Control/AR_PosControl.cpp +++ b/libraries/APM_Control/AR_PosControl.cpp @@ -244,7 +244,7 @@ bool AR_PosControl::init() // set target velocity and acceleration _vel_desired = vel_NED.xy(); _vel_target.zero(); - _accel_desired = AP::ahrs().get_accel_ef_blended().xy(); + _accel_desired = AP::ahrs().get_accel_ef().xy(); _accel_target.zero(); // clear reversed setting @@ -335,7 +335,7 @@ void AR_PosControl::write_log() } // get acceleration - const Vector3f curr_accel_NED = AP::ahrs().get_accel_ef_blended() * 100.0; + const Vector3f curr_accel_NED = AP::ahrs().get_accel_ef() * 100.0; // convert position to required format Vector2f pos_target_2d_cm = get_pos_target().tofloat() * 100.0;