AHRS: update for new _fly_forward flag

This commit is contained in:
Andrew Tridgell 2012-03-26 12:57:48 +11:00
parent 2600afe18a
commit 0399aa9480

View File

@ -325,7 +325,7 @@ void AP_AHRS_Quaternion::update(void)
// the quaternion system uses opposite sign for accel
accel = - _imu->get_accel();
if (_centripetal && _gps && _gps->status() == GPS::GPS_OK) {
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