APM_Control: change namespace of MultiCopter and FixedWing params

this stops the libraries knowing anything about AP_Vehicle
This commit is contained in:
Peter Barker 2022-09-30 09:10:40 +10:00 committed by Andrew Tridgell
parent 28a9622a1e
commit 7f202b8a0e
9 changed files with 24 additions and 19 deletions

View File

@ -26,6 +26,8 @@
#include <AP_Logger/AP_Logger.h> #include <AP_Logger/AP_Logger.h>
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AC_PID/AC_PID.h> #include <AC_PID/AC_PID.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -45,7 +47,7 @@ extern const AP_HAL::HAL& hal;
// constructor // constructor
AP_AutoTune::AP_AutoTune(ATGains &_gains, ATType _type, AP_AutoTune::AP_AutoTune(ATGains &_gains, ATType _type,
const AP_Vehicle::FixedWing &parms, const AP_FixedWing &parms,
AC_PID &_rpid) : AC_PID &_rpid) :
current(_gains), current(_gains),
rpid(_rpid), rpid(_rpid),

View File

@ -1,9 +1,11 @@
#pragma once #pragma once
#include <AP_Logger/AP_Logger.h>
#include <AP_Logger/LogStructure.h> #include <AP_Logger/LogStructure.h>
#include <AP_Param/AP_Param.h>
#include <AP_Vehicle/AP_FixedWing.h>
#include <Filter/SlewLimiter.h> #include <Filter/SlewLimiter.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <Filter/ModeFilter.h> #include <Filter/ModeFilter.h>
class AP_AutoTune class AP_AutoTune
@ -41,9 +43,8 @@ public:
float tau; float tau;
}; };
// constructor // 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 // called when autotune mode is entered
void start(void); void start(void);
@ -67,7 +68,7 @@ private:
// what type of autotune is this // what type of autotune is this
ATType type; ATType type;
const AP_Vehicle::FixedWing &aparm; const AP_FixedWing &aparm;
// values to restore if we leave autotune mode // values to restore if we leave autotune mode
ATGains restore; ATGains restore;

View File

@ -19,6 +19,8 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include "AP_PitchController.h" #include "AP_PitchController.h"
#include <AP_AHRS/AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -134,7 +136,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
AP_GROUPEND AP_GROUPEND
}; };
AP_PitchController::AP_PitchController(const AP_Vehicle::FixedWing &parms) AP_PitchController::AP_PitchController(const AP_FixedWing &parms)
: aparm(parms) : aparm(parms)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);

View File

@ -1,7 +1,6 @@
#pragma once #pragma once
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include "AP_AutoTune.h" #include "AP_AutoTune.h"
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AC_PID/AC_PID.h> #include <AC_PID/AC_PID.h>
@ -9,7 +8,7 @@
class AP_PitchController class AP_PitchController
{ {
public: public:
AP_PitchController(const AP_Vehicle::FixedWing &parms); AP_PitchController(const AP_FixedWing &parms);
/* Do not allow copies */ /* Do not allow copies */
CLASS_NO_COPY(AP_PitchController); CLASS_NO_COPY(AP_PitchController);
@ -48,7 +47,7 @@ public:
void convert_pid(); void convert_pid();
private: private:
const AP_Vehicle::FixedWing &aparm; const AP_FixedWing &aparm;
AP_AutoTune::ATGains gains; AP_AutoTune::ATGains gains;
AP_AutoTune *autotune; AP_AutoTune *autotune;
bool failed_autotune_alloc; bool failed_autotune_alloc;

View File

@ -20,6 +20,8 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include "AP_RollController.h" #include "AP_RollController.h"
#include <AP_AHRS/AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -118,7 +120,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = {
}; };
// constructor // constructor
AP_RollController::AP_RollController(const AP_Vehicle::FixedWing &parms) AP_RollController::AP_RollController(const AP_FixedWing &parms)
: aparm(parms) : aparm(parms)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);

View File

@ -1,7 +1,6 @@
#pragma once #pragma once
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include "AP_AutoTune.h" #include "AP_AutoTune.h"
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AC_PID/AC_PID.h> #include <AC_PID/AC_PID.h>
@ -9,7 +8,7 @@
class AP_RollController class AP_RollController
{ {
public: public:
AP_RollController(const AP_Vehicle::FixedWing &parms); AP_RollController(const AP_FixedWing &parms);
/* Do not allow copies */ /* Do not allow copies */
CLASS_NO_COPY(AP_RollController); CLASS_NO_COPY(AP_RollController);
@ -50,7 +49,7 @@ public:
void convert_pid(); void convert_pid();
private: private:
const AP_Vehicle::FixedWing &aparm; const AP_FixedWing &aparm;
AP_AutoTune::ATGains gains; AP_AutoTune::ATGains gains;
AP_AutoTune *autotune; AP_AutoTune *autotune;
bool failed_autotune_alloc; bool failed_autotune_alloc;

View File

@ -1,7 +1,6 @@
#pragma once #pragma once
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AC_PID/AP_PIDInfo.h> #include <AC_PID/AP_PIDInfo.h>
class AP_SteerController { class AP_SteerController {

View File

@ -20,6 +20,8 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include "AP_YawController.h" #include "AP_YawController.h"
#include <AP_AHRS/AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Scheduler/AP_Scheduler.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -148,7 +150,7 @@ const AP_Param::GroupInfo AP_YawController::var_info[] = {
AP_GROUPEND AP_GROUPEND
}; };
AP_YawController::AP_YawController(const AP_Vehicle::FixedWing &parms) AP_YawController::AP_YawController(const AP_FixedWing &parms)
: aparm(parms) : aparm(parms)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);

View File

@ -1,14 +1,13 @@
#pragma once #pragma once
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AC_PID/AC_PID.h> #include <AC_PID/AC_PID.h>
#include "AP_AutoTune.h" #include "AP_AutoTune.h"
class AP_YawController class AP_YawController
{ {
public: public:
AP_YawController(const AP_Vehicle::FixedWing &parms); AP_YawController(const AP_FixedWing &parms);
/* Do not allow copies */ /* Do not allow copies */
CLASS_NO_COPY(AP_YawController); CLASS_NO_COPY(AP_YawController);
@ -52,7 +51,7 @@ public:
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];
private: private:
const AP_Vehicle::FixedWing &aparm; const AP_FixedWing &aparm;
AP_Float _K_A; AP_Float _K_A;
AP_Float _K_I; AP_Float _K_I;
AP_Float _K_D; AP_Float _K_D;