Skip to content

Commit

Permalink
AC_CustomControl: tidy AC_CustomControl defines / add config file
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Feb 15, 2024
1 parent 4b5553a commit f2407d3
Show file tree
Hide file tree
Showing 8 changed files with 57 additions and 33 deletions.
15 changes: 7 additions & 8 deletions libraries/AC_CustomControl/AC_CustomControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@

#if AP_CUSTOMCONTROL_ENABLED


#include "AC_CustomControl_Backend.h"
// #include "AC_CustomControl_Empty.h"
#include "AC_CustomControl_PID.h"
Expand Down Expand Up @@ -123,30 +122,30 @@ void AC_CustomControl::set_custom_controller(bool enabled)

// don't allow accidental main controller reset without active custom controller
if (_controller_type == CustomControlType::CONT_NONE) {
gcs().send_text(MAV_SEVERITY_INFO, "Custom controller is not enabled");
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller is not enabled");
return;
}

// controller type is out of range
if (_controller_type > CUSTOMCONTROL_MAX_TYPES) {
gcs().send_text(MAV_SEVERITY_INFO, "Custom controller type is out of range");
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller type is out of range");
return;
}

// backend is not created
if (_backend == nullptr) {
gcs().send_text(MAV_SEVERITY_INFO, "Reboot to enable selected custom controller");
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Reboot to enable selected custom controller");
return;
}

if (_custom_controller_mask == 0 && enabled) {
gcs().send_text(MAV_SEVERITY_INFO, "Axis mask is not set");
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Axis mask is not set");
return;
}

// reset main controller
if (!enabled) {
gcs().send_text(MAV_SEVERITY_INFO, "Custom controller is OFF");
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller is OFF");
// don't reset if the empty backend is selected
if (_controller_type > CustomControlType::CONT_EMPTY) {
reset_main_att_controller();
Expand All @@ -156,7 +155,7 @@ void AC_CustomControl::set_custom_controller(bool enabled)
if (enabled && _controller_type > CustomControlType::CONT_NONE) {
// reset custom controller filter, integrator etc.
_backend->reset();
gcs().send_text(MAV_SEVERITY_INFO, "Custom controller is ON");
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller is ON");
}

_custom_controller_active = enabled;
Expand Down Expand Up @@ -193,4 +192,4 @@ void AC_CustomControl::set_notch_sample_rate(float sample_rate)
#endif
}

#endif
#endif // AP_CUSTOMCONTROL_ENABLED
8 changes: 5 additions & 3 deletions libraries/AC_CustomControl/AC_CustomControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,17 @@
/// @file AC_CustomControl.h
/// @brief ArduCopter custom control library

#include "AC_CustomControl_config.h"

#if AP_CUSTOMCONTROL_ENABLED

#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_AHRS/AP_AHRS_View.h>
#include <AC_AttitudeControl/AC_AttitudeControl.h>
#include <AP_Motors/AP_MotorsMulticopter.h>
#include <AP_Logger/AP_Logger.h>

#if AP_CUSTOMCONTROL_ENABLED

#ifndef CUSTOMCONTROL_MAX_TYPES
#define CUSTOMCONTROL_MAX_TYPES 2
#endif
Expand Down Expand Up @@ -72,4 +74,4 @@ class AC_CustomControl {
AC_CustomControl_Backend *_backend;
};

#endif
#endif // AP_CUSTOMCONTROL_ENABLED
6 changes: 4 additions & 2 deletions libraries/AC_CustomControl/AC_CustomControl_Backend.h
Original file line number Diff line number Diff line change
@@ -1,9 +1,11 @@
#pragma once

#include "AC_CustomControl.h"
#include "AC_CustomControl_config.h"

#if AP_CUSTOMCONTROL_ENABLED

#include "AC_CustomControl.h"

class AC_CustomControl_Backend
{
public:
Expand Down Expand Up @@ -34,4 +36,4 @@ class AC_CustomControl_Backend
AC_CustomControl& _frontend;
};

#endif
#endif // AP_CUSTOMCONTROL_ENABLED
10 changes: 6 additions & 4 deletions libraries/AC_CustomControl/AC_CustomControl_Empty.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
#include "AC_CustomControl_Empty.h"
#include "AC_CustomControl_config.h"

#if AP_CUSTOMCONTROL_EMPTY_ENABLED

#if CUSTOMCONTROL_EMPTY_ENABLED
#include "AC_CustomControl_Empty.h"

#include <GCS_MAVLink/GCS.h>

Expand Down Expand Up @@ -57,7 +59,7 @@ Vector3f AC_CustomControl_Empty::update(void)
// arducopter main attitude controller already ran
// we don't need to do anything else

gcs().send_text(MAV_SEVERITY_INFO, "empty custom controller working");
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "empty custom controller working");

