From bfe71fea82a38c4ed6c1fe239c701be630ec4c26 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 31 Oct 2014 15:07:33 -0700 Subject: [PATCH] AC_PosControl: Use blended accelerometer measurement in altitude control --- libraries/AC_AttitudeControl/AC_PosControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index c849cc0a6a..8073bf4ce1 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -353,7 +353,7 @@ void AC_PosControl::accel_to_throttle(float accel_target_z) int32_t p,i,d; // used to capture pid values for logging // Calculate Earth Frame Z acceleration - z_accel_meas = -(_ahrs.get_accel_ef().z + GRAVITY_MSS) * 100.0f; + z_accel_meas = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f; // reset target altitude if this controller has just been engaged if (_flags.reset_accel_to_throttle) {