AC_CustomControl: tidy AC_CustomControl defines / add config file

This commit is contained in:
Peter Barker 2024-02-15 11:40:28 +11:00 committed by Andrew Tridgell
parent 0e742fe51c
commit bedcbc24b6
8 changed files with 58 additions and 34 deletions

View File

@ -4,7 +4,6 @@
#if AP_CUSTOMCONTROL_ENABLED
#include "AC_CustomControl_Backend.h"
// #include "AC_CustomControl_Empty.h"
#include "AC_CustomControl_PID.h"
@ -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();
@ -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;
@ -193,4 +192,4 @@ void AC_CustomControl::set_notch_sample_rate(float sample_rate)
#endif
}
#endif
#endif // AP_CUSTOMCONTROL_ENABLED

View File

@ -3,6 +3,10 @@
/// @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>
@ -10,8 +14,6 @@
#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
@ -72,4 +74,4 @@ private:
AC_CustomControl_Backend *_backend;
};
#endif
#endif // AP_CUSTOMCONTROL_ENABLED

View File

@ -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:
@ -34,4 +36,4 @@ protected:
AC_CustomControl& _frontend;
};
#endif
#endif // AP_CUSTOMCONTROL_ENABLED

View File

@ -1,6 +1,8 @@
#include "AC_CustomControl_Empty.h"
#include "AC_CustomControl_config.h"
#if CUSTOMCONTROL_EMPTY_ENABLED
#if AP_CUSTOMCONTROL_EMPTY_ENABLED
#include "AC_CustomControl_Empty.h"
#include <GCS_MAVLink/GCS.h>
@ -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());
@ -69,4 +71,4 @@ void AC_CustomControl_Empty::reset(void)
{
}
#endif
#endif // AP_CUSTOMCONTROL_EMPTY_ENABLED

View File

@ -1,13 +1,11 @@
#pragma once
#include "AC_CustomControl_config.h"
#if AP_CUSTOMCONTROL_EMPTY_ENABLED
#include "AC_CustomControl_Backend.h"
#ifndef CUSTOMCONTROL_EMPTY_ENABLED
#define CUSTOMCONTROL_EMPTY_ENABLED AP_CUSTOMCONTROL_ENABLED
#endif
#if CUSTOMCONTROL_EMPTY_ENABLED
class AC_CustomControl_Empty : public AC_CustomControl_Backend {
public:
AC_CustomControl_Empty(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt);
@ -26,4 +24,4 @@ protected:
AP_Float param3;
};
#endif
#endif // AP_CUSTOMCONTROL_EMPTY_ENABLED

View File

@ -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
@ -403,4 +405,4 @@ void AC_CustomControl_PID::set_notch_sample_rate(float sample_rate)
#endif
}
#endif
#endif // AP_CUSTOMCONTROL_PID_ENABLED

View File

@ -1,5 +1,9 @@
#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>
@ -7,12 +11,6 @@
#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);
@ -42,4 +40,4 @@ protected:
AC_PID _pid_atti_rate_yaw;
};
#endif
#endif // AP_CUSTOMCONTROL_PID_ENABLED

View File

@ -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