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_Heli.cpp
Views: 1798
1
#include "AC_AttitudeControl_Heli.h"
2
#include <AP_HAL/AP_HAL.h>
3
#include <AP_Scheduler/AP_Scheduler.h>
4
5
// table of user settable parameters
6
const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
7
// parameters from parent vehicle
8
AP_NESTEDGROUPINFO(AC_AttitudeControl, 0),
9
10
// @Param: HOVR_ROL_TRM
11
// @DisplayName: Hover Roll Trim
12
// @Description: Trim the hover roll angle to counter tail rotor thrust in a hover
13
// @Units: cdeg
14
// @Increment: 10
15
// @Range: 0 1000
16
// @User: Advanced
17
AP_GROUPINFO("HOVR_ROL_TRM", 1, AC_AttitudeControl_Heli, _hover_roll_trim, AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT),
18
19
// @Param: RAT_RLL_P
20
// @DisplayName: Roll axis rate controller P gain
21
// @Description: Roll axis rate controller P gain. Corrects in proportion to the difference between the desired roll rate vs actual roll rate
22
// @Range: 0.0 0.35
23
// @Increment: 0.005
24
// @User: Standard
25
26
// @Param: RAT_RLL_I
27
// @DisplayName: Roll axis rate controller I gain
28
// @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
29
// @Range: 0.0 0.6
30
// @Increment: 0.01
31
// @User: Standard
32
33
// @Param: RAT_RLL_IMAX
34
// @DisplayName: Roll axis rate controller I gain maximum
35
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum that the I term will output
36
// @Range: 0 1
37
// @Increment: 0.01
38
// @User: Standard
39
40
// @Param: RAT_RLL_ILMI
41
// @DisplayName: Roll axis rate controller I-term leak minimum
42
// @Description: Point below which I-term will not leak down
43
// @Range: 0 1
44
// @User: Advanced
45
46
// @Param: RAT_RLL_D
47
// @DisplayName: Roll axis rate controller D gain
48
// @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
49
// @Range: 0.0 0.03
50
// @Increment: 0.001
51
// @User: Standard
52
53
// @Param: RAT_RLL_FF
54
// @DisplayName: Roll axis rate controller feed forward
55
// @Description: Roll axis rate controller feed forward
56
// @Range: 0.05 0.5
57
// @Increment: 0.001
58
// @User: Standard
59
60
// @Param: RAT_RLL_FLTT
61
// @DisplayName: Roll axis rate controller target frequency in Hz
62
// @Description: Roll axis rate controller target frequency in Hz
63
// @Range: 5 50
64
// @Increment: 1
65
// @Units: Hz
66
// @User: Standard
67
68
// @Param: RAT_RLL_FLTE
69
// @DisplayName: Roll axis rate controller error frequency in Hz
70
// @Description: Roll axis rate controller error frequency in Hz
71
// @Range: 5 50
72
// @Increment: 1
73
// @Units: Hz
74
// @User: Standard
75
76
// @Param: RAT_RLL_FLTD
77
// @DisplayName: Roll axis rate controller derivative frequency in Hz
78
// @Description: Roll axis rate controller derivative frequency in Hz
79
// @Range: 0 50
80
// @Increment: 1
81
// @Units: Hz
82
// @User: Standard
83
84
// @Param: RAT_RLL_SMAX
85
// @DisplayName: Roll slew rate limit
86
// @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.
87
// @Range: 0 200
88
// @Increment: 0.5
89
// @User: Advanced
90
91
// @Param: RAT_RLL_D_FF
92
// @DisplayName: Roll Derivative FeedForward Gain
93
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
94
// @Range: 0 0.02
95
// @Increment: 0.0001
96
// @User: Advanced
97
98
// @Param: RAT_RLL_NTF
99
// @DisplayName: Roll Target notch filter index
100
// @Description: Roll Target notch filter index
101
// @Range: 1 8
102
// @User: Advanced
103
104
// @Param: RAT_RLL_NEF
105
// @DisplayName: Roll Error notch filter index
106
// @Description: Roll Error notch filter index
107
// @Range: 1 8
108
// @User: Advanced
109
110
AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 2, AC_AttitudeControl_Heli, AC_HELI_PID),
111
112
// @Param: RAT_PIT_P
113
// @DisplayName: Pitch axis rate controller P gain
114
// @Description: Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate
115
// @Range: 0.0 0.35
116
// @Increment: 0.005
117
// @User: Standard
118
119
// @Param: RAT_PIT_I
120
// @DisplayName: Pitch axis rate controller I gain
121
// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
122
// @Range: 0.0 0.6
123
// @Increment: 0.01
124
// @User: Standard
125
126
// @Param: RAT_PIT_IMAX
127
// @DisplayName: Pitch axis rate controller I gain maximum
128
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output
129
// @Range: 0 1
130
// @Increment: 0.01
131
// @User: Standard
132
133
// @Param: RAT_PIT_ILMI
134
// @DisplayName: Pitch axis rate controller I-term leak minimum
135
// @Description: Point below which I-term will not leak down
136
// @Range: 0 1
137
// @User: Advanced
138
139
// @Param: RAT_PIT_D
140
// @DisplayName: Pitch axis rate controller D gain
141
// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
142
// @Range: 0.0 0.03
143
// @Increment: 0.001
144
// @User: Standard
145
146
// @Param: RAT_PIT_FF
147
// @DisplayName: Pitch axis rate controller feed forward
148
// @Description: Pitch axis rate controller feed forward
149
// @Range: 0.05 0.5
150
// @Increment: 0.001
151
// @User: Standard
152
153
// @Param: RAT_PIT_FLTT
154
// @DisplayName: Pitch axis rate controller target frequency in Hz
155
// @Description: Pitch axis rate controller target frequency in Hz
156
// @Range: 5 50
157
// @Increment: 1
158
// @Units: Hz
159
// @User: Standard
160
161
// @Param: RAT_PIT_FLTE
162
// @DisplayName: Pitch axis rate controller error frequency in Hz
163
// @Description: Pitch axis rate controller error frequency in Hz
164
// @Range: 5 50
165
// @Increment: 1
166
// @Units: Hz
167
// @User: Standard
168
169
// @Param: RAT_PIT_FLTD
170
// @DisplayName: Pitch axis rate controller derivative frequency in Hz
171
// @Description: Pitch axis rate controller derivative frequency in Hz
172
// @Range: 0 50
173
// @Increment: 1
174
// @Units: Hz
175
// @User: Standard
176
177
// @Param: RAT_PIT_SMAX
178
// @DisplayName: Pitch slew rate limit
179
// @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.
180
// @Range: 0 200
181
// @Increment: 0.5
182
// @User: Advanced
183
184
// @Param: RAT_PIT_D_FF
185
// @DisplayName: Pitch Derivative FeedForward Gain
186
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
187
// @Range: 0 0.02
188
// @Increment: 0.0001
189
// @User: Advanced
190
191
// @Param: RAT_PIT_NTF
192
// @DisplayName: Pitch Target notch filter index
193
// @Description: Pitch Target notch filter index
194
// @Range: 1 8
195
// @User: Advanced
196
197
// @Param: RAT_PIT_NEF
198
// @DisplayName: Pitch Error notch filter index
199
// @Description: Pitch Error notch filter index
200
// @Range: 1 8
201
// @User: Advanced
202
203
AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 3, AC_AttitudeControl_Heli, AC_HELI_PID),
204
205
// @Param: RAT_YAW_P
206
// @DisplayName: Yaw axis rate controller P gain
207
// @Description: Yaw axis rate controller P gain. Corrects in proportion to the difference between the desired yaw rate vs actual yaw rate
208
// @Range: 0.180 0.60
209
// @Increment: 0.005
210
// @User: Standard
211
212
// @Param: RAT_YAW_I
213
// @DisplayName: Yaw axis rate controller I gain
214
// @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
215
// @Range: 0.01 0.2
216
// @Increment: 0.01
217
// @User: Standard
218
219
// @Param: RAT_YAW_IMAX
220
// @DisplayName: Yaw axis rate controller I gain maximum
221
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum that the I term will output
222
// @Range: 0 1
223
// @Increment: 0.01
224
// @User: Standard
225
226
// @Param: RAT_YAW_ILMI
227
// @DisplayName: Yaw axis rate controller I-term leak minimum
228
// @Description: Point below which I-term will not leak down
229
// @Range: 0 1
230
// @User: Advanced
231
232
// @Param: RAT_YAW_D
233
// @DisplayName: Yaw axis rate controller D gain
234
// @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
235
// @Range: 0.000 0.02
236
// @Increment: 0.001
237
// @User: Standard
238
239
// @Param: RAT_YAW_FF
240
// @DisplayName: Yaw axis rate controller feed forward
241
// @Description: Yaw axis rate controller feed forward
242
// @Range: 0 0.5
243
// @Increment: 0.001
244
// @User: Standard
245
246
// @Param: RAT_YAW_FLTT
247
// @DisplayName: Yaw axis rate controller target frequency in Hz
248
// @Description: Yaw axis rate controller target frequency in Hz
249
// @Range: 5 50
250
// @Increment: 1
251
// @Units: Hz
252
// @User: Standard
253
254
// @Param: RAT_YAW_FLTE
255
// @DisplayName: Yaw axis rate controller error frequency in Hz
256
// @Description: Yaw axis rate controller error frequency in Hz
257
// @Range: 5 50
258
// @Increment: 1
259
// @Units: Hz
260
// @User: Standard
261
262
// @Param: RAT_YAW_FLTD
263
// @DisplayName: Yaw axis rate controller derivative frequency in Hz
264
// @Description: Yaw axis rate controller derivative frequency in Hz
265
// @Range: 0 50
266
// @Increment: 1
267
// @Units: Hz
268
// @User: Standard
269
270
// @Param: RAT_YAW_SMAX
271
// @DisplayName: Yaw slew rate limit
272
// @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.
273
// @Range: 0 200
274
// @Increment: 0.5
275
// @User: Advanced
276
277
// @Param: RAT_YAW_D_FF
278
// @DisplayName: Yaw Derivative FeedForward Gain
279
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
280
// @Range: 0 0.02
281
// @Increment: 0.0001
282
// @User: Advanced
283
284
// @Param: RAT_YAW_NTF
285
// @DisplayName: Yaw Target notch filter index
286
// @Description: Yaw Target notch filter index
287
// @Range: 1 8
288
// @Units: Hz
289
// @User: Advanced
290
291
// @Param: RAT_YAW_NEF
292
// @DisplayName: Yaw Error notch filter index
293
// @Description: Yaw Error notch filter index
294
// @Range: 1 8
295
// @User: Advanced
296
297
AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 4, AC_AttitudeControl_Heli, AC_HELI_PID),
298
299
// @Param: PIRO_COMP
300
// @DisplayName: Piro Comp Enable
301
// @Description: Pirouette compensation enabled
302
// @Values: 0:Disabled,1:Enabled
303
// @User: Advanced
304
AP_GROUPINFO("PIRO_COMP", 5, AC_AttitudeControl_Heli, _piro_comp_enabled, 0),
305
306
AP_GROUPEND
307
};
308
309
AC_AttitudeControl_Heli::AC_AttitudeControl_Heli(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsHeli& motors) :
310
AC_AttitudeControl(ahrs, aparm, motors)
311
{
312
AP_Param::setup_object_defaults(this, var_info);
313
314
// initialise flags
315
_flags_heli.leaky_i = true;
316
_flags_heli.flybar_passthrough = false;
317
_flags_heli.tail_passthrough = false;
318
#if AP_FILTER_ENABLED
319
set_notch_sample_rate(AP::scheduler().get_loop_rate_hz());
320
#endif
321
}
322
323
// passthrough_bf_roll_pitch_rate_yaw - passthrough the pilots roll and pitch inputs directly to swashplate for flybar acro mode
324
void AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds)
325
{
326
// convert from centidegrees on public interface to radians
327
float yaw_rate_bf_rads = radians(yaw_rate_bf_cds * 0.01f);
328
329
// store roll, pitch and passthroughs
330
// NOTE: this abuses yaw_rate_bf_rads
331
_passthrough_roll = roll_passthrough;
332
_passthrough_pitch = pitch_passthrough;
333
_passthrough_yaw = degrees(yaw_rate_bf_rads) * 100.0f;
334
335
// set rate controller to use pass through
336
_flags_heli.flybar_passthrough = true;
337
338
// set bf rate targets to current body frame rates (i.e. relax and be ready for vehicle to switch out of acro)
339
_ang_vel_target.x = _ahrs.get_gyro().x;
340
_ang_vel_target.y = _ahrs.get_gyro().y;
341
342
// accel limit desired yaw rate
343
if (get_accel_yaw_max_radss() > 0.0f) {
344
float rate_change_limit_rads = get_accel_yaw_max_radss() * _dt;
345
float rate_change_rads = yaw_rate_bf_rads - _ang_vel_target.z;
346
rate_change_rads = constrain_float(rate_change_rads, -rate_change_limit_rads, rate_change_limit_rads);
347
_ang_vel_target.z += rate_change_rads;
348
} else {
349
_ang_vel_target.z = yaw_rate_bf_rads;
350
}
351
352
integrate_bf_rate_error_to_angle_errors();
353
_att_error_rot_vec_rad.x = 0;
354
_att_error_rot_vec_rad.y = 0;
355
356
// update our earth-frame angle targets
357
Vector3f att_error_euler_rad;
358
359
// convert angle error rotation vector into 321-intrinsic euler angle difference
360
// NOTE: this results an an approximation linearized about the vehicle's attitude
361
Quaternion att;
362
_ahrs.get_quat_body_to_ned(att);
363
if (ang_vel_to_euler_rate(att, _att_error_rot_vec_rad, att_error_euler_rad)) {
364
_euler_angle_target.x = wrap_PI(att_error_euler_rad.x + _ahrs.roll);
365
_euler_angle_target.y = wrap_PI(att_error_euler_rad.y + _ahrs.pitch);
366
_euler_angle_target.z = wrap_2PI(att_error_euler_rad.z + _ahrs.yaw);
367
}
368
369
// handle flipping over pitch axis
370
if (_euler_angle_target.y > M_PI / 2.0f) {
371
_euler_angle_target.x = wrap_PI(_euler_angle_target.x + M_PI);
372
_euler_angle_target.y = wrap_PI(M_PI - _euler_angle_target.x);
373
_euler_angle_target.z = wrap_2PI(_euler_angle_target.z + M_PI);
374
}
375
if (_euler_angle_target.y < -M_PI / 2.0f) {
376
_euler_angle_target.x = wrap_PI(_euler_angle_target.x + M_PI);
377
_euler_angle_target.y = wrap_PI(-M_PI - _euler_angle_target.x);
378
_euler_angle_target.z = wrap_2PI(_euler_angle_target.z + M_PI);
379
}
380
381
// convert body-frame angle errors to body-frame rate targets
382
_ang_vel_body = update_ang_vel_target_from_att_error(_att_error_rot_vec_rad);
383
384
// set body-frame roll/pitch rate target to current desired rates which are the vehicle's actual rates
385
_ang_vel_body.x = _ang_vel_target.x;
386
_ang_vel_body.y = _ang_vel_target.y;
387
388
// add desired target to yaw
389
_ang_vel_body.z += _ang_vel_target.z;
390
_thrust_error_angle = _att_error_rot_vec_rad.xy().length();
391
}
392
393
void AC_AttitudeControl_Heli::integrate_bf_rate_error_to_angle_errors()
394
{
395
// Integrate the angular velocity error into the attitude error
396
_att_error_rot_vec_rad += (_ang_vel_target - _ahrs.get_gyro()) * _dt;
397
398
// Constrain attitude error
399
_att_error_rot_vec_rad.x = constrain_float(_att_error_rot_vec_rad.x, -AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD, AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD);
400
_att_error_rot_vec_rad.y = constrain_float(_att_error_rot_vec_rad.y, -AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD, AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD);
401
_att_error_rot_vec_rad.z = constrain_float(_att_error_rot_vec_rad.z, -AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD, AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD);
402
}
403
404
// subclass non-passthrough too, for external gyro, no flybar
405
void AC_AttitudeControl_Heli::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
406
{
407
_passthrough_yaw = yaw_rate_bf_cds;
408
409
AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(roll_rate_bf_cds, pitch_rate_bf_cds, yaw_rate_bf_cds);
410
}
411
412
//
413
// rate controller (body-frame) methods
414
//
415
416
// rate_controller_run - run lowest level rate controller and send outputs to the motors
417
// should be called at 100hz or more
418
void AC_AttitudeControl_Heli::rate_controller_run()
419
{
420
_ang_vel_body += _sysid_ang_vel_body;
421
422
_rate_gyro = _ahrs.get_gyro_latest();
423
_rate_gyro_time_us = AP_HAL::micros64();
424
425
// call rate controllers and send output to motors object
426
// if using a flybar passthrough roll and pitch directly to motors
427
if (_flags_heli.flybar_passthrough) {
428
_motors.set_roll(_passthrough_roll / 4500.0f);
429
_motors.set_pitch(_passthrough_pitch / 4500.0f);
430
} else {
431
rate_bf_to_motor_roll_pitch(_rate_gyro, _ang_vel_body.x, _ang_vel_body.y);
432
}
433
if (_flags_heli.tail_passthrough) {
434
_motors.set_yaw(_passthrough_yaw / 4500.0f);
435
} else {
436
_motors.set_yaw(rate_target_to_motor_yaw(_rate_gyro.z, _ang_vel_body.z));
437
}
438
439
_sysid_ang_vel_body.zero();
440
_actuator_sysid.zero();
441
442
}
443
444
// Update Alt_Hold angle maximum
445
void AC_AttitudeControl_Heli::update_althold_lean_angle_max(float throttle_in)
446
{
447
float althold_lean_angle_max = acosf(constrain_float(throttle_in / AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX, 0.0f, 1.0f));
448
_althold_lean_angle_max = _althold_lean_angle_max + (_dt / (_dt + _angle_limit_tc)) * (althold_lean_angle_max - _althold_lean_angle_max);
449
}
450
451
//
452
// private methods
453
//
454
455
//
456
// body-frame rate controller
457
//
458
459
// rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target rate in radians/second
460
void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads)
461
{
462
463
if (_flags_heli.leaky_i) {
464
_pid_rate_roll.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);
465
}
466
float roll_pid = _pid_rate_roll.update_all(rate_roll_target_rads, rate_rads.x, _dt, _motors.limit.roll) + _actuator_sysid.x;
467
468
if (_flags_heli.leaky_i) {
469
_pid_rate_pitch.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);
470
}
471
472
float pitch_pid = _pid_rate_pitch.update_all(rate_pitch_target_rads, rate_rads.y, _dt, _motors.limit.pitch) + _actuator_sysid.y;
473
474
// use pid library to calculate ff
475
float roll_ff = _pid_rate_roll.get_ff();
476
float pitch_ff = _pid_rate_pitch.get_ff();
477
478
// add feed forward and final output
479
float roll_out = roll_pid + roll_ff;
480
float pitch_out = pitch_pid + pitch_ff;
481
482
// constrain output
483
roll_out = constrain_float(roll_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX);
484
pitch_out = constrain_float(pitch_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX);
485
486
// output to motors
487
_motors.set_roll(roll_out);
488
_motors.set_pitch(pitch_out);
489
490
// Piro-Comp, or Pirouette Compensation is a pre-compensation calculation, which basically rotates the Roll and Pitch Rate I-terms as the
491
// helicopter rotates in yaw. Much of the built-up I-term is needed to tip the disk into the incoming wind. Fast yawing can create an instability
492
// as the built-up I-term in one axis must be reduced, while the other increases. This helps solve that by rotating the I-terms before the error occurs.
493
// It does assume that the rotor aerodynamics and mechanics are essentially symmetrical about the main shaft, which is a generally valid assumption.
494
if (_piro_comp_enabled) {
495
496
// used to hold current I-terms while doing piro comp:
497
const float piro_roll_i = _pid_rate_roll.get_i();
498
const float piro_pitch_i = _pid_rate_pitch.get_i();
499
500
Vector2f yawratevector;
501
yawratevector.x = cosf(-rate_rads.z * _dt);
502
yawratevector.y = sinf(-rate_rads.z * _dt);
503
yawratevector.normalize();
504
505
_pid_rate_roll.set_integrator(piro_roll_i * yawratevector.x - piro_pitch_i * yawratevector.y);
506
_pid_rate_pitch.set_integrator(piro_pitch_i * yawratevector.x + piro_roll_i * yawratevector.y);
507
}
508
509
}
510
511
// rate_bf_to_motor_yaw - ask the rate controller to calculate the motor outputs to achieve the target rate in radians/second
512
float AC_AttitudeControl_Heli::rate_target_to_motor_yaw(float rate_yaw_actual_rads, float rate_target_rads)
513
{
514
if (!((AP_MotorsHeli&)_motors).rotor_runup_complete()) {
515
_pid_rate_yaw.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);
516
}
517
518
float pid = _pid_rate_yaw.update_all(rate_target_rads, rate_yaw_actual_rads, _dt, _motors.limit.yaw) + _actuator_sysid.z;
519
520
// use pid library to calculate ff
521
float vff = _pid_rate_yaw.get_ff()*_feedforward_scalar;
522
523
// add feed forward
524
float yaw_out = pid + vff;
525
526
// constrain output
527
yaw_out = constrain_float(yaw_out, -AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX);
528
529
// output to motors
530
return yaw_out;
531
}
532
533
//
534
// throttle functions
535
//
536
537
void AC_AttitudeControl_Heli::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)
538
{
539
_throttle_in = throttle_in;
540
update_althold_lean_angle_max(throttle_in);
541
542
_motors.set_throttle_filter_cutoff(filter_cutoff);
543
if (apply_angle_boost && !((AP_MotorsHeli&)_motors).in_autorotation()) {
544
// Apply angle boost
545
throttle_in = get_throttle_boosted(throttle_in);
546
} else {
547
// Clear angle_boost for logging purposes
548
_angle_boost = 0.0f;
549
}
550
_motors.set_throttle(throttle_in);
551
}
552
553
// returns a throttle including compensation for roll/pitch angle
554
// throttle value should be 0 ~ 1
555
float AC_AttitudeControl_Heli::get_throttle_boosted(float throttle_in)
556
{
557
if (!_angle_boost_enabled) {
558
_angle_boost = 0;
559
return throttle_in;
560
}
561
// inverted_factor is 1 for tilt angles below 60 degrees
562
// inverted_factor changes from 1 to -1 for tilt angles between 60 and 120 degrees
563
564
float cos_tilt = _ahrs.cos_pitch() * _ahrs.cos_roll();
565
float inverted_factor = constrain_float(2.0f * cos_tilt, -1.0f, 1.0f);
566
float cos_tilt_target = fabsf(cosf(_thrust_angle));
567
float boost_factor = 1.0f / constrain_float(cos_tilt_target, 0.1f, 1.0f);
568
569
// angle boost and inverted factor applied about the zero thrust collective
570
const float coll_mid = ((AP_MotorsHeli&)_motors).get_coll_mid();
571
float throttle_out = ((throttle_in - coll_mid) * inverted_factor * boost_factor) + coll_mid;
572
_angle_boost = constrain_float(throttle_out - throttle_in, -1.0f, 1.0f);
573
return throttle_out;
574
}
575
576
// get_roll_trim - angle in centi-degrees to be added to roll angle for learn hover collective. Used by helicopter to counter tail rotor thrust in hover
577
float AC_AttitudeControl_Heli::get_roll_trim_cd()
578
{
579
// hover roll trim is given the opposite sign in inverted flight since the tail rotor thrust is pointed in the opposite direction.
580
float inverted_factor = constrain_float(2.0f * _ahrs.cos_roll(), -1.0f, 1.0f);
581
return constrain_float(_hover_roll_trim_scalar * _hover_roll_trim * inverted_factor, -1000.0f,1000.0f);
582
}
583
584
// Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
585
void AC_AttitudeControl_Heli::input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)
586
{
587
if (_inverted_flight) {
588
euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);
589
}
590
AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_rate_cds);
591
}
592
593
// Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
594
void AC_AttitudeControl_Heli::input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)
595
{
596
if (_inverted_flight) {
597
euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);
598
}
599
AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_angle_cd, slew_yaw);
600
}
601
602
void AC_AttitudeControl_Heli::set_notch_sample_rate(float sample_rate)
603
{
604
#if AP_FILTER_ENABLED
605
_pid_rate_roll.set_notch_sample_rate(sample_rate);
606
_pid_rate_pitch.set_notch_sample_rate(sample_rate);
607
_pid_rate_yaw.set_notch_sample_rate(sample_rate);
608
#endif
609
}
610
611
// Command a thrust vector and heading rate
612
void AC_AttitudeControl_Heli::input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds, bool slew_yaw)
613
{
614
615
if (!_inverted_flight) {
616
AC_AttitudeControl::input_thrust_vector_rate_heading(thrust_vector, heading_rate_cds, slew_yaw);
617
return;
618
}
619
// convert thrust vector to a roll and pitch angles
620
// this negates the advantage of using thrust vector control, but works just fine
621
Vector3f angle_target = attitude_from_thrust_vector(thrust_vector, _ahrs.yaw).to_vector312();
622
623
float euler_roll_angle_cd = degrees(angle_target.x) * 100.0f;
624
euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);
625
AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(euler_roll_angle_cd, degrees(angle_target.y) * 100.0f, heading_rate_cds);
626
}
627
628
// Command a thrust vector, heading and heading rate
629
void AC_AttitudeControl_Heli::input_thrust_vector_heading(const Vector3f& thrust_vector, float heading_angle_cd, float heading_rate_cds)
630
{
631
if (!_inverted_flight) {
632
AC_AttitudeControl::input_thrust_vector_heading(thrust_vector, heading_angle_cd, heading_rate_cds);
633
return;
634
}
635
// convert thrust vector to a roll and pitch angles
636
Vector3f angle_target = attitude_from_thrust_vector(thrust_vector, _ahrs.yaw).to_vector312();
637
638
float euler_roll_angle_cd = degrees(angle_target.x) * 100.0f;
639
euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);
640
// note that we are throwing away heading rate here
641
AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, degrees(angle_target.y) * 100.0f, heading_angle_cd, true);
642
}
643
644