diff --git a/libraries/AC_CustomControl/AC_CustomControl.cpp b/libraries/AC_CustomControl/AC_CustomControl.cpp index ada094b691..a5df09f11b 100644 --- a/libraries/AC_CustomControl/AC_CustomControl.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl.cpp @@ -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), diff --git a/libraries/AC_CustomControl/AC_CustomControl.h b/libraries/AC_CustomControl/AC_CustomControl.h index 9cda1f21db..e4405b3c28 100644 --- a/libraries/AC_CustomControl/AC_CustomControl.h +++ b/libraries/AC_CustomControl/AC_CustomControl.h @@ -6,7 +6,7 @@ #include #include #include -#include +#include #include #include @@ -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 _controller_type; diff --git a/libraries/AC_CustomControl/AC_CustomControl_Backend.h b/libraries/AC_CustomControl/AC_CustomControl_Backend.h index c4068a7b1b..5355ef9cbc 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_Backend.h +++ b/libraries/AC_CustomControl/AC_CustomControl_Backend.h @@ -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; }; diff --git a/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp b/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp index 222510c4f4..5c0550b089 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp @@ -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); diff --git a/libraries/AC_CustomControl/AC_CustomControl_Empty.h b/libraries/AC_CustomControl/AC_CustomControl_Empty.h index 692815f1cc..e3a6374d21 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_Empty.h +++ b/libraries/AC_CustomControl/AC_CustomControl_Empty.h @@ -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; diff --git a/libraries/AC_CustomControl/AC_CustomControl_PID.cpp b/libraries/AC_CustomControl/AC_CustomControl_PID.cpp index ddf6a40c6b..5535d44990 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_PID.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl_PID.cpp @@ -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), diff --git a/libraries/AC_CustomControl/AC_CustomControl_PID.h b/libraries/AC_CustomControl/AC_CustomControl_PID.h index b3cdf68884..75649a5dd9 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_PID.h +++ b/libraries/AC_CustomControl/AC_CustomControl_PID.h @@ -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;