AP_CustomControl: use base class AC_AttitudeControl object

This commit is contained in:
Iampete1 2023-07-19 14:08:19 +01:00 committed by Randy Mackay
parent 60ceaec901
commit d26fdfc3b2
7 changed files with 11 additions and 10 deletions

View File

@ -38,7 +38,7 @@ const AP_Param::GroupInfo AC_CustomControl::var_info[] = {
const struct AP_Param::GroupInfo *AC_CustomControl::_backend_var_info[CUSTOMCONTROL_MAX_TYPES];
AC_CustomControl::AC_CustomControl(AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& att_control, AP_MotorsMulticopter*& motors, float dt) :
AC_CustomControl::AC_CustomControl(AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt) :
_dt(dt),
_ahrs(ahrs),
_att_control(att_control),

View File

@ -6,7 +6,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_AHRS/AP_AHRS_View.h>
#include <AC_AttitudeControl/AC_AttitudeControl_Multi.h>
#include <AC_AttitudeControl/AC_AttitudeControl.h>
#include <AP_Motors/AP_MotorsMulticopter.h>
#include <AP_Logger/AP_Logger.h>
@ -20,7 +20,7 @@ class AC_CustomControl_Backend;
class AC_CustomControl {
public:
AC_CustomControl(AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& _att_control, AP_MotorsMulticopter*& motors, float dt);
AC_CustomControl(AP_AHRS_View*& ahrs, AC_AttitudeControl*& _att_control, AP_MotorsMulticopter*& motors, float dt);
CLASS_NO_COPY(AC_CustomControl); /* Do not allow copies */
@ -62,7 +62,7 @@ protected:
// References to external libraries
AP_AHRS_View*& _ahrs;
AC_AttitudeControl_Multi*& _att_control;
AC_AttitudeControl*& _att_control;
AP_MotorsMulticopter*& _motors;
AP_Enum<CustomControlType> _controller_type;

View File

@ -7,7 +7,7 @@
class AC_CustomControl_Backend
{
public:
AC_CustomControl_Backend(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& att_control, AP_MotorsMulticopter*& motors, float dt) :
AC_CustomControl_Backend(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt) :
_frontend(frontend),
_ahrs(ahrs),
_att_control(att_control),
@ -29,7 +29,7 @@ public:
protected:
// References to external libraries
AP_AHRS_View*& _ahrs;
AC_AttitudeControl_Multi*& _att_control;
AC_AttitudeControl*& _att_control;
AP_MotorsMulticopter*& _motors;
AC_CustomControl& _frontend;
};

View File

@ -28,7 +28,7 @@ const AP_Param::GroupInfo AC_CustomControl_Empty::var_info[] = {
};
// initialize in the constructor
AC_CustomControl_Empty::AC_CustomControl_Empty(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& att_control, AP_MotorsMulticopter*& motors, float dt) :
AC_CustomControl_Empty::AC_CustomControl_Empty(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt) :
AC_CustomControl_Backend(frontend, ahrs, att_control, motors, dt)
{
AP_Param::setup_object_defaults(this, var_info);

View File

@ -10,7 +10,7 @@
class AC_CustomControl_Empty : public AC_CustomControl_Backend {
public:
AC_CustomControl_Empty(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& att_control, AP_MotorsMulticopter*& motors, float dt);
AC_CustomControl_Empty(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt);
Vector3f update(void) override;

View File

@ -1,4 +1,5 @@
#include "AC_CustomControl_PID.h"
#include "AC_AttitudeControl/AC_AttitudeControl_Multi.h"
#if CUSTOMCONTROL_PID_ENABLED
@ -315,7 +316,7 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
AP_GROUPEND
};
AC_CustomControl_PID::AC_CustomControl_PID(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& att_control, AP_MotorsMulticopter*& motors, float dt) :
AC_CustomControl_PID::AC_CustomControl_PID(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt) :
AC_CustomControl_Backend(frontend, ahrs, att_control, motors, dt),
_p_angle_roll2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f),
_p_angle_pitch2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f),

View File

@ -15,7 +15,7 @@
class AC_CustomControl_PID : public AC_CustomControl_Backend {
public:
AC_CustomControl_PID(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& att_control, AP_MotorsMulticopter*& motors, float dt);
AC_CustomControl_PID(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt);
// run lowest level body-frame rate controller and send outputs to the motors
Vector3f update() override;