diff --git a/libraries/AP_Soaring/AP_Soaring.cpp b/libraries/AP_Soaring/AP_Soaring.cpp index aedc24ac82..53e6165284 100644 --- a/libraries/AP_Soaring/AP_Soaring.cpp +++ b/libraries/AP_Soaring/AP_Soaring.cpp @@ -166,7 +166,7 @@ const AP_Param::GroupInfo SoaringController::var_info[] = { AP_GROUPEND }; -SoaringController::SoaringController(AP_TECS &tecs, const AP_Vehicle::FixedWing &parms) : +SoaringController::SoaringController(AP_TECS &tecs, const AP_FixedWing &parms) : _tecs(tecs), _vario(parms,_polarParams), _speedToFly(_polarParams), diff --git a/libraries/AP_Soaring/AP_Soaring.h b/libraries/AP_Soaring/AP_Soaring.h index 737f7a38bc..4d13ef8e79 100644 --- a/libraries/AP_Soaring/AP_Soaring.h +++ b/libraries/AP_Soaring/AP_Soaring.h @@ -36,7 +36,7 @@ class SoaringController { Variometer _vario; SpeedToFly _speedToFly; - const AP_Vehicle::FixedWing &_aparm; + const AP_FixedWing &_aparm; // store aircraft location at last update Vector3f _prev_update_location; @@ -81,7 +81,7 @@ protected: AP_Float soar_thermal_flap; public: - SoaringController(class AP_TECS &tecs, const AP_Vehicle::FixedWing &parms); + SoaringController(class AP_TECS &tecs, const AP_FixedWing &parms); enum class LoiterStatus { DISABLED, diff --git a/libraries/AP_Soaring/Variometer.cpp b/libraries/AP_Soaring/Variometer.cpp index eb1ca5493e..a7a59f789e 100644 --- a/libraries/AP_Soaring/Variometer.cpp +++ b/libraries/AP_Soaring/Variometer.cpp @@ -6,7 +6,7 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity. #include -Variometer::Variometer(const AP_Vehicle::FixedWing &parms, const PolarParams &polarParams) : +Variometer::Variometer(const AP_FixedWing &parms, const PolarParams &polarParams) : _aparm(parms), _polarParams(polarParams) { diff --git a/libraries/AP_Soaring/Variometer.h b/libraries/AP_Soaring/Variometer.h index 0678884ee9..d5237b92dc 100644 --- a/libraries/AP_Soaring/Variometer.h +++ b/libraries/AP_Soaring/Variometer.h @@ -8,11 +8,11 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity. #include #include #include -#include +#include class Variometer { - const AP_Vehicle::FixedWing &_aparm; + const AP_FixedWing &_aparm; // store time of last update uint64_t _prev_update_time; @@ -53,7 +53,7 @@ public: AP_Float B; }; - Variometer(const AP_Vehicle::FixedWing &parms, const PolarParams &polarParams); + Variometer(const AP_FixedWing &parms, const PolarParams &polarParams); float alt; float reading;