mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
Quaternion: we no longer support acceleration in the GPS driver
remove the linear acceleration compensation code
This commit is contained in:
parent
79aae2114c
commit
41a974683e
@ -316,12 +316,6 @@ void AP_AHRS_Quaternion::update(void)
|
|||||||
accel = - _imu->get_accel();
|
accel = - _imu->get_accel();
|
||||||
|
|
||||||
if (_fly_forward && _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
|
|
||||||
float acceleration = _gps->acceleration();
|
|
||||||
accel.x += acceleration;
|
|
||||||
|
|
||||||
// compensate for centripetal acceleration
|
// compensate for centripetal acceleration
|
||||||
float veloc;
|
float veloc;
|
||||||
veloc = _gps->ground_speed * 0.01;
|
veloc = _gps->ground_speed * 0.01;
|
||||||
|
Loading…
Reference in New Issue
Block a user