// return what arducopter main controller outputted
return Vector3f(_motors->get_roll(), _motors->get_pitch(), _motors->get_yaw());
Expand All @@ -69,4 +71,4 @@ void AC_CustomControl_Empty::reset(void)
{
}

#endif
#endif // AP_CUSTOMCONTROL_EMPTY_ENABLED
10 changes: 4 additions & 6 deletions libraries/AC_CustomControl/AC_CustomControl_Empty.h
Original file line number Diff line number Diff line change
@@ -1,12 +1,10 @@
#pragma once

#include "AC_CustomControl_Backend.h"
#include "AC_CustomControl_config.h"

#ifndef CUSTOMCONTROL_EMPTY_ENABLED
#define CUSTOMCONTROL_EMPTY_ENABLED AP_CUSTOMCONTROL_ENABLED
#endif
#if AP_CUSTOMCONTROL_EMPTY_ENABLED

#if CUSTOMCONTROL_EMPTY_ENABLED
#include "AC_CustomControl_Backend.h"

class AC_CustomControl_Empty : public AC_CustomControl_Backend {
public:
Expand All @@ -26,4 +24,4 @@ class AC_CustomControl_Empty : public AC_CustomControl_Backend {
AP_Float param3;
};

#endif
#endif // AP_CUSTOMCONTROL_EMPTY_ENABLED
8 changes: 5 additions & 3 deletions libraries/AC_CustomControl/AC_CustomControl_PID.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,10 @@
#include "AC_CustomControl_config.h"

#if AP_CUSTOMCONTROL_PID_ENABLED

#include "AC_CustomControl_PID.h"
#include "AC_AttitudeControl/AC_AttitudeControl_Multi.h"

#if CUSTOMCONTROL_PID_ENABLED

// table of user settable parameters
const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @Param: ANG_RLL_P
Expand Down Expand Up @@ -403,4 +405,4 @@ void AC_CustomControl_PID::set_notch_sample_rate(float sample_rate)
#endif
}

#endif
#endif // AP_CUSTOMCONTROL_PID_ENABLED
12 changes: 5 additions & 7 deletions libraries/AC_CustomControl/AC_CustomControl_PID.h
Original file line number Diff line number Diff line change
@@ -1,18 +1,16 @@
#pragma once

#include "AC_CustomControl_config.h"

#if AP_CUSTOMCONTROL_PID_ENABLED

#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AC_PID/AC_PID.h>
#include <AC_PID/AC_P.h>

#include "AC_CustomControl_Backend.h"

#ifndef CUSTOMCONTROL_PID_ENABLED
#define CUSTOMCONTROL_PID_ENABLED AP_CUSTOMCONTROL_ENABLED
#endif

#if CUSTOMCONTROL_PID_ENABLED

class AC_CustomControl_PID : public AC_CustomControl_Backend {
public:
AC_CustomControl_PID(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt);
Expand Down Expand Up @@ -42,4 +40,4 @@ class AC_CustomControl_PID : public AC_CustomControl_Backend {
AC_PID _pid_atti_rate_yaw;
};

#endif
#endif // AP_CUSTOMCONTROL_PID_ENABLED
21 changes: 21 additions & 0 deletions libraries/AC_CustomControl/AC_CustomControl_config.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
#pragma once

#include <AP_HAL/AP_HAL_Boards.h>

// note boards.py sets this, so the default value in here doesn't
// really matter:
//#ifndef AP_CUSTOMCONTROL_ENABLED
//#define AP_CUSTOMCONTROL_ENABLED 0
//#endif

#ifndef AP_CUSTOMCONTROL_BACKEND_DEFAULT_ENABLED
#define AP_CUSTOMCONTROL_BACKEND_DEFAULT_ENABLED AP_CUSTOMCONTROL_ENABLED
#endif

#ifndef AP_CUSTOMCONTROL_EMPTY_ENABLED
#define AP_CUSTOMCONTROL_EMPTY_ENABLED AP_CUSTOMCONTROL_BACKEND_DEFAULT_ENABLED
#endif

#ifndef AP_CUSTOMCONTROL_PID_ENABLED
#define AP_CUSTOMCONTROL_PID_ENABLED AP_CUSTOMCONTROL_BACKEND_DEFAULT_ENABLED
#endif

0 comments on commit f2407d3

Please sign in to comment.