mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 18:38:28 -04:00
DCM: removed the limit on linear acceleration
we get linear accelerations of more than 1g when turning corners
This commit is contained in:
parent
4f739ea28f
commit
9e07fa3af6
@ -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
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user