AHRS: fixed build on ARM
This commit is contained in:
parent
5277dd4b0f
commit
3ac3aeb1b1
@ -198,9 +198,6 @@ protected:
|
||||
// accelerometer values in the earth frame in m/s/s
|
||||
Vector3f _accel_ef;
|
||||
|
||||
// acceleration due to gravity in m/s/s
|
||||
const float _gravity = 9.80665;
|
||||
|
||||
};
|
||||
|
||||
#include <AP_AHRS_DCM.h>
|
||||
|
@ -485,7 +485,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
||||
// equation 9: get the corrected acceleration vector in earth frame. Units
|
||||
// are m/s/s
|
||||
Vector3f GA_e;
|
||||
float v_scale = gps_gain.get()/(_ra_deltat*_gravity);
|
||||
float v_scale = gps_gain.get()/(_ra_deltat*GRAVITY_MSS);
|
||||
Vector3f vdelta = (velocity - _last_velocity) * v_scale;
|
||||
// limit vertical acceleration correction to 0.5 gravities. The
|
||||
// barometer sometimes gives crazy acceleration changes.
|
||||
@ -498,7 +498,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
||||
}
|
||||
|
||||
// calculate the error term in earth frame.
|
||||
Vector3f GA_b = _ra_sum / (_ra_deltat * _gravity);
|
||||
Vector3f GA_b = _ra_sum / (_ra_deltat * GRAVITY_MSS);
|
||||
float length = GA_b.length();
|
||||
if (length > 1.0) {
|
||||
GA_b /= length;
|
||||
|
Loading…
Reference in New Issue
Block a user