From 0fb5be7f2b43482fee7ad2ad90feadbd952e9780 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 1 Mar 2022 12:19:06 +1100 Subject: [PATCH] AC_AttitudeControl: tidy includes --- libraries/AC_AttitudeControl/AC_PosControl.cpp | 2 ++ libraries/AC_AttitudeControl/AC_PosControl.h | 6 ++---- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 8cda28b862..bbee0577ee 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -2,6 +2,8 @@ #include "AC_PosControl.h" #include #include +#include // motors library +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index 29c4a6f62c..2c240f8792 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -12,8 +12,6 @@ #include // PID library (2-axis) #include // Inertial Navigation library #include "AC_AttitudeControl.h" // Attitude control library -#include // motors library -#include // common vehicle parameters // position controller default definitions @@ -42,7 +40,7 @@ public: /// Constructor AC_PosControl(AP_AHRS_View& ahrs, const AP_InertialNav& inav, - const AP_Motors& motors, AC_AttitudeControl& attitude_control, float dt); + const class AP_Motors& motors, AC_AttitudeControl& attitude_control, float dt); /// get_dt - gets time delta in seconds for all position controllers float get_dt() const { return _dt; } @@ -420,7 +418,7 @@ protected: // references to inertial nav and ahrs libraries AP_AHRS_View& _ahrs; const AP_InertialNav& _inav; - const AP_Motors& _motors; + const class AP_Motors& _motors; AC_AttitudeControl& _attitude_control; // parameters