From 562069cbd7d7e7a7ef137fd17cb83e6cf9eb598b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Aug 2012 11:08:10 +1000 Subject: [PATCH] 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. --- libraries/AP_AHRS/AP_AHRS.h | 6 ++---- libraries/AP_AHRS/AP_AHRS_DCM.h | 8 ++++++++ 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 9234c803b0..0d44f6d9a1 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -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; diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 95fae8c0cc..885c18f8b7 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -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