Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Copter: use attitude control base class #25224

Merged
merged 2 commits into from
Dec 4, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 2 additions & 7 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,12 +77,6 @@
#include "defines.h"
#include "config.h"

#if FRAME_CONFIG == HELI_FRAME
#define AC_AttitudeControl_t AC_AttitudeControl_Heli
#else
#define AC_AttitudeControl_t AC_AttitudeControl_Multi
#endif

#if FRAME_CONFIG == HELI_FRAME
#define MOTOR_CLASS AP_MotorsHeli
#else
Expand Down Expand Up @@ -485,7 +479,8 @@ class Copter : public AP_Vehicle {

// Attitude, Position and Waypoint navigation objects
// To-Do: move inertial nav up or other navigation variables down here
AC_AttitudeControl_t *attitude_control;
AC_AttitudeControl *attitude_control;
const struct AP_Param::GroupInfo *attitude_control_var_info;
AC_PosControl *pos_control;
AC_WPNav *wp_nav;
AC_Loiter *loiter_nav;
Expand Down
6 changes: 1 addition & 5 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -498,11 +498,7 @@ const AP_Param::Info Copter::var_info[] = {

// @Group: ATC_
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
#if FRAME_CONFIG == HELI_FRAME
GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Heli),
#else
GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Multi),
#endif
GOBJECTVARPTR(attitude_control, "ATC_", &copter.attitude_control_var_info),

// @Group: PSC
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -241,7 +241,7 @@ class Mode {
AC_PosControl *&pos_control;
AP_InertialNav &inertial_nav;
AP_AHRS &ahrs;
AC_AttitudeControl_t *&attitude_control;
AC_AttitudeControl *&attitude_control;
MOTOR_CLASS *&motors;
RC_Channel *&channel_roll;
RC_Channel *&channel_pitch;
Expand Down
10 changes: 4 additions & 6 deletions ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -444,26 +444,24 @@ void Copter::allocate_motors(void)
AP_BoardConfig::allocation_error("AP_AHRS_View");
}

const struct AP_Param::GroupInfo *ac_var_info;

#if FRAME_CONFIG != HELI_FRAME
if ((AP_Motors::motor_frame_class)g2.frame_class.get() == AP_Motors::MOTOR_FRAME_6DOF_SCRIPTING) {
#if AP_SCRIPTING_ENABLED
attitude_control = new AC_AttitudeControl_Multi_6DoF(*ahrs_view, aparm, *motors);
ac_var_info = AC_AttitudeControl_Multi_6DoF::var_info;
attitude_control_var_info = AC_AttitudeControl_Multi_6DoF::var_info;
#endif // AP_SCRIPTING_ENABLED
} else {
attitude_control = new AC_AttitudeControl_Multi(*ahrs_view, aparm, *motors);
ac_var_info = AC_AttitudeControl_Multi::var_info;
attitude_control_var_info = AC_AttitudeControl_Multi::var_info;
}
#else
attitude_control = new AC_AttitudeControl_Heli(*ahrs_view, aparm, *motors);
ac_var_info = AC_AttitudeControl_Heli::var_info;
attitude_control_var_info = AC_AttitudeControl_Heli::var_info;
#endif
if (attitude_control == nullptr) {
AP_BoardConfig::allocation_error("AttitudeControl");
}
AP_Param::load_object_from_eeprom(attitude_control, ac_var_info);
AP_Param::load_object_from_eeprom(attitude_control, attitude_control_var_info);

pos_control = new AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control);
if (pos_control == nullptr) {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AC_CustomControl/AC_CustomControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down
6 changes: 3 additions & 3 deletions libraries/AC_CustomControl/AC_CustomControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -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>

Expand All @@ -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 */

Expand Down Expand Up @@ -62,7 +62,7 @@ class AC_CustomControl {

// 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;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AC_CustomControl/AC_CustomControl_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand All @@ -29,7 +29,7 @@ class AC_CustomControl_Backend
protected:
// References to external libraries
AP_AHRS_View*& _ahrs;
AC_AttitudeControl_Multi*& _att_control;
AC_AttitudeControl*& _att_control;
AP_MotorsMulticopter*& _motors;
AC_CustomControl& _frontend;
};
Expand Down
2 changes: 1 addition & 1 deletion libraries/AC_CustomControl/AC_CustomControl_Empty.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AC_CustomControl/AC_CustomControl_Empty.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
3 changes: 2 additions & 1 deletion libraries/AC_CustomControl/AC_CustomControl_PID.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include "AC_CustomControl_PID.h"
#include "AC_AttitudeControl/AC_AttitudeControl_Multi.h"
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is needed because the same default defines are used for PID gains.


#if CUSTOMCONTROL_PID_ENABLED

Expand Down Expand Up @@ -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),
Expand Down
2 changes: 1 addition & 1 deletion libraries/AC_CustomControl/AC_CustomControl_PID.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down