diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index f4d0bef687..b7ab34a856 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -39,6 +39,9 @@ public: _gyro_drift_limit = imu->get_gyro_drift_rate(); } + // empty init + virtual void init() {}; + // Accessors void set_fly_forward(bool b) { _fly_forward = b; } void set_compass(Compass *compass) { _compass = compass; } @@ -84,7 +87,7 @@ public: // attitude virtual Matrix3f get_dcm_matrix(void) = 0; - static const struct AP_Param::GroupInfo var_info[]; + //static const struct AP_Param::GroupInfo var_info[]; protected: // pointer to compass object, if enabled @@ -113,6 +116,7 @@ protected: #include #include +#include #include #endif // AP_AHRS_H