DCM: removed the limit on linear acceleration

we get linear accelerations of more than 1g when turning corners
This commit is contained in:
Andrew Tridgell 2012-03-08 00:00:26 +11:00
parent 4f739ea28f
commit 9e07fa3af6
2 changed files with 8 additions and 6 deletions

View File

@ -135,13 +135,14 @@ void
AP_DCM::accel_adjust(Vector3f &accel)
{
float veloc;
// compensate for linear acceleration, limited to 1g
// 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();
acceleration = constrain(acceleration, 0, 9.8);
accel.x -= acceleration;
// compensate for centripetal acceleration
veloc = _gps->ground_speed / 100;
veloc = _gps->ground_speed * 0.01;
// We are working with a modified version of equation 26 as
// our IMU object reports acceleration in the positive axis

View File

@ -495,14 +495,15 @@ void AP_Quaternion::update(void)
accel.z = -accel.z;
if (_centripetal && _gps && _gps->status() == GPS::GPS_OK) {
// compensate for linear acceleration, limited to 1g
// 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();
acceleration = constrain(acceleration, 0, 9.8);
accel.x -= acceleration;
// compensate for centripetal acceleration
float veloc;
veloc = _gps->ground_speed / 100;
veloc = _gps->ground_speed * 0.01;
// be careful of the signs in this calculation. the
// quaternion system uses different signs than the
// rest of APM