diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index ed52980623ef51..716c2d7ea07e47 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -131,11 +131,11 @@ class AP_AHRS { #endif } - void external_wind_estimate(float speed, float direction) { #if AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED + void external_wind_estimate(float speed, float direction) { dcm.external_wind_estimate(speed, direction); -#endif } +#endif // return the parameter AHRS_WIND_MAX in metres per second uint8_t get_max_wind() const { diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index e48e2657fa9a23..04a70ad693e57a 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -1028,6 +1028,7 @@ void AP_AHRS_DCM::estimate_wind(void) #endif } +#ifdef AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED void AP_AHRS_DCM::external_wind_estimate(float speed, float direction) { Vector3f wind = Vector3f(); wind.z = 0; @@ -1037,6 +1038,7 @@ void AP_AHRS_DCM::external_wind_estimate(float speed, float direction) { _wind = wind; } +#endif // return our current position estimate using // dead-reckoning or GPS