Quaternion: we no longer support acceleration in the GPS driver

remove the linear acceleration compensation code
This commit is contained in:
Andrew Tridgell 2012-08-14 18:33:06 +10:00
parent 79aae2114c
commit 41a974683e

View File

@ -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;