diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index 27a52909cf..c8008b61d4 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -26,6 +26,8 @@ #include #include #include +#include +#include extern const AP_HAL::HAL& hal; @@ -45,7 +47,7 @@ extern const AP_HAL::HAL& hal; // constructor AP_AutoTune::AP_AutoTune(ATGains &_gains, ATType _type, - const AP_Vehicle::FixedWing &parms, + const AP_FixedWing &parms, AC_PID &_rpid) : current(_gains), rpid(_rpid), diff --git a/libraries/APM_Control/AP_AutoTune.h b/libraries/APM_Control/AP_AutoTune.h index 1f3ba38011..1859a2489f 100644 --- a/libraries/APM_Control/AP_AutoTune.h +++ b/libraries/APM_Control/AP_AutoTune.h @@ -1,9 +1,11 @@ #pragma once +#include #include - +#include +#include #include -#include + #include class AP_AutoTune @@ -41,9 +43,8 @@ public: float tau; }; - // constructor - AP_AutoTune(ATGains &_gains, ATType type, const AP_Vehicle::FixedWing &parms, class AC_PID &rpid); + AP_AutoTune(ATGains &_gains, ATType type, const AP_FixedWing &parms, class AC_PID &rpid); // called when autotune mode is entered void start(void); @@ -67,7 +68,7 @@ private: // what type of autotune is this ATType type; - const AP_Vehicle::FixedWing &aparm; + const AP_FixedWing &aparm; // values to restore if we leave autotune mode ATGains restore; diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 502d9d9f20..53bcadd95e 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -19,6 +19,8 @@ #include #include "AP_PitchController.h" #include +#include +#include extern const AP_HAL::HAL& hal; @@ -134,7 +136,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = { AP_GROUPEND }; -AP_PitchController::AP_PitchController(const AP_Vehicle::FixedWing &parms) +AP_PitchController::AP_PitchController(const AP_FixedWing &parms) : aparm(parms) { AP_Param::setup_object_defaults(this, var_info); diff --git a/libraries/APM_Control/AP_PitchController.h b/libraries/APM_Control/AP_PitchController.h index 3e6d42249a..31b8a0a61e 100644 --- a/libraries/APM_Control/AP_PitchController.h +++ b/libraries/APM_Control/AP_PitchController.h @@ -1,7 +1,6 @@ #pragma once #include -#include #include "AP_AutoTune.h" #include #include @@ -9,7 +8,7 @@ class AP_PitchController { public: - AP_PitchController(const AP_Vehicle::FixedWing &parms); + AP_PitchController(const AP_FixedWing &parms); /* Do not allow copies */ CLASS_NO_COPY(AP_PitchController); @@ -48,7 +47,7 @@ public: void convert_pid(); private: - const AP_Vehicle::FixedWing &aparm; + const AP_FixedWing &aparm; AP_AutoTune::ATGains gains; AP_AutoTune *autotune; bool failed_autotune_alloc; diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index 799a9d3240..4e2eab685a 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -20,6 +20,8 @@ #include #include "AP_RollController.h" #include +#include +#include extern const AP_HAL::HAL& hal; @@ -118,7 +120,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = { }; // constructor -AP_RollController::AP_RollController(const AP_Vehicle::FixedWing &parms) +AP_RollController::AP_RollController(const AP_FixedWing &parms) : aparm(parms) { AP_Param::setup_object_defaults(this, var_info); diff --git a/libraries/APM_Control/AP_RollController.h b/libraries/APM_Control/AP_RollController.h index 5241a38389..5a2c3f4268 100644 --- a/libraries/APM_Control/AP_RollController.h +++ b/libraries/APM_Control/AP_RollController.h @@ -1,7 +1,6 @@ #pragma once #include -#include #include "AP_AutoTune.h" #include #include @@ -9,7 +8,7 @@ class AP_RollController { public: - AP_RollController(const AP_Vehicle::FixedWing &parms); + AP_RollController(const AP_FixedWing &parms); /* Do not allow copies */ CLASS_NO_COPY(AP_RollController); @@ -50,7 +49,7 @@ public: void convert_pid(); private: - const AP_Vehicle::FixedWing &aparm; + const AP_FixedWing &aparm; AP_AutoTune::ATGains gains; AP_AutoTune *autotune; bool failed_autotune_alloc; diff --git a/libraries/APM_Control/AP_SteerController.h b/libraries/APM_Control/AP_SteerController.h index a52df4f0f3..d3557503cc 100644 --- a/libraries/APM_Control/AP_SteerController.h +++ b/libraries/APM_Control/AP_SteerController.h @@ -1,7 +1,6 @@ #pragma once #include -#include #include class AP_SteerController { diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index 493d70636e..334f1e66bb 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -20,6 +20,8 @@ #include #include "AP_YawController.h" #include +#include +#include extern const AP_HAL::HAL& hal; @@ -148,7 +150,7 @@ const AP_Param::GroupInfo AP_YawController::var_info[] = { AP_GROUPEND }; -AP_YawController::AP_YawController(const AP_Vehicle::FixedWing &parms) +AP_YawController::AP_YawController(const AP_FixedWing &parms) : aparm(parms) { AP_Param::setup_object_defaults(this, var_info); diff --git a/libraries/APM_Control/AP_YawController.h b/libraries/APM_Control/AP_YawController.h index eebffa289e..8c4f933edf 100644 --- a/libraries/APM_Control/AP_YawController.h +++ b/libraries/APM_Control/AP_YawController.h @@ -1,14 +1,13 @@ #pragma once #include -#include #include #include "AP_AutoTune.h" class AP_YawController { public: - AP_YawController(const AP_Vehicle::FixedWing &parms); + AP_YawController(const AP_FixedWing &parms); /* Do not allow copies */ CLASS_NO_COPY(AP_YawController); @@ -52,7 +51,7 @@ public: static const struct AP_Param::GroupInfo var_info[]; private: - const AP_Vehicle::FixedWing &aparm; + const AP_FixedWing &aparm; AP_Float _K_A; AP_Float _K_I; AP_Float _K_D;