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