diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index 2c240f8792..4da7108c6b 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -395,7 +395,7 @@ protected: float get_throttle_with_vibration_override(); // get earth-frame Z-axis acceleration with gravity removed in cm/s/s with +ve being up - float get_z_accel_cmss() const { return -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f; } + float get_z_accel_cmss() const { return -(_ahrs.get_accel_ef().z + GRAVITY_MSS) * 100.0f; } // lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s void accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float& roll_target, float& pitch_target) const;