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_PitchController.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
// Initial Code by Jon Challinger
17
// Modified by Paul Riseborough
18
19
#include <AP_HAL/AP_HAL.h>
20
#include "AP_PitchController.h"
21
#include <AP_AHRS/AP_AHRS.h>
22
#include <AP_Scheduler/AP_Scheduler.h>
23
#include <GCS_MAVLink/GCS.h>
24
25
extern const AP_HAL::HAL& hal;
26
27
const AP_Param::GroupInfo AP_PitchController::var_info[] = {
28
29
// @Param: 2SRV_TCONST
30
// @DisplayName: Pitch Time Constant
31
// @Description: Time constant in seconds from demanded to achieved pitch 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_PitchController, gains.tau, 0.5f),
37
38
// index 1 to 3 reserved for old PID values
39
40
// @Param: 2SRV_RMAX_UP
41
// @DisplayName: Pitch up max rate
42
// @Description: This sets the maximum nose up pitch rate that the attitude controller will demand (degrees/sec) in angle stabilized modes. Setting it to zero disables the limit.
43
// @Range: 0 100
44
// @Units: deg/s
45
// @Increment: 1
46
// @User: Advanced
47
AP_GROUPINFO("2SRV_RMAX_UP", 4, AP_PitchController, gains.rmax_pos, 0.0f),
48
49
// @Param: 2SRV_RMAX_DN
50
// @DisplayName: Pitch down max rate
51
// @Description: This sets the maximum nose down pitch rate that the attitude controller will demand (degrees/sec) in angle stabilized modes. Setting it to zero disables the limit.
52
// @Range: 0 100
53
// @Units: deg/s
54
// @Increment: 1
55
// @User: Advanced
56
AP_GROUPINFO("2SRV_RMAX_DN", 5, AP_PitchController, gains.rmax_neg, 0.0f),
57
58
// @Param: 2SRV_RLL
59
// @DisplayName: Roll compensation
60
// @Description: Gain added to pitch to keep aircraft from descending or ascending in turns. Increase in increments of 0.05 to reduce altitude loss. Decrease for altitude gain.
61
// @Range: 0.7 1.5
62
// @Increment: 0.05
63
// @User: Standard
64
AP_GROUPINFO("2SRV_RLL", 6, AP_PitchController, _roll_ff, 1.0f),
65
66
// index 7, 8 reserved for old IMAX, FF
67
68
// @Param: _RATE_P
69
// @DisplayName: Pitch axis rate controller P gain
70
// @Description: Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate
71
// @Range: 0.08 0.35
72
// @Increment: 0.005
73
// @User: Standard
74
75
// @Param: _RATE_I
76
// @DisplayName: Pitch axis rate controller I gain
77
// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
78
// @Range: 0.01 0.6
79
// @Increment: 0.01
80
// @User: Standard
81
82
// @Param: _RATE_IMAX
83
// @DisplayName: Pitch axis rate controller I gain maximum
84
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output
85
// @Range: 0 1
86
// @Increment: 0.01
87
// @User: Standard
88
89
// @Param: _RATE_D
90
// @DisplayName: Pitch axis rate controller D gain
91
// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
92
// @Range: 0.001 0.03
93
// @Increment: 0.001
94
// @User: Standard
95
96
// @Param: _RATE_FF
97
// @DisplayName: Pitch axis rate controller feed forward
98
// @Description: Pitch axis rate controller feed forward
99
// @Range: 0 3.0
100
// @Increment: 0.001
101
// @User: Standard
102
103
// @Param: _RATE_FLTT
104
// @DisplayName: Pitch axis rate controller target frequency in Hz
105
// @Description: Pitch axis rate controller target frequency in Hz
106
// @Range: 2 50
107
// @Increment: 1
108
// @Units: Hz
109
// @User: Standard
110
111
// @Param: _RATE_FLTE
112
// @DisplayName: Pitch axis rate controller error frequency in Hz
113
// @Description: Pitch axis rate controller error frequency in Hz
114
// @Range: 2 50
115
// @Increment: 1
116
// @Units: Hz
117
// @User: Standard
118
119
// @Param: _RATE_FLTD
120
// @DisplayName: Pitch axis rate controller derivative frequency in Hz
121
// @Description: Pitch axis rate controller derivative frequency in Hz
122
// @Range: 0 50
123
// @Increment: 1
124
// @Units: Hz
125
// @User: Standard
126
127
// @Param: _RATE_SMAX
128
// @DisplayName: Pitch slew rate limit
129
// @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.
130
// @Range: 0 200
131
// @Increment: 0.5
132
// @User: Advanced
133
134
// @Param: _RATE_PDMX
135
// @DisplayName: Pitch axis rate controller PD sum maximum
136
// @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
137
// @Range: 0 1
138
// @Increment: 0.01
139
140
// @Param: _RATE_D_FF
141
// @DisplayName: Pitch Derivative FeedForward Gain
142
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
143
// @Range: 0 0.03
144
// @Increment: 0.001
145
// @User: Advanced
146
147
// @Param: _RATE_NTF
148
// @DisplayName: Pitch Target notch filter index
149
// @Description: Pitch Target notch filter index
150
// @Range: 1 8
151
// @User: Advanced
152
153
// @Param: _RATE_NEF
154
// @DisplayName: Pitch Error notch filter index
155
// @Description: Pitch Error notch filter index
156
// @Range: 1 8
157
// @User: Advanced
158
159
AP_SUBGROUPINFO(rate_pid, "_RATE_", 11, AP_PitchController, AC_PID),
160
161
AP_GROUPEND
162
};
163
164
AP_PitchController::AP_PitchController(const AP_FixedWing &parms)
165
: aparm(parms)
166
{
167
AP_Param::setup_object_defaults(this, var_info);
168
rate_pid.set_slew_limit_scale(45);
169
}
170
171
/*
172
AC_PID based rate controller
173
*/
174
float AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed, bool ground_mode)
175
{
176
const float dt = AP::scheduler().get_loop_period_s();
177
178
const AP_AHRS &_ahrs = AP::ahrs();
179
180
const float eas2tas = _ahrs.get_EAS2TAS();
181
bool limit_I = fabsf(_last_out) >= 45;
182
float rate_y = _ahrs.get_gyro().y;
183
float old_I = rate_pid.get_i();
184
185
bool underspeed = aspeed <= 0.5*float(aparm.airspeed_min);
186
if (underspeed) {
187
limit_I = true;
188
}
189
190
// the P and I elements are scaled by sq(scaler). To use an
191
// unmodified AC_PID object we scale the inputs and calculate FF separately
192
//
193
// note that we run AC_PID in radians so that the normal scaling
194
// range for IMAX in AC_PID applies (usually an IMAX value less than 1.0)
195
rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate_y * scaler * scaler, dt, limit_I);
196
197
if (underspeed) {
198
// when underspeed we lock the integrator
199
rate_pid.set_integrator(old_I);
200
}
201
202
// FF should be scaled by scaler/eas2tas, but since we have scaled
203
// the AC_PID target above by scaler*scaler we need to instead
204
// divide by scaler*eas2tas to get the right scaling
205
const float ff = degrees(ff_scale * rate_pid.get_ff() / (scaler * eas2tas));
206
ff_scale = 1.0;
207
208
if (disable_integrator) {
209
rate_pid.reset_I();
210
}
211
212
// convert AC_PID info object to same scale as old controller
213
_pid_info = rate_pid.get_pid_info();
214
auto &pinfo = _pid_info;
215
216
const float deg_scale = degrees(1);
217
pinfo.FF = ff;
218
pinfo.P *= deg_scale;
219
pinfo.I *= deg_scale;
220
pinfo.D *= deg_scale;
221
pinfo.DFF *= deg_scale;
222
223
// fix the logged target and actual values to not have the scalers applied
224
pinfo.target = desired_rate;
225
pinfo.actual = degrees(rate_y);
226
227
// sum components
228
float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D + pinfo.DFF;
229
if (ground_mode) {
230
// when on ground suppress D and half P term to prevent oscillations
231
out -= pinfo.D + 0.5*pinfo.P;
232
}
233
234
// remember the last output to trigger the I limit
235
_last_out = out;
236
237
if (autotune != nullptr && autotune->running && aspeed > aparm.airspeed_min) {
238
// let autotune have a go at the values
239
autotune->update(pinfo, scaler, angle_err_deg);
240
}
241
242
// output is scaled to notional centidegrees of deflection
243
return constrain_float(out * 100, -4500, 4500);
244
}
245
246
/*
247
Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500
248
A positive demand is up
249
Inputs are:
250
1) demanded pitch rate in degrees/second
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
5) maximum FBW airspeed (metres/sec)
255
*/
256
float AP_PitchController::get_rate_out(float desired_rate, float scaler)
257
{
258
float aspeed;
259
if (!AP::ahrs().airspeed_estimate(aspeed)) {
260
// If no airspeed available use average of min and max
261
aspeed = 0.5f*(float(aparm.airspeed_min) + float(aparm.airspeed_max));
262
}
263
return _get_rate_out(desired_rate, scaler, false, aspeed, false);
264
}
265
266
/*
267
get the rate offset in degrees/second needed for pitch in body frame
268
to maintain height in a coordinated turn.
269
270
Also returns the inverted flag and the estimated airspeed in m/s for
271
use by the rest of the pitch controller
272
*/
273
float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inverted) const
274
{
275
float rate_offset;
276
float bank_angle = AP::ahrs().get_roll();
277
278
// limit bank angle between +- 80 deg if right way up
279
if (fabsf(bank_angle) < radians(90)) {
280
bank_angle = constrain_float(bank_angle,-radians(80),radians(80));
281
inverted = false;
282
} else {
283
inverted = true;
284
if (bank_angle > 0.0f) {
285
bank_angle = constrain_float(bank_angle,radians(100),radians(180));
286
} else {
287
bank_angle = constrain_float(bank_angle,-radians(180),-radians(100));
288
}
289
}
290
const AP_AHRS &_ahrs = AP::ahrs();
291
if (!_ahrs.airspeed_estimate(aspeed)) {
292
// If no airspeed available use average of min and max
293
aspeed = 0.5f*(float(aparm.airspeed_min) + float(aparm.airspeed_max));
294
}
295
if (abs(_ahrs.pitch_sensor) > 7000) {
296
// don't do turn coordination handling when at very high pitch angles
297
rate_offset = 0;
298
} else {
299
rate_offset = cosf(_ahrs.get_pitch())*fabsf(ToDeg((GRAVITY_MSS / MAX((aspeed * _ahrs.get_EAS2TAS()), MAX(aparm.airspeed_min, 1))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff;
300
}
301
if (inverted) {
302
rate_offset = -rate_offset;
303
}
304
return rate_offset;
305
}
306
307
// Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500
308
// A positive demand is up
309
// Inputs are:
310
// 1) demanded pitch angle in centi-degrees
311
// 2) control gain scaler = scaling_speed / aspeed
312
// 3) boolean which is true when stabilise mode is active
313
// 4) minimum FBW airspeed (metres/sec)
314
// 5) maximum FBW airspeed (metres/sec)
315
//
316
float AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode)
317
{
318
// Calculate offset to pitch rate demand required to maintain pitch angle whilst banking
319
// Calculate ideal turn rate from bank angle and airspeed assuming a level coordinated turn
320
// Pitch rate offset is the component of turn rate about the pitch axis
321
float aspeed;
322
float rate_offset;
323
bool inverted;
324
325
if (gains.tau < 0.05f) {
326
gains.tau.set(0.05f);
327
}
328
329
rate_offset = _get_coordination_rate_offset(aspeed, inverted);
330
331
// Calculate the desired pitch rate (deg/sec) from the angle error
332
angle_err_deg = angle_err * 0.01;
333
float desired_rate = angle_err_deg / gains.tau;
334
335
// limit the maximum pitch rate demand. Don't apply when inverted
336
// as the rates will be tuned when upright, and it is common that
337
// much higher rates are needed inverted
338
if (!inverted) {
339
desired_rate += rate_offset;
340
if (gains.rmax_neg && desired_rate < -gains.rmax_neg) {
341
desired_rate = -gains.rmax_neg;
342
} else if (gains.rmax_pos && desired_rate > gains.rmax_pos) {
343
desired_rate = gains.rmax_pos;
344
}
345
} else {
346
// Make sure not to invert the turn coordination offset
347
desired_rate = -desired_rate + rate_offset;
348
}
349
350
/*
351
when we are past the users defined roll limit for the aircraft
352
our priority should be to bring the aircraft back within the
353
roll limit. Using elevator for pitch control at large roll
354
angles is ineffective, and can be counter productive as it
355
induces earth-frame yaw which can reduce the ability to roll. We
356
linearly reduce pitch demanded rate when beyond the configured
357
roll limit, reducing to zero at 90 degrees
358
*/
359
const AP_AHRS &_ahrs = AP::ahrs();
360
float roll_wrapped = labs(_ahrs.roll_sensor);
361
if (roll_wrapped > 9000) {
362
roll_wrapped = 18000 - roll_wrapped;
363
}
364
const float roll_limit_margin = MIN(aparm.roll_limit*100 + 500.0, 8500.0);
365
if (roll_wrapped > roll_limit_margin && labs(_ahrs.pitch_sensor) < 7000) {
366
float roll_prop = (roll_wrapped - roll_limit_margin) / (float)(9000 - roll_limit_margin);
367
desired_rate *= (1 - roll_prop);
368
}
369
370
return _get_rate_out(desired_rate, scaler, disable_integrator, aspeed, ground_mode);
371
}
372
373
void AP_PitchController::reset_I()
374
{
375
rate_pid.reset_I();
376
}
377
378
/*
379
convert from old to new PIDs
380
this is a temporary conversion function during development
381
*/
382
void AP_PitchController::convert_pid()
383
{
384
AP_Float &ff = rate_pid.ff();
385
if (ff.configured()) {
386
return;
387
}
388
389
float old_ff=0, old_p=1.0, old_i=0.3, old_d=0.08;
390
int16_t old_imax = 3000;
391
bool have_old = AP_Param::get_param_by_index(this, 1, AP_PARAM_FLOAT, &old_p);
392
have_old |= AP_Param::get_param_by_index(this, 3, AP_PARAM_FLOAT, &old_i);
393
have_old |= AP_Param::get_param_by_index(this, 2, AP_PARAM_FLOAT, &old_d);
394
have_old |= AP_Param::get_param_by_index(this, 8, AP_PARAM_FLOAT, &old_ff);
395
have_old |= AP_Param::get_param_by_index(this, 7, AP_PARAM_FLOAT, &old_imax);
396
if (!have_old) {
397
// none of the old gains were set
398
return;
399
}
400
401
const float kp_ff = MAX((old_p - old_i * gains.tau) * gains.tau - old_d, 0);
402
rate_pid.ff().set_and_save(old_ff + kp_ff);
403
rate_pid.kI().set_and_save_ifchanged(old_i * gains.tau);
404
rate_pid.kP().set_and_save_ifchanged(old_d);
405
rate_pid.kD().set_and_save_ifchanged(0);
406
rate_pid.kIMAX().set_and_save_ifchanged(old_imax/4500.0);
407
}
408
409
/*
410
start an autotune
411
*/
412
void AP_PitchController::autotune_start(void)
413
{
414
if (autotune == nullptr) {
415
autotune = NEW_NOTHROW AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_PITCH, aparm, rate_pid);
416
if (autotune == nullptr) {
417
if (!failed_autotune_alloc) {
418
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed pitch allocation");
419
}
420
failed_autotune_alloc = true;
421
}
422
}
423
if (autotune != nullptr) {
424
autotune->start();
425
}
426
}
427
428
/*
429
restore autotune gains
430
*/
431
void AP_PitchController::autotune_restore(void)
432
{
433
if (autotune != nullptr) {
434
autotune->stop();
435
}
436
}
437
438