mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AC_AttitudeControl: change namespace of MultiCopter and FixedWing params
this stops the libraries knowing anything about AP_Vehicle
This commit is contained in:
parent
38bc9bfab1
commit
48d25cfc9f
@ -1,5 +1,6 @@
|
||||
#include "AC_AttitudeControl.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -6,11 +6,11 @@
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <AP_AHRS/AP_AHRS_View.h>
|
||||
#include <AP_Motors/AP_Motors.h>
|
||||
#include <AC_PID/AC_PID.h>
|
||||
#include <AC_PID/AC_P.h>
|
||||
#include <AP_Vehicle/AP_MultiCopter.h>
|
||||
|
||||
#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;
|
||||
|
@ -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),
|
||||
|
@ -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),
|
||||
|
@ -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() {}
|
||||
|
@ -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) {
|
||||
|
@ -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),
|
||||
|
@ -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() {}
|
||||
|
@ -3,7 +3,7 @@
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AP_Motors/AP_Motors.h> // motors library
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -13,7 +13,6 @@
|
||||
#include <AP_InertialNav/AP_InertialNav.h> // 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
|
||||
|
Loading…
Reference in New Issue
Block a user