diff --git a/libraries/AP_Soaring/AP_Soaring.cpp b/libraries/AP_Soaring/AP_Soaring.cpp index 77a684519d..aedc24ac82 100644 --- a/libraries/AP_Soaring/AP_Soaring.cpp +++ b/libraries/AP_Soaring/AP_Soaring.cpp @@ -1,11 +1,12 @@ #include "AP_Soaring.h" -#include -#include -#include -extern const AP_HAL::HAL& hal; #if HAL_SOARING_ENABLED +#include +#include +#include +#include + // ArduSoar parameters const AP_Param::GroupInfo SoaringController::var_info[] = { // @Param: ENABLE diff --git a/libraries/AP_Soaring/AP_Soaring.h b/libraries/AP_Soaring/AP_Soaring.h index 203bdd45f1..1bb3694aa5 100644 --- a/libraries/AP_Soaring/AP_Soaring.h +++ b/libraries/AP_Soaring/AP_Soaring.h @@ -9,13 +9,7 @@ #pragma once -#include -#include -#include -#include "ExtendedKalmanFilter.h" -#include "Variometer.h" -#include -#include "SpeedToFly.h" +#include #ifndef HAL_SOARING_ENABLED #define HAL_SOARING_ENABLED !HAL_MINIMIZE_FEATURES @@ -23,6 +17,12 @@ #if HAL_SOARING_ENABLED +#include +#include +#include "ExtendedKalmanFilter.h" +#include "Variometer.h" +#include "SpeedToFly.h" + #define INITIAL_THERMAL_RADIUS 80.0 #define INITIAL_STRENGTH_COVARIANCE 0.0049 #define INITIAL_RADIUS_COVARIANCE 400.0 @@ -32,7 +32,7 @@ class SoaringController { Variometer::PolarParams _polarParams; ExtendedKalmanFilter _ekf{}; - AP_TECS &_tecs; + class AP_TECS &_tecs; Variometer _vario; SpeedToFly _speedToFly; @@ -81,7 +81,7 @@ protected: AP_Float soar_thermal_flap; public: - SoaringController(AP_TECS &tecs, const AP_Vehicle::FixedWing &parms); + SoaringController(class AP_TECS &tecs, const AP_Vehicle::FixedWing &parms); enum class LoiterStatus { DISABLED,