diff --git a/libraries/APM_Control/AP_PitchController.h b/libraries/APM_Control/AP_PitchController.h index e99ffd1600..488e38cdbe 100644 --- a/libraries/APM_Control/AP_PitchController.h +++ b/libraries/APM_Control/AP_PitchController.h @@ -5,12 +5,12 @@ #include #include -#include +#include #include class AP_PitchController { public: - AP_PitchController(AP_AHRS &ahrs, const AP_SpdHgtControl::AircraftParameters &parms) : + AP_PitchController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) : aparm(parms), _ahrs(ahrs) { @@ -26,7 +26,7 @@ public: static const struct AP_Param::GroupInfo var_info[]; private: - const AP_SpdHgtControl::AircraftParameters &aparm; + const AP_Vehicle::FixedWing &aparm; AP_Float _tau; AP_Float _K_P; AP_Float _K_I; diff --git a/libraries/APM_Control/AP_RollController.h b/libraries/APM_Control/AP_RollController.h index 49f59ca5e6..25c615a463 100644 --- a/libraries/APM_Control/AP_RollController.h +++ b/libraries/APM_Control/AP_RollController.h @@ -5,12 +5,12 @@ #include #include -#include +#include #include class AP_RollController { public: - AP_RollController(AP_AHRS &ahrs, const AP_SpdHgtControl::AircraftParameters &parms) : + AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) : aparm(parms), _ahrs(ahrs) { @@ -25,7 +25,7 @@ public: static const struct AP_Param::GroupInfo var_info[]; private: - const AP_SpdHgtControl::AircraftParameters &aparm; + const AP_Vehicle::FixedWing &aparm; AP_Float _tau; AP_Float _K_P; AP_Float _K_I; diff --git a/libraries/APM_Control/AP_SteerController.h b/libraries/APM_Control/AP_SteerController.h index 59ce32e910..ab1f4997d1 100644 --- a/libraries/APM_Control/AP_SteerController.h +++ b/libraries/APM_Control/AP_SteerController.h @@ -5,7 +5,7 @@ #include #include -#include +#include #include class AP_SteerController { diff --git a/libraries/APM_Control/AP_YawController.h b/libraries/APM_Control/AP_YawController.h index dd3c3ca158..e63196e5cd 100644 --- a/libraries/APM_Control/AP_YawController.h +++ b/libraries/APM_Control/AP_YawController.h @@ -5,12 +5,12 @@ #include #include -#include +#include #include class AP_YawController { public: - AP_YawController(AP_AHRS &ahrs, const AP_SpdHgtControl::AircraftParameters &parms) : + AP_YawController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) : aparm(parms), _ahrs(ahrs) { @@ -24,7 +24,7 @@ public: static const struct AP_Param::GroupInfo var_info[]; private: - const AP_SpdHgtControl::AircraftParameters &aparm; + const AP_Vehicle::FixedWing &aparm; AP_Float _K_A; AP_Float _K_I; AP_Float _K_D;