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_AttitudeControl/AC_AttitudeControl_Multi.cpp
Views: 1798
1
#include "AC_AttitudeControl_Multi.h"
2
#include <AP_HAL/AP_HAL.h>
3
#include <AP_Math/AP_Math.h>
4
#include <AC_PID/AC_PID.h>
5
#include <AP_Scheduler/AP_Scheduler.h>
6
7
// table of user settable parameters
8
const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
9
// parameters from parent vehicle
10
AP_NESTEDGROUPINFO(AC_AttitudeControl, 0),
11
12
// @Param: RAT_RLL_P
13
// @DisplayName: Roll axis rate controller P gain
14
// @Description: Roll axis rate controller P gain. Corrects in proportion to the difference between the desired roll rate vs actual roll rate
15
// @Range: 0.01 0.5
16
// @Increment: 0.005
17
// @User: Standard
18
19
// @Param: RAT_RLL_I
20
// @DisplayName: Roll axis rate controller I gain
21
// @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
22
// @Range: 0.01 2.0
23
// @Increment: 0.01
24
// @User: Standard
25
26
// @Param: RAT_RLL_IMAX
27
// @DisplayName: Roll axis rate controller I gain maximum
28
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum that the I term will output
29
// @Range: 0 1
30
// @Increment: 0.01
31
// @User: Standard
32
33
// @Param: RAT_RLL_D
34
// @DisplayName: Roll axis rate controller D gain
35
// @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
36
// @Range: 0.0 0.05
37
// @Increment: 0.001
38
// @User: Standard
39
40
// @Param: RAT_RLL_FF
41
// @DisplayName: Roll axis rate controller feed forward
42
// @Description: Roll axis rate controller feed forward
43
// @Range: 0 0.5
44
// @Increment: 0.001
45
// @User: Standard
46
47
// @Param: RAT_RLL_FLTT
48
// @DisplayName: Roll axis rate controller target frequency in Hz
49
// @Description: Roll axis rate controller target frequency in Hz
50
// @Range: 5 100
51
// @Increment: 1
52
// @Units: Hz
53
// @User: Standard
54
55
// @Param: RAT_RLL_FLTE
56
// @DisplayName: Roll axis rate controller error frequency in Hz
57
// @Description: Roll axis rate controller error frequency in Hz
58
// @Range: 0 100
59
// @Increment: 1
60
// @Units: Hz
61
// @User: Standard
62
63
// @Param: RAT_RLL_FLTD
64
// @DisplayName: Roll axis rate controller derivative frequency in Hz
65
// @Description: Roll axis rate controller derivative frequency in Hz
66
// @Range: 5 100
67
// @Increment: 1
68
// @Units: Hz
69
// @User: Standard
70
71
// @Param: RAT_RLL_SMAX
72
// @DisplayName: Roll slew rate limit
73
// @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.
74
// @Range: 0 200
75
// @Increment: 0.5
76
// @User: Advanced
77
78
// @Param: RAT_RLL_PDMX
79
// @DisplayName: Roll axis rate controller PD sum maximum
80
// @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
81
// @Range: 0 1
82
// @Increment: 0.01
83
84
// @Param: RAT_RLL_D_FF
85
// @DisplayName: Roll Derivative FeedForward Gain
86
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
87
// @Range: 0 0.02
88
// @Increment: 0.0001
89
// @User: Advanced
90
91
// @Param: RAT_RLL_NTF
92
// @DisplayName: Roll Target notch filter index
93
// @Description: Roll Target notch filter index
94
// @Range: 1 8
95
// @User: Advanced
96
97
// @Param: RAT_RLL_NEF
98
// @DisplayName: Roll Error notch filter index
99
// @Description: Roll Error notch filter index
100
// @Range: 1 8
101
// @User: Advanced
102
103
AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Multi, AC_PID),
104
105
// @Param: RAT_PIT_P
106
// @DisplayName: Pitch axis rate controller P gain
107
// @Description: Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate output
108
// @Range: 0.01 0.50
109
// @Increment: 0.005
110
// @User: Standard
111
112
// @Param: RAT_PIT_I
113
// @DisplayName: Pitch axis rate controller I gain
114
// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
115
// @Range: 0.01 2.0
116
// @Increment: 0.01
117
// @User: Standard
118
119
// @Param: RAT_PIT_IMAX
120
// @DisplayName: Pitch axis rate controller I gain maximum
121
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output
122
// @Range: 0 1
123
// @Increment: 0.01
124
// @User: Standard
125
126
// @Param: RAT_PIT_D
127
// @DisplayName: Pitch axis rate controller D gain
128
// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
129
// @Range: 0.0 0.05
130
// @Increment: 0.001
131
// @User: Standard
132
133
// @Param: RAT_PIT_FF
134
// @DisplayName: Pitch axis rate controller feed forward
135
// @Description: Pitch axis rate controller feed forward
136
// @Range: 0 0.5
137
// @Increment: 0.001
138
// @User: Standard
139
140
// @Param: RAT_PIT_FLTT
141
// @DisplayName: Pitch axis rate controller target frequency in Hz
142
// @Description: Pitch axis rate controller target frequency in Hz
143
// @Range: 5 100
144
// @Increment: 1
145
// @Units: Hz
146
// @User: Standard
147
148
// @Param: RAT_PIT_FLTE
149
// @DisplayName: Pitch axis rate controller error frequency in Hz
150
// @Description: Pitch axis rate controller error frequency in Hz
151
// @Range: 0 100
152
// @Increment: 1
153
// @Units: Hz
154
// @User: Standard
155
156
// @Param: RAT_PIT_FLTD
157
// @DisplayName: Pitch axis rate controller derivative frequency in Hz
158
// @Description: Pitch axis rate controller derivative frequency in Hz
159
// @Range: 5 100
160
// @Increment: 1
161
// @Units: Hz
162
// @User: Standard
163
164
// @Param: RAT_PIT_SMAX
165
// @DisplayName: Pitch slew rate limit
166
// @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.
167
// @Range: 0 200
168
// @Increment: 0.5
169
// @User: Advanced
170
171
// @Param: RAT_PIT_PDMX
172
// @DisplayName: Pitch axis rate controller PD sum maximum
173
// @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
174
// @Range: 0 1
175
// @Increment: 0.01
176
177
// @Param: RAT_PIT_D_FF
178
// @DisplayName: Pitch Derivative FeedForward Gain
179
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
180
// @Range: 0 0.02
181
// @Increment: 0.0001
182
// @User: Advanced
183
184
// @Param: RAT_PIT_NTF
185
// @DisplayName: Pitch Target notch filter index
186
// @Description: Pitch Target notch filter index
187
// @Range: 1 8
188
// @User: Advanced
189
190
// @Param: RAT_PIT_NEF
191
// @DisplayName: Pitch Error notch filter index
192
// @Description: Pitch Error notch filter index
193
// @Range: 1 8
194
// @User: Advanced
195
196
AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Multi, AC_PID),
197
198
// @Param: RAT_YAW_P
199
// @DisplayName: Yaw axis rate controller P gain
200
// @Description: Yaw axis rate controller P gain. Corrects in proportion to the difference between the desired yaw rate vs actual yaw rate
201
// @Range: 0.10 2.50
202
// @Increment: 0.005
203
// @User: Standard
204
205
// @Param: RAT_YAW_I
206
// @DisplayName: Yaw axis rate controller I gain
207
// @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
208
// @Range: 0.010 1.0
209
// @Increment: 0.01
210
// @User: Standard
211
212
// @Param: RAT_YAW_IMAX
213
// @DisplayName: Yaw axis rate controller I gain maximum
214
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum that the I term will output
215
// @Range: 0 1
216
// @Increment: 0.01
217
// @User: Standard
218
219
// @Param: RAT_YAW_D
220
// @DisplayName: Yaw axis rate controller D gain
221
// @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
222
// @Range: 0.000 0.02
223
// @Increment: 0.001
224
// @User: Standard
225
226
// @Param: RAT_YAW_FF
227
// @DisplayName: Yaw axis rate controller feed forward
228
// @Description: Yaw axis rate controller feed forward
229
// @Range: 0 0.5
230
// @Increment: 0.001
231
// @User: Standard
232
233
// @Param: RAT_YAW_FLTT
234
// @DisplayName: Yaw axis rate controller target frequency in Hz
235
// @Description: Yaw axis rate controller target frequency in Hz
236
// @Range: 1 50
237
// @Increment: 1
238
// @Units: Hz
239
// @User: Standard
240
241
// @Param: RAT_YAW_FLTE
242
// @DisplayName: Yaw axis rate controller error frequency in Hz
243
// @Description: Yaw axis rate controller error frequency in Hz
244
// @Range: 0 20
245
// @Increment: 1
246
// @Units: Hz
247
// @User: Standard
248
249
// @Param: RAT_YAW_FLTD
250
// @DisplayName: Yaw axis rate controller derivative frequency in Hz
251
// @Description: Yaw axis rate controller derivative frequency in Hz
252
// @Range: 5 50
253
// @Increment: 1
254
// @Units: Hz
255
// @User: Standard
256
257
// @Param: RAT_YAW_SMAX
258
// @DisplayName: Yaw slew rate limit
259
// @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.
260
// @Range: 0 200
261
// @Increment: 0.5
262
// @User: Advanced
263
264
// @Param: RAT_YAW_PDMX
265
// @DisplayName: Yaw axis rate controller PD sum maximum
266
// @Description: Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
267
// @Range: 0 1
268
// @Increment: 0.01
269
270
// @Param: RAT_YAW_D_FF
271
// @DisplayName: Yaw Derivative FeedForward Gain
272
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
273
// @Range: 0 0.02
274
// @Increment: 0.0001
275
// @User: Advanced
276
277
// @Param: RAT_YAW_NTF
278
// @DisplayName: Yaw Target notch filter index
279
// @Description: Yaw Target notch filter index
280
// @Range: 1 8
281
// @Units: Hz
282
// @User: Advanced
283
284
// @Param: RAT_YAW_NEF
285
// @DisplayName: Yaw Error notch filter index
286
// @Description: Yaw Error notch filter index
287
// @Range: 1 8
288
// @User: Advanced
289
290
AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Multi, AC_PID),
291
292
// @Param: THR_MIX_MIN
293
// @DisplayName: Throttle Mix Minimum
294
// @Description: Throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
295
// @Range: 0.1 0.25
296
// @User: Advanced
297
AP_GROUPINFO("THR_MIX_MIN", 4, AC_AttitudeControl_Multi, _thr_mix_min, AC_ATTITUDE_CONTROL_MIN_DEFAULT),
298
299
// @Param: THR_MIX_MAX
300
// @DisplayName: Throttle Mix Maximum
301
// @Description: Throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)
302
// @Range: 0.5 0.9
303
// @User: Advanced
304
AP_GROUPINFO("THR_MIX_MAX", 5, AC_AttitudeControl_Multi, _thr_mix_max, AC_ATTITUDE_CONTROL_MAX_DEFAULT),
305
306
// @Param: THR_MIX_MAN
307
// @DisplayName: Throttle Mix Manual
308
// @Description: Throttle vs attitude control prioritisation used during manual flight (higher values mean we prioritise attitude control over throttle)
309
// @Range: 0.1 0.9
310
// @User: Advanced
311
AP_GROUPINFO("THR_MIX_MAN", 6, AC_AttitudeControl_Multi, _thr_mix_man, AC_ATTITUDE_CONTROL_MAN_DEFAULT),
312
313
// @Param: THR_G_BOOST
314
// @DisplayName: Throttle-gain boost
315
// @Description: Throttle-gain boost ratio. A value of 0 means no boosting is applied, a value of 1 means full boosting is applied. Describes the ratio increase that is applied to angle P and PD on pitch and roll.
316
// @Range: 0 1
317
// @User: Advanced
318
AP_GROUPINFO("THR_G_BOOST", 7, AC_AttitudeControl_Multi, _throttle_gain_boost, 0.0f),
319
320
AP_GROUPEND
321
};
322
323
AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsMulticopter& motors) :
324
AC_AttitudeControl(ahrs, aparm, motors),
325
_motors_multi(motors)
326
{
327
AP_Param::setup_object_defaults(this, var_info);
328
329
#if AP_FILTER_ENABLED
330
set_notch_sample_rate(AP::scheduler().get_loop_rate_hz());
331
#endif
332
}
333
334
// Update Alt_Hold angle maximum
335
void AC_AttitudeControl_Multi::update_althold_lean_angle_max(float throttle_in)
336
{
337
// calc maximum tilt angle based on throttle
338
float thr_max = _motors_multi.get_throttle_thrust_max();
339
340
// divide by zero check
341
if (is_zero(thr_max)) {
342
_althold_lean_angle_max = 0.0f;
343
return;
344
}
345
346
float althold_lean_angle_max = acosf(constrain_float(throttle_in / (AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX * thr_max), 0.0f, 1.0f));
347
_althold_lean_angle_max = _althold_lean_angle_max + (_dt / (_dt + _angle_limit_tc)) * (althold_lean_angle_max - _althold_lean_angle_max);
348
}
349
350
void AC_AttitudeControl_Multi::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)
351
{
352
_throttle_in = throttle_in;
353
update_althold_lean_angle_max(throttle_in);
354
_motors.set_throttle_filter_cutoff(filter_cutoff);
355
if (apply_angle_boost) {
356
// Apply angle boost
357
throttle_in = get_throttle_boosted(throttle_in);
358
} else {
359
// Clear angle_boost for logging purposes
360
_angle_boost = 0.0f;
361
}
362
_motors.set_throttle(throttle_in);
363
_motors.set_throttle_avg_max(get_throttle_avg_max(MAX(throttle_in, _throttle_in)));
364
}
365
366
void AC_AttitudeControl_Multi::set_throttle_mix_max(float ratio)
367
{
368
ratio = constrain_float(ratio, 0.0f, 1.0f);
369
_throttle_rpy_mix_desired = (1.0f - ratio) * _thr_mix_min + ratio * _thr_mix_max;
370
}
371
372
// returns a throttle including compensation for roll/pitch angle
373
// throttle value should be 0 ~ 1
374
float AC_AttitudeControl_Multi::get_throttle_boosted(float throttle_in)
375
{
376
if (!_angle_boost_enabled) {
377
_angle_boost = 0;
378
return throttle_in;
379
}
380
// inverted_factor is 1 for tilt angles below 60 degrees
381
// inverted_factor reduces from 1 to 0 for tilt angles between 60 and 90 degrees
382
383
float cos_tilt = _ahrs.cos_pitch() * _ahrs.cos_roll();
384
float inverted_factor = constrain_float(10.0f * cos_tilt, 0.0f, 1.0f);
385
float cos_tilt_target = cosf(_thrust_angle);
386
float boost_factor = 1.0f / constrain_float(cos_tilt_target, 0.1f, 1.0f);
387
388
float throttle_out = throttle_in * inverted_factor * boost_factor;
389
_angle_boost = constrain_float(throttle_out - throttle_in, -1.0f, 1.0f);
390
return throttle_out;
391
}
392
393
// returns a throttle including compensation for roll/pitch angle
394
// throttle value should be 0 ~ 1
395
float AC_AttitudeControl_Multi::get_throttle_avg_max(float throttle_in)
396
{
397
throttle_in = constrain_float(throttle_in, 0.0f, 1.0f);
398
return MAX(throttle_in, throttle_in * MAX(0.0f, 1.0f - _throttle_rpy_mix) + _motors.get_throttle_hover() * _throttle_rpy_mix);
399
}
400
401
// update_throttle_gain_boost - boost angle_p/pd each cycle on high throttle slew
402
void AC_AttitudeControl_Multi::update_throttle_gain_boost()
403
{
404
// Boost PD and Angle P on very rapid throttle changes
405
if (_motors.get_throttle_slew_rate() > AC_ATTITUDE_CONTROL_THR_G_BOOST_THRESH) {
406
const float pd_boost = constrain_float(_throttle_gain_boost + 1.0f, 1.0, 2.0);
407
set_PD_scale_mult(Vector3f(pd_boost, pd_boost, 1.0f));
408
409
const float angle_p_boost = constrain_float((_throttle_gain_boost + 1.0f) * (_throttle_gain_boost + 1.0f), 1.0, 4.0);
410
set_angle_P_scale_mult(Vector3f(angle_p_boost, angle_p_boost, 1.0f));
411
}
412
}
413
414
// update_throttle_rpy_mix - slew set_throttle_rpy_mix to requested value
415
void AC_AttitudeControl_Multi::update_throttle_rpy_mix()
416
{
417
// slew _throttle_rpy_mix to _throttle_rpy_mix_desired
418
if (_throttle_rpy_mix < _throttle_rpy_mix_desired) {
419
// increase quickly (i.e. from 0.1 to 0.9 in 0.4 seconds)
420
_throttle_rpy_mix += MIN(2.0f * _dt, _throttle_rpy_mix_desired - _throttle_rpy_mix);
421
} else if (_throttle_rpy_mix > _throttle_rpy_mix_desired) {
422
// reduce more slowly (from 0.9 to 0.1 in 1.6 seconds)
423
_throttle_rpy_mix -= MIN(0.5f * _dt, _throttle_rpy_mix - _throttle_rpy_mix_desired);
424
425
// if the mix is still higher than that being used, reset immediately
426
const float throttle_hover = _motors.get_throttle_hover();
427
const float throttle_in = _motors.get_throttle();
428
const float throttle_out = MAX(_motors.get_throttle_out(), throttle_in);
429
float mix_used;
430
// since throttle_out >= throttle_in at this point we don't need to check throttle_in < throttle_hover
431
if (throttle_out < throttle_hover) {
432
mix_used = (throttle_out - throttle_in) / (throttle_hover - throttle_in);
433
} else {
434
mix_used = throttle_out / throttle_hover;
435
}
436
437
_throttle_rpy_mix = MIN(_throttle_rpy_mix, MAX(mix_used, _throttle_rpy_mix_desired));
438
}
439
_throttle_rpy_mix = constrain_float(_throttle_rpy_mix, 0.1f, AC_ATTITUDE_CONTROL_MAX);
440
}
441
442
void AC_AttitudeControl_Multi::rate_controller_run_dt(const Vector3f& gyro, float dt)
443
{
444
// take a copy of the target so that it can't be changed from under us.
445
Vector3f ang_vel_body = _ang_vel_body;
446
447
// boost angle_p/pd each cycle on high throttle slew
448
update_throttle_gain_boost();
449
450
// move throttle vs attitude mixing towards desired (called from here because this is conveniently called on every iteration)
451
update_throttle_rpy_mix();
452
453
ang_vel_body += _sysid_ang_vel_body;
454
455
_rate_gyro = gyro;
456
_rate_gyro_time_us = AP_HAL::micros64();
457
458
_motors.set_roll(get_rate_roll_pid().update_all(ang_vel_body.x, gyro.x, dt, _motors.limit.roll, _pd_scale.x) + _actuator_sysid.x);
459
_motors.set_roll_ff(get_rate_roll_pid().get_ff());
460
461
_motors.set_pitch(get_rate_pitch_pid().update_all(ang_vel_body.y, gyro.y, dt, _motors.limit.pitch, _pd_scale.y) + _actuator_sysid.y);
462
_motors.set_pitch_ff(get_rate_pitch_pid().get_ff());
463
464
_motors.set_yaw(get_rate_yaw_pid().update_all(ang_vel_body.z, gyro.z, dt, _motors.limit.yaw, _pd_scale.z) + _actuator_sysid.z);
465
_motors.set_yaw_ff(get_rate_yaw_pid().get_ff()*_feedforward_scalar);
466
467
_pd_scale_used = _pd_scale;
468
469
control_monitor_update();
470
}
471
472
// reset the rate controller target loop updates
473
void AC_AttitudeControl_Multi::rate_controller_target_reset()
474
{
475
_sysid_ang_vel_body.zero();
476
_actuator_sysid.zero();
477
_pd_scale = VECTORF_111;
478
}
479
480
// run the rate controller using the configured _dt and latest gyro
481
void AC_AttitudeControl_Multi::rate_controller_run()
482
{
483
Vector3f gyro_latest = _ahrs.get_gyro_latest();
484
rate_controller_run_dt(gyro_latest, _dt);
485
}
486
487
// sanity check parameters. should be called once before takeoff
488
void AC_AttitudeControl_Multi::parameter_sanity_check()
489
{
490
// sanity check throttle mix parameters
491
if (_thr_mix_man < 0.1f || _thr_mix_man > AC_ATTITUDE_CONTROL_MAN_LIMIT) {
492
// parameter description recommends thr-mix-man be no higher than 0.9 but we allow up to 4.0
493
// which can be useful for very high powered copters with very low hover throttle
494
_thr_mix_man.set_and_save(constrain_float(_thr_mix_man, 0.1, AC_ATTITUDE_CONTROL_MAN_LIMIT));
495
}
496
if (_thr_mix_min < 0.1f || _thr_mix_min > AC_ATTITUDE_CONTROL_MIN_LIMIT) {
497
_thr_mix_min.set_and_save(constrain_float(_thr_mix_min, 0.1, AC_ATTITUDE_CONTROL_MIN_LIMIT));
498
}
499
if (_thr_mix_max < 0.5f || _thr_mix_max > AC_ATTITUDE_CONTROL_MAX) {
500
// parameter description recommends thr-mix-max be no higher than 0.9 but we allow up to 5.0
501
// which can be useful for very high powered copters with very low hover throttle
502
_thr_mix_max.set_and_save(constrain_float(_thr_mix_max, 0.5, AC_ATTITUDE_CONTROL_MAX));
503
}
504
if (_thr_mix_min > _thr_mix_max) {
505
_thr_mix_min.set_and_save(AC_ATTITUDE_CONTROL_MIN_DEFAULT);
506
_thr_mix_max.set_and_save(AC_ATTITUDE_CONTROL_MAX_DEFAULT);
507
}
508
}
509
510
void AC_AttitudeControl_Multi::set_notch_sample_rate(float sample_rate)
511
{
512
#if AP_FILTER_ENABLED
513
_pid_rate_roll.set_notch_sample_rate(sample_rate);
514
_pid_rate_pitch.set_notch_sample_rate(sample_rate);
515
_pid_rate_yaw.set_notch_sample_rate(sample_rate);
516
#endif
517
}
518
519