From 41a974683e3ecb912f4e3f2e02519c04f9bb9e25 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 14 Aug 2012 18:33:06 +1000 Subject: [PATCH] Quaternion: we no longer support acceleration in the GPS driver remove the linear acceleration compensation code --- libraries/AP_AHRS/AP_AHRS_Quaternion.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_Quaternion.cpp b/libraries/AP_AHRS/AP_AHRS_Quaternion.cpp index d5f375a861..d8c76bcd15 100644 --- a/libraries/AP_AHRS/AP_AHRS_Quaternion.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Quaternion.cpp @@ -316,12 +316,6 @@ void AP_AHRS_Quaternion::update(void) accel = - _imu->get_accel(); if (_fly_forward && _gps && _gps->status() == GPS::GPS_OK) { - // compensate for linear acceleration. This makes a - // surprisingly large difference in the pitch estimate when - // turning, plus on takeoff and landing - float acceleration = _gps->acceleration(); - accel.x += acceleration; - // compensate for centripetal acceleration float veloc; veloc = _gps->ground_speed * 0.01;