AHRS: avoid a compiler bug in quaternion code

Having _wind in the AP_AHRS class causes a register allocation error
when building the Quaternion code with some versions of avr-gcc. Quite
bizarre.
This commit is contained in:
Andrew Tridgell 2012-08-13 11:08:10 +10:00
parent 455cfa4caa
commit 562069cbd7
2 changed files with 10 additions and 4 deletions

View File

@ -104,10 +104,11 @@ public:
// return a wind estimation vector, in m/s
Vector3f wind_estimate(void) {
return _wind;
return Vector3f(0,0,0);
}
protected:
// pointer to compass object, if available
Compass * _compass;
@ -130,9 +131,6 @@ protected:
// the limit of the gyro drift claimed by the sensors, in
// radians/s/s
float _gyro_drift_limit;
// estimated wind in m/s
Vector3f _wind;
// acceleration due to gravity in m/s/s
static const float _gravity = 9.80665;

View File

@ -53,6 +53,11 @@ public:
// allow for runtime disabling of GPS usage for position
AP_Int8 _gps_use;
// return a wind estimation vector, in m/s
Vector3f wind_estimate(void) {
return _wind;
}
// for holding parameters
static const struct AP_Param::GroupInfo var_info[];
@ -131,6 +136,9 @@ private:
Vector3f _last_vel;
uint32_t _last_wind_time;
float _last_airspeed;
// estimated wind in m/s
Vector3f _wind;
};
#endif // AP_AHRS_DCM_H