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/APM_Control/AP_RollController.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
// Code by Jon Challinger
17
// Modified by Paul Riseborough
18
//
19
20
#include <AP_HAL/AP_HAL.h>
21
#include "AP_RollController.h"
22
#include <AP_AHRS/AP_AHRS.h>
23
#include <AP_Scheduler/AP_Scheduler.h>
24
#include <GCS_MAVLink/GCS.h>
25
26
extern const AP_HAL::HAL& hal;
27
28
const AP_Param::GroupInfo AP_RollController::var_info[] = {
29
// @Param: 2SRV_TCONST
30
// @DisplayName: Roll Time Constant
31
// @Description: Time constant in seconds from demanded to achieved roll angle. Most models respond well to 0.5. May be reduced for faster responses, but setting lower than a model can achieve will not help.
32
// @Range: 0.4 1.0
33
// @Units: s
34
// @Increment: 0.1
35
// @User: Advanced
36
AP_GROUPINFO("2SRV_TCONST", 0, AP_RollController, gains.tau, 0.5f),
37
38
// index 1 to 3 reserved for old PID values
39
40
// @Param: 2SRV_RMAX
41
// @DisplayName: Maximum Roll Rate
42
// @Description: This sets the maximum roll rate that the attitude controller will demand (degrees/sec) in angle stabilized modes. Setting it to zero disables this limit.
43
// @Range: 0 180
44
// @Units: deg/s
45
// @Increment: 1
46
// @User: Advanced
47
AP_GROUPINFO("2SRV_RMAX", 4, AP_RollController, gains.rmax_pos, 0),
48
49
// index 5, 6 reserved for old IMAX, FF
50
51
// @Param: _RATE_P
52
// @DisplayName: Roll axis rate controller P gain
53
// @Description: Roll axis rate controller P gain. Corrects in proportion to the difference between the desired roll rate vs actual roll rate
54
// @Range: 0.08 0.35
55
// @Increment: 0.005
56
// @User: Standard
57
58
// @Param: _RATE_I
59
// @DisplayName: Roll axis rate controller I gain
60
// @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
61
// @Range: 0.01 0.6
62
// @Increment: 0.01
63
// @User: Standard
64
65
// @Param: _RATE_IMAX
66
// @DisplayName: Roll axis rate controller I gain maximum
67
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum that the I term will output
68
// @Range: 0 1
69
// @Increment: 0.01
70
// @User: Standard
71
72
// @Param: _RATE_D
73
// @DisplayName: Roll axis rate controller D gain
74
// @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
75
// @Range: 0.001 0.03
76
// @Increment: 0.001
77
// @User: Standard
78
79
// @Param: _RATE_FF
80
// @DisplayName: Roll axis rate controller feed forward
81
// @Description: Roll axis rate controller feed forward
82
// @Range: 0 3.0
83
// @Increment: 0.001
84
// @User: Standard
85
86
// @Param: _RATE_FLTT
87
// @DisplayName: Roll axis rate controller target frequency in Hz
88
// @Description: Roll axis rate controller target frequency in Hz
89
// @Range: 2 50
90
// @Increment: 1
91
// @Units: Hz
92
// @User: Standard
93
94
// @Param: _RATE_FLTE
95
// @DisplayName: Roll axis rate controller error frequency in Hz
96
// @Description: Roll axis rate controller error frequency in Hz
97
// @Range: 2 50
98
// @Increment: 1
99
// @Units: Hz
100
// @User: Standard
101
102
// @Param: _RATE_FLTD
103
// @DisplayName: Roll axis rate controller derivative frequency in Hz
104
// @Description: Roll axis rate controller derivative frequency in Hz
105
// @Range: 0 50
106
// @Increment: 1
107
// @Units: Hz
108
// @User: Standard
109
110
// @Param: _RATE_SMAX
111
// @DisplayName: Roll slew rate limit
112
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
113
// @Range: 0 200
114
// @Increment: 0.5
115
// @User: Advanced
116
117
// @Param: _RATE_PDMX
118
// @DisplayName: Roll axis rate controller PD sum maximum
119
// @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
120
// @Range: 0 1
121
// @Increment: 0.01
122
123
// @Param: _RATE_D_FF
124
// @DisplayName: Roll Derivative FeedForward Gain
125
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
126
// @Range: 0 0.03
127
// @Increment: 0.001
128
// @User: Advanced
129
130
// @Param: _RATE_NTF
131
// @DisplayName: Roll Target notch filter index
132
// @Description: Roll Target notch filter index
133
// @Range: 1 8
134
// @User: Advanced
135
136
// @Param: _RATE_NEF
137
// @DisplayName: Roll Error notch filter index
138
// @Description: Roll Error notch filter index
139
// @Range: 1 8
140
// @User: Advanced
141
142
AP_SUBGROUPINFO(rate_pid, "_RATE_", 9, AP_RollController, AC_PID),
143
144
AP_GROUPEND
145
};
146
147
// constructor
148
AP_RollController::AP_RollController(const AP_FixedWing &parms)
149
: aparm(parms)
150
{
151
AP_Param::setup_object_defaults(this, var_info);
152
rate_pid.set_slew_limit_scale(45);
153
}
154
155
156
/*
157
AC_PID based rate controller
158
*/
159
float AP_RollController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator, bool ground_mode)
160
{
161
const AP_AHRS &_ahrs = AP::ahrs();
162
163
const float dt = AP::scheduler().get_loop_period_s();
164
const float eas2tas = _ahrs.get_EAS2TAS();
165
bool limit_I = fabsf(_last_out) >= 45;
166
float rate_x = _ahrs.get_gyro().x;
167
float aspeed;
168
float old_I = rate_pid.get_i();
169
170
if (!_ahrs.airspeed_estimate(aspeed)) {
171
aspeed = 0;
172
}
173
bool underspeed = aspeed <= float(aparm.airspeed_min);
174
if (underspeed) {
175
limit_I = true;
176
}
177
178
// the P and I elements are scaled by sq(scaler). To use an
179
// unmodified AC_PID object we scale the inputs and calculate FF separately
180
//
181
// note that we run AC_PID in radians so that the normal scaling
182
// range for IMAX in AC_PID applies (usually an IMAX value less than 1.0)
183
rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate_x * scaler * scaler, dt, limit_I);
184
185
if (underspeed) {
186
// when underspeed we lock the integrator
187
rate_pid.set_integrator(old_I);
188
}
189
190
// FF should be scaled by scaler/eas2tas, but since we have scaled
191
// the AC_PID target above by scaler*scaler we need to instead
192
// divide by scaler*eas2tas to get the right scaling
193
const float ff = degrees(ff_scale * rate_pid.get_ff() / (scaler * eas2tas));
194
ff_scale = 1.0;
195
196
if (disable_integrator) {
197
rate_pid.reset_I();
198
}
199
200
// convert AC_PID info object to same scale as old controller
201
_pid_info = rate_pid.get_pid_info();
202
auto &pinfo = _pid_info;
203
204
const float deg_scale = degrees(1);
205
pinfo.FF = ff;
206
pinfo.P *= deg_scale;
207
pinfo.I *= deg_scale;
208
pinfo.D *= deg_scale;
209
pinfo.DFF *= deg_scale;
210
211
// fix the logged target and actual values to not have the scalers applied
212
pinfo.target = desired_rate;
213
pinfo.actual = degrees(rate_x);
214
215
// sum components
216
float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D + pinfo.DFF;
217
if (ground_mode) {
218
// when on ground suppress D term to prevent oscillations
219
out -= pinfo.D + 0.5*pinfo.P;
220
}
221
222
// remember the last output to trigger the I limit
223
_last_out = out;
224
225
if (autotune != nullptr && autotune->running && aspeed > aparm.airspeed_min) {
226
// let autotune have a go at the values
227
autotune->update(pinfo, scaler, angle_err_deg);
228
}
229
230
// output is scaled to notional centidegrees of deflection
231
return constrain_float(out * 100, -4500, 4500);
232
}
233
234
/*
235
Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500
236
A positive demand is up
237
Inputs are:
238
1) desired roll rate in degrees/sec
239
2) control gain scaler = scaling_speed / aspeed
240
*/
241
float AP_RollController::get_rate_out(float desired_rate, float scaler)
242
{
243
return _get_rate_out(desired_rate, scaler, false, false);
244
}
245
246
/*
247
Function returns an equivalent aileron deflection in centi-degrees in the range from -4500 to 4500
248
A positive demand is up
249
Inputs are:
250
1) demanded bank angle in centi-degrees
251
2) control gain scaler = scaling_speed / aspeed
252
3) boolean which is true when stabilise mode is active
253
4) minimum FBW airspeed (metres/sec)
254
*/
255
float AP_RollController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode)
256
{
257
if (gains.tau < 0.05f) {
258
gains.tau.set(0.05f);
259
}
260
261
// Calculate the desired roll rate (deg/sec) from the angle error
262
angle_err_deg = angle_err * 0.01;
263
float desired_rate = angle_err_deg/ gains.tau;
264
265
// Limit the demanded roll rate
266
if (gains.rmax_pos && desired_rate < -gains.rmax_pos) {
267
desired_rate = - gains.rmax_pos;
268
} else if (gains.rmax_pos && desired_rate > gains.rmax_pos) {
269
desired_rate = gains.rmax_pos;
270
}
271
272
return _get_rate_out(desired_rate, scaler, disable_integrator, ground_mode);
273
}
274
275
void AP_RollController::reset_I()
276
{
277
rate_pid.reset_I();
278
}
279
280
/*
281
convert from old to new PIDs
282
this is a temporary conversion function during development
283
*/
284
void AP_RollController::convert_pid()
285
{
286
AP_Float &ff = rate_pid.ff();
287
if (ff.configured()) {
288
return;
289
}
290
float old_ff=0, old_p=1.0, old_i=0.3, old_d=0.08;
291
int16_t old_imax=3000;
292
bool have_old = AP_Param::get_param_by_index(this, 1, AP_PARAM_FLOAT, &old_p);
293
have_old |= AP_Param::get_param_by_index(this, 3, AP_PARAM_FLOAT, &old_i);
294
have_old |= AP_Param::get_param_by_index(this, 2, AP_PARAM_FLOAT, &old_d);
295
have_old |= AP_Param::get_param_by_index(this, 6, AP_PARAM_FLOAT, &old_ff);
296
have_old |= AP_Param::get_param_by_index(this, 5, AP_PARAM_INT16, &old_imax);
297
if (!have_old) {
298
// none of the old gains were set
299
return;
300
}
301
302
const float kp_ff = MAX((old_p - old_i * gains.tau) * gains.tau - old_d, 0);
303
rate_pid.ff().set_and_save(old_ff + kp_ff);
304
rate_pid.kI().set_and_save_ifchanged(old_i * gains.tau);
305
rate_pid.kP().set_and_save_ifchanged(old_d);
306
rate_pid.kD().set_and_save_ifchanged(0);
307
rate_pid.kIMAX().set_and_save_ifchanged(old_imax/4500.0);
308
}
309
310
/*
311
start an autotune
312
*/
313
void AP_RollController::autotune_start(void)
314
{
315
if (autotune == nullptr) {
316
autotune = NEW_NOTHROW AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_ROLL, aparm, rate_pid);
317
if (autotune == nullptr) {
318
if (!failed_autotune_alloc) {
319
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed roll allocation");
320
}
321
failed_autotune_alloc = true;
322
}
323
}
324
if (autotune != nullptr) {
325
autotune->start();
326
}
327
}
328
329
/*
330
restore autotune gains
331
*/
332
void AP_RollController::autotune_restore(void)
333
{
334
if (autotune != nullptr) {
335
autotune->stop();
336
}
337
}
338
339