Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/APM_Control/AP_PitchController.cpp
9398 views
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
24
extern const AP_HAL::HAL& hal;
25
26
const AP_Param::GroupInfo AP_PitchController::var_info[] = {
27
28
// @Param: 2SRV_TCONST
29
// @DisplayName: Pitch Time Constant
30
// @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.
31
// @Range: 0.4 1.0
32
// @Units: s
33
// @Increment: 0.1
34
// @User: Advanced
35
AP_GROUPINFO("2SRV_TCONST", 0, AP_PitchController, gains.tau, 0.5f),
36
37
// index 1 to 3 reserved for old PID values
38
39
// @Param: 2SRV_RMAX_UP
40
// @DisplayName: Pitch up max rate
41
// @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.
42
// @Range: 0 100
43
// @Units: deg/s
44
// @Increment: 1
45
// @User: Advanced
46
AP_GROUPINFO("2SRV_RMAX_UP", 4, AP_PitchController, gains.rmax_pos, 0.0f),
47
48
// @Param: 2SRV_RMAX_DN
49
// @DisplayName: Pitch down max rate
50
// @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.
51
// @Range: 0 100
52
// @Units: deg/s
53
// @Increment: 1
54
// @User: Advanced
55
AP_GROUPINFO("2SRV_RMAX_DN", 5, AP_PitchController, gains.rmax_neg, 0.0f),
56
57
// @Param: 2SRV_RLL
58
// @DisplayName: Roll compensation
59
// @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.
60
// @Range: 0.7 1.5
61
// @Increment: 0.05
62
// @User: Standard
63
AP_GROUPINFO("2SRV_RLL", 6, AP_PitchController, _roll_ff, 1.0f),
64
65
// index 7, 8 reserved for old IMAX, FF
66
67
// @Param: _RATE_P
68
// @DisplayName: Pitch axis rate controller P gain
69
// @Description: Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate
70
// @Range: 0.08 0.35
71
// @Increment: 0.005
72
// @User: Standard
73
74
// @Param: _RATE_I
75
// @DisplayName: Pitch axis rate controller I gain
76
// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
77
// @Range: 0.01 0.6
78
// @Increment: 0.01
79
// @User: Standard
80
81
// @Param: _RATE_IMAX
82
// @DisplayName: Pitch axis rate controller I gain maximum
83
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output
84
// @Range: 0 1
85
// @Increment: 0.01
86
// @User: Standard
87
88
// @Param: _RATE_D
89
// @DisplayName: Pitch axis rate controller D gain
90
// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
91
// @Range: 0.001 0.03
92
// @Increment: 0.001
93
// @User: Standard
94
95
// @Param: _RATE_FF
96
// @DisplayName: Pitch axis rate controller feed forward
97
// @Description: Pitch axis rate controller feed forward
98
// @Range: 0 3.0
99
// @Increment: 0.001
100
// @User: Standard
101
102
// @Param: _RATE_FLTT
103
// @DisplayName: Pitch axis rate controller target frequency in Hz
104
// @Description: Pitch axis rate controller target frequency in Hz
105
// @Range: 2 50
106
// @Increment: 1
107
// @Units: Hz
108
// @User: Standard
109
110
// @Param: _RATE_FLTE
111
// @DisplayName: Pitch axis rate controller error frequency in Hz
112
// @Description: Pitch axis rate controller error frequency in Hz
113
// @Range: 2 50
114
// @Increment: 1
115
// @Units: Hz
116
// @User: Standard
117
118
// @Param: _RATE_FLTD
119
// @DisplayName: Pitch axis rate controller derivative frequency in Hz
120
// @Description: Pitch axis rate controller derivative frequency in Hz
121
// @Range: 0 50
122
// @Increment: 1
123
// @Units: Hz
124
// @User: Standard
125
126
// @Param: _RATE_SMAX
127
// @DisplayName: Pitch slew rate limit
128
// @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.
129
// @Range: 0 200
130
// @Increment: 0.5
131
// @User: Advanced
132
133
// @Param: _RATE_PDMX
134
// @DisplayName: Pitch axis rate controller PD sum maximum
135
// @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
136
// @Range: 0 1
137
// @Increment: 0.01
138
139
// @Param: _RATE_D_FF
140
// @DisplayName: Pitch Derivative FeedForward Gain
141
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
142
// @Range: 0 0.03
143
// @Increment: 0.001
144
// @User: Advanced
145
146
// @Param: _RATE_NTF
147
// @DisplayName: Pitch Target notch filter index
148
// @Description: Pitch Target notch filter index
149
// @Range: 1 8
150
// @User: Advanced
151
152
// @Param: _RATE_NEF
153
// @DisplayName: Pitch Error notch filter index
154
// @Description: Pitch Error notch filter index
155
// @Range: 1 8
156
// @User: Advanced
157
158
AP_SUBGROUPINFO(rate_pid, "_RATE_", 11, AP_PitchController, AC_PID),
159
160
AP_GROUPEND
161
};
162
163
AP_PitchController::AP_PitchController(const AP_FixedWing &parms)
164
: AP_FW_Controller(parms,
165
AC_PID::Defaults{
166
.p = 0.04,
167
.i = 0.15,
168
.d = 0.0,
169
.ff = 0.345,
170
.imax = 0.666,
171
.filt_T_hz = 3.0,
172
.filt_E_hz = 0.0,
173
.filt_D_hz = 12.0,
174
.srmax = 150.0,
175
.srtau = 1.0
176
},
177
AP_AutoTune::ATType::AUTOTUNE_PITCH)
178
{
179
AP_Param::setup_object_defaults(this, var_info);
180
}
181
182
float AP_PitchController::get_measured_rate() const
183
{
184
return AP::ahrs().get_gyro().y;
185
}
186
187
float AP_PitchController::get_airspeed() const
188
{
189
float aspeed;
190
if (!AP::ahrs().airspeed_EAS(aspeed)) {
191
// If no airspeed available use average of min and max
192
aspeed = 0.5f*(float(aparm.airspeed_min) + float(aparm.airspeed_max));
193
}
194
return aspeed;
195
}
196
197
bool AP_PitchController::is_underspeed(const float aspeed) const
198
{
199
return aspeed <= 0.5*float(aparm.airspeed_min);
200
}
201
202
/*
203
get the rate offset in degrees/second needed for pitch in body frame
204
to maintain height in a coordinated turn.
205
206
Also returns the inverted flag and the estimated airspeed in m/s for
207
use by the rest of the pitch controller
208
*/
209
float AP_PitchController::_get_coordination_rate_offset(const float &aspeed, bool &inverted) const
210
{
211
float rate_offset;
212
float bank_angle = AP::ahrs().get_roll_rad();
213
214
// limit bank angle between +- 80 deg if right way up
215
if (fabsf(bank_angle) < radians(90)) {
216
bank_angle = constrain_float(bank_angle,-radians(80),radians(80));
217
inverted = false;
218
} else {
219
inverted = true;
220
if (bank_angle > 0.0f) {
221
bank_angle = constrain_float(bank_angle,radians(100),radians(180));
222
} else {
223
bank_angle = constrain_float(bank_angle,-radians(180),-radians(100));
224
}
225
}
226
const AP_AHRS &_ahrs = AP::ahrs();
227
if (abs(_ahrs.pitch_sensor) > 7000) {
228
// don't do turn coordination handling when at very high pitch angles
229
rate_offset = 0;
230
} else {
231
rate_offset = cosf(_ahrs.get_pitch_rad())*fabsf(degrees((GRAVITY_MSS / MAX((aspeed * _ahrs.get_EAS2TAS()), MAX(aparm.airspeed_min, 1))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff;
232
}
233
if (inverted) {
234
rate_offset = -rate_offset;
235
}
236
return rate_offset;
237
}
238
239
// Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500
240
// A positive demand is up
241
// Inputs are:
242
// 1) demanded pitch angle in centi-degrees
243
// 2) control gain scaler = scaling_speed / aspeed
244
// 3) boolean which is true when stabilise mode is active
245
// 4) minimum FBW airspeed (metres/sec)
246
// 5) maximum FBW airspeed (metres/sec)
247
//
248
float AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode)
249
{
250
// Calculate offset to pitch rate demand required to maintain pitch angle whilst banking
251
// Calculate ideal turn rate from bank angle and airspeed assuming a level coordinated turn
252
// Pitch rate offset is the component of turn rate about the pitch axis
253
float rate_offset;
254
bool inverted;
255
256
if (gains.tau < 0.05f) {
257
gains.tau.set(0.05f);
258
}
259
260
const float aspeed = get_airspeed();
261
262
rate_offset = _get_coordination_rate_offset(aspeed, inverted);
263
264
// Calculate the desired pitch rate (deg/sec) from the angle error
265
angle_err_deg = angle_err * 0.01;
266
float desired_rate = angle_err_deg / gains.tau;
267
268
// limit the maximum pitch rate demand. Don't apply when inverted
269
// as the rates will be tuned when upright, and it is common that
270
// much higher rates are needed inverted
271
if (!inverted) {
272
desired_rate += rate_offset;
273
if (gains.rmax_neg && desired_rate < -gains.rmax_neg) {
274
desired_rate = -gains.rmax_neg;
275
} else if (gains.rmax_pos && desired_rate > gains.rmax_pos) {
276
desired_rate = gains.rmax_pos;
277
}
278
} else {
279
// Make sure not to invert the turn coordination offset
280
desired_rate = -desired_rate + rate_offset;
281
}
282
283
/*
284
when we are past the users defined roll limit for the aircraft
285
our priority should be to bring the aircraft back within the
286
roll limit. Using elevator for pitch control at large roll
287
angles is ineffective, and can be counter productive as it
288
induces earth-frame yaw which can reduce the ability to roll. We
289
linearly reduce pitch demanded rate when beyond the configured
290
roll limit, reducing to zero at 90 degrees
291
*/
292
const AP_AHRS &_ahrs = AP::ahrs();
293
float roll_wrapped = labs(_ahrs.roll_sensor);
294
if (roll_wrapped > 9000) {
295
roll_wrapped = 18000 - roll_wrapped;
296
}
297
const float roll_limit_margin = MIN(aparm.roll_limit*100 + 500.0, 8500.0);
298
if (roll_wrapped > roll_limit_margin && labs(_ahrs.pitch_sensor) < 7000) {
299
float roll_prop = (roll_wrapped - roll_limit_margin) / (float)(9000 - roll_limit_margin);
300
desired_rate *= (1 - roll_prop);
301
}
302
303
return _get_rate_out(desired_rate, scaler, disable_integrator, aspeed, ground_mode);
304
}
305
306
/*
307
convert from old to new PIDs
308
this is a temporary conversion function during development
309
*/
310
void AP_PitchController::convert_pid()
311
{
312
AP_Float &ff = rate_pid.ff();
313
if (ff.configured()) {
314
return;
315
}
316
317
float old_ff=0, old_p=1.0, old_i=0.3, old_d=0.08;
318
int16_t old_imax = 3000;
319
bool have_old = AP_Param::get_param_by_index(this, 1, AP_PARAM_FLOAT, &old_p);
320
have_old |= AP_Param::get_param_by_index(this, 3, AP_PARAM_FLOAT, &old_i);
321
have_old |= AP_Param::get_param_by_index(this, 2, AP_PARAM_FLOAT, &old_d);
322
have_old |= AP_Param::get_param_by_index(this, 8, AP_PARAM_FLOAT, &old_ff);
323
have_old |= AP_Param::get_param_by_index(this, 7, AP_PARAM_FLOAT, &old_imax);
324
if (!have_old) {
325
// none of the old gains were set
326
return;
327
}
328
329
const float kp_ff = MAX((old_p - old_i * gains.tau) * gains.tau - old_d, 0);
330
rate_pid.ff().set_and_save(old_ff + kp_ff);
331
rate_pid.kI().set_and_save_ifchanged(old_i * gains.tau);
332
rate_pid.kP().set_and_save_ifchanged(old_d);
333
rate_pid.kD().set_and_save_ifchanged(0);
334
rate_pid.kIMAX().set_and_save_ifchanged(old_imax/4500.0);
335
}
336
337