From 48d25cfc9f12aeb14c7b9aa00f9274f7cd286faa Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 30 Sep 2022 09:10:39 +1000 Subject: [PATCH] AC_AttitudeControl: change namespace of MultiCopter and FixedWing params this stops the libraries knowing anything about AP_Vehicle --- libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | 1 + libraries/AC_AttitudeControl/AC_AttitudeControl.h | 6 +++--- libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h | 2 +- libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp | 2 +- libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h | 2 +- .../AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h | 2 +- libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp | 2 +- libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h | 2 +- libraries/AC_AttitudeControl/AC_PosControl.cpp | 2 +- libraries/AC_AttitudeControl/AC_PosControl.h | 1 - 10 files changed, 11 insertions(+), 11 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index 3be03334c1..db8cf0dfe5 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -1,5 +1,6 @@ #include "AC_AttitudeControl.h" #include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 92cccc1f8e..b5e9a91575 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -6,11 +6,11 @@ #include #include #include -#include #include #include #include #include +#include #define AC_ATTITUDE_CONTROL_ANGLE_P 4.5f // default angle P gain for roll, pitch and yaw @@ -48,7 +48,7 @@ class AC_AttitudeControl { public: AC_AttitudeControl( AP_AHRS_View &ahrs, - const AP_Vehicle::MultiCopter &aparm, + const AP_MultiCopter &aparm, AP_Motors& motors, float dt) : _p_angle_roll(AC_ATTITUDE_CONTROL_ANGLE_P), @@ -516,7 +516,7 @@ protected: // References to external libraries const AP_AHRS_View& _ahrs; - const AP_Vehicle::MultiCopter &_aparm; + const AP_MultiCopter &_aparm; AP_Motors& _motors; static AC_AttitudeControl *_singleton; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h index a802883951..f3a98026fd 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h @@ -32,7 +32,7 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl { public: AC_AttitudeControl_Heli( AP_AHRS_View &ahrs, - const AP_Vehicle::MultiCopter &aparm, + const AP_MultiCopter &aparm, AP_MotorsHeli& motors, float dt) : AC_AttitudeControl(ahrs, aparm, motors, dt), diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index ea2596ddd8..f3dba5ca11 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -235,7 +235,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { AP_GROUPEND }; -AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt) : +AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt) : AC_AttitudeControl(ahrs, aparm, motors, dt), _motors_multi(motors), _pid_rate_roll(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ, dt), diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h index 28bccb33cf..eedefb85ff 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h @@ -41,7 +41,7 @@ class AC_AttitudeControl_Multi : public AC_AttitudeControl { public: - AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt); + AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt); // empty destructor to suppress compiler warning virtual ~AC_AttitudeControl_Multi() {} diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h index d65784dd03..f077245850 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h @@ -5,7 +5,7 @@ class AC_AttitudeControl_Multi_6DoF : public AC_AttitudeControl_Multi { public: - AC_AttitudeControl_Multi_6DoF(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt): + AC_AttitudeControl_Multi_6DoF(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt): AC_AttitudeControl_Multi(ahrs,aparm,motors,dt) { if (_singleton != nullptr) { diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp index 2b017aadeb..7fa78d99ff 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp @@ -259,7 +259,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { AP_GROUPEND }; -AC_AttitudeControl_Sub::AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt) : +AC_AttitudeControl_Sub::AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt) : AC_AttitudeControl(ahrs, aparm, motors, dt), _motors_multi(motors), _pid_rate_roll(AC_ATC_SUB_RATE_RP_P, AC_ATC_SUB_RATE_RP_I, AC_ATC_SUB_RATE_RP_D, 0.0f, AC_ATC_SUB_RATE_RP_IMAX, AC_ATC_SUB_RATE_RP_FILT_HZ, 0.0f, AC_ATC_SUB_RATE_RP_FILT_HZ, dt), diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h index b460daf26b..90c4aef7f4 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h @@ -25,7 +25,7 @@ class AC_AttitudeControl_Sub : public AC_AttitudeControl { public: - AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt); + AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt); // empty destructor to suppress compiler warning virtual ~AC_AttitudeControl_Sub() {} diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 2a78e0ac65..79260a64ff 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -3,7 +3,7 @@ #include #include #include // motors library -#include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index 2c81ca28df..da696169c3 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -13,7 +13,6 @@ #include // Inertial Navigation library #include "AC_AttitudeControl.h" // Attitude control library - // position controller default definitions #define POSCONTROL_ACCEL_XY 100.0f // default horizontal acceleration in cm/s/s. This is overwritten by waypoint and loiter controllers #define POSCONTROL_JERK_XY 5.0f // default horizontal jerk m/s/s/s