CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_CustomControl/AC_CustomControl.cpp
Views: 1798
1
#include <AP_HAL/AP_HAL.h>
2
3
#include "AC_CustomControl.h"
4
5
#if AP_CUSTOMCONTROL_ENABLED
6
7
#include "AC_CustomControl_Backend.h"
8
// #include "AC_CustomControl_Empty.h"
9
#include "AC_CustomControl_PID.h"
10
#include <GCS_MAVLink/GCS.h>
11
#include <AP_Logger/AP_Logger.h>
12
13
// table of user settable parameters
14
const AP_Param::GroupInfo AC_CustomControl::var_info[] = {
15
// @Param: _TYPE
16
// @DisplayName: Custom control type
17
// @Description: Custom control type to be used
18
// @Values: 0:None, 1:Empty, 2:PID
19
// @RebootRequired: True
20
// @User: Advanced
21
AP_GROUPINFO_FLAGS("_TYPE", 1, AC_CustomControl, _controller_type, 0, AP_PARAM_FLAG_ENABLE),
22
23
// @Param: _AXIS_MASK
24
// @DisplayName: Custom Controller bitmask
25
// @Description: Custom Controller bitmask to chose which axis to run
26
// @Bitmask: 0:Roll, 1:Pitch, 2:Yaw
27
// @User: Advanced
28
AP_GROUPINFO("_AXIS_MASK", 2, AC_CustomControl, _custom_controller_mask, 0),
29
30
// parameters for empty controller. only used as a template, no need for param table
31
// AP_SUBGROUPVARPTR(_backend, "1_", 6, AC_CustomControl, _backend_var_info[0]),
32
33
// parameters for PID controller
34
AP_SUBGROUPVARPTR(_backend, "2_", 7, AC_CustomControl, _backend_var_info[1]),
35
36
AP_GROUPEND
37
};
38
39
const struct AP_Param::GroupInfo *AC_CustomControl::_backend_var_info[CUSTOMCONTROL_MAX_TYPES];
40
41
AC_CustomControl::AC_CustomControl(AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt) :
42
_dt(dt),
43
_ahrs(ahrs),
44
_att_control(att_control),
45
_motors(motors)
46
{
47
AP_Param::setup_object_defaults(this, var_info);
48
}
49
50
void AC_CustomControl::init(void)
51
{
52
switch (CustomControlType(_controller_type))
53
{
54
case CustomControlType::CONT_NONE:
55
break;
56
case CustomControlType::CONT_EMPTY: // This is template backend. Don't initialize it.
57
// This is template backend. Don't initialize it.
58
// _backend = NEW_NOTHROW AC_CustomControl_Empty(*this, _ahrs, _att_control, _motors, _dt);
59
// _backend_var_info[get_type()] = AC_CustomControl_Empty::var_info;
60
break;
61
case CustomControlType::CONT_PID:
62
_backend = NEW_NOTHROW AC_CustomControl_PID(*this, _ahrs, _att_control, _motors, _dt);
63
_backend_var_info[get_type()] = AC_CustomControl_PID::var_info;
64
break;
65
default:
66
return;
67
}
68
69
if (_backend && _backend_var_info[get_type()]) {
70
AP_Param::load_object_from_eeprom(_backend, _backend_var_info[get_type()]);
71
}
72
}
73
74
// run custom controller if it is activated by RC switch and appropriate type is selected
75
void AC_CustomControl::update(void)
76
{
77
if (is_safe_to_run()) {
78
Vector3f motor_out_rpy;
79
80
motor_out_rpy = _backend->update();
81
82
motor_set(motor_out_rpy);
83
}
84
}
85
86
// choose which axis to apply custom controller output
87
void AC_CustomControl::motor_set(Vector3f rpy) {
88
if (_custom_controller_mask & (uint8_t)CustomControlOption::ROLL) {
89
_motors->set_roll(rpy.x);
90
_att_control->get_rate_roll_pid().set_integrator(0.0);
91
}
92
if (_custom_controller_mask & (uint8_t)CustomControlOption::PITCH) {
93
_motors->set_pitch(rpy.y);
94
_att_control->get_rate_pitch_pid().set_integrator(0.0);
95
}
96
if (_custom_controller_mask & (uint8_t)CustomControlOption::YAW) {
97
_motors->set_yaw(rpy.z);
98
_att_control->get_rate_yaw_pid().set_integrator(0.0);
99
}
100
}
101
102
// move main controller's target to current states, reset filters,
103
// and move integrator to motor output
104
// to allow smooth transition to the primary controller
105
void AC_CustomControl::reset_main_att_controller(void)
106
{
107
// reset attitude and rate target, if feedforward is enabled
108
if (_att_control->get_bf_feedforward()) {
109
_att_control->relax_attitude_controllers();
110
}
111
112
_att_control->get_rate_roll_pid().set_integrator(0.0);
113
_att_control->get_rate_pitch_pid().set_integrator(0.0);
114
_att_control->get_rate_yaw_pid().set_integrator(0.0);
115
}
116
117
void AC_CustomControl::set_custom_controller(bool enabled)
118
{
119
// double logging switch makes the state change very clear in the log
120
log_switch();
121
122
_custom_controller_active = false;
123
124
// don't allow accidental main controller reset without active custom controller
125
if (_controller_type == CustomControlType::CONT_NONE) {
126
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller is not enabled");
127
return;
128
}
129
130
// controller type is out of range
131
if (_controller_type > CUSTOMCONTROL_MAX_TYPES) {
132
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller type is out of range");
133
return;
134
}
135
136
// backend is not created
137
if (_backend == nullptr) {
138
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Reboot to enable selected custom controller");
139
return;
140
}
141
142
if (_custom_controller_mask == 0 && enabled) {
143
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Axis mask is not set");
144
return;
145
}
146
147
// reset main controller
148
if (!enabled) {
149
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller is OFF");
150
// don't reset if the empty backend is selected
151
if (_controller_type > CustomControlType::CONT_EMPTY) {
152
reset_main_att_controller();
153
}
154
}
155
156
if (enabled && _controller_type > CustomControlType::CONT_NONE) {
157
// reset custom controller filter, integrator etc.
158
_backend->reset();
159
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller is ON");
160
}
161
162
_custom_controller_active = enabled;
163
164
// log successful switch
165
log_switch();
166
}
167
168
// check that RC switch is on, backend is not changed mid flight and controller type is selected
169
bool AC_CustomControl::is_safe_to_run(void) {
170
if (_custom_controller_active && (_controller_type > CustomControlType::CONT_NONE)
171
&& (_controller_type <= CUSTOMCONTROL_MAX_TYPES) && _backend != nullptr)
172
{
173
return true;
174
}
175
176
return false;
177
}
178
179
// log when the custom controller is switch into
180
void AC_CustomControl::log_switch(void) {
181
AP::logger().Write("CC", "TimeUS,Type,Act","QBB",
182
AP_HAL::micros64(),
183
_controller_type,
184
_custom_controller_active);
185
}
186
187
void AC_CustomControl::set_notch_sample_rate(float sample_rate)
188
{
189
#if AP_FILTER_ENABLED
190
if (_backend != nullptr) {
191
_backend->set_notch_sample_rate(sample_rate);
192
}
193
#endif
194
}
195
196
#endif // AP_CUSTOMCONTROL_ENABLED
197
198