Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
9560 views
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_cd, 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, AP_MotorsHeli& motors) :
310
AC_AttitudeControl(ahrs, 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_norm - 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_norm(float roll_passthrough_norm, float pitch_passthrough_norm, float yaw_passthrough_norm)
325
{
326
// store roll, pitch and passthroughs
327
// NOTE: this abuses yaw_rate_bf_rads
328
_passthrough_roll_norm = roll_passthrough_norm;
329
_passthrough_pitch_norm = pitch_passthrough_norm;
330
_passthrough_yaw_norm = yaw_passthrough_norm;
331
332
// set rate controller to use pass through
333
_flags_heli.flybar_passthrough = true;
334
335
// set bf rate targets to current body frame rates (i.e. relax and be ready for vehicle to switch out of acro)
336
_ang_vel_target_rads.x = _ahrs.get_gyro().x;
337
_ang_vel_target_rads.y = _ahrs.get_gyro().y;
338
339
// accel limit desired yaw rate
340
if (get_accel_yaw_max_radss() > 0.0f) {
341
float rate_change_limit_rads = get_accel_yaw_max_radss() * _dt_s;
342
float rate_change_rads = yaw_passthrough_norm * radians(45.0) - _ang_vel_target_rads.z;
343
rate_change_rads = constrain_float(rate_change_rads, -rate_change_limit_rads, rate_change_limit_rads);
344
_ang_vel_target_rads.z += rate_change_rads;
345
} else {
346
_ang_vel_target_rads.z = yaw_passthrough_norm * radians(45.0);
347
}
348
349
integrate_bf_rate_error_to_angle_errors();
350
_att_error_rot_vec_rad.x = 0;
351
_att_error_rot_vec_rad.y = 0;
352
353
// update our earth-frame angle targets
354
Vector3f att_error_euler_rad;
355
356
// convert angle error rotation vector into 321-intrinsic euler angle difference
357
// NOTE: this results an an approximation linearized about the vehicle's attitude
358
Quaternion att;
359
_ahrs.get_quat_body_to_ned(att);
360
if (body_to_euler_derivative(att, _att_error_rot_vec_rad, att_error_euler_rad)) {
361
_euler_angle_target_rad.x = wrap_PI(att_error_euler_rad.x + _ahrs.roll);
362
_euler_angle_target_rad.y = wrap_PI(att_error_euler_rad.y + _ahrs.pitch);
363
_euler_angle_target_rad.z = wrap_2PI(att_error_euler_rad.z + _ahrs.yaw);
364
}
365
366
// handle flipping over pitch axis
367
if (_euler_angle_target_rad.y > M_PI / 2.0f) {
368
_euler_angle_target_rad.x = wrap_PI(_euler_angle_target_rad.x + M_PI);
369
_euler_angle_target_rad.y = wrap_PI(M_PI - _euler_angle_target_rad.x);
370
_euler_angle_target_rad.z = wrap_2PI(_euler_angle_target_rad.z + M_PI);
371
}
372
if (_euler_angle_target_rad.y < -M_PI / 2.0f) {
373
_euler_angle_target_rad.x = wrap_PI(_euler_angle_target_rad.x + M_PI);
374
_euler_angle_target_rad.y = wrap_PI(-M_PI - _euler_angle_target_rad.x);
375
_euler_angle_target_rad.z = wrap_2PI(_euler_angle_target_rad.z + M_PI);
376
}
377
378
// convert body-frame angle errors to body-frame rate targets
379
_ang_vel_body_rads = update_ang_vel_target_from_att_error(_att_error_rot_vec_rad);
380
381
// set body-frame roll/pitch rate target to current desired rates which are the vehicle's actual rates
382
_ang_vel_body_rads.x = _ang_vel_target_rads.x;
383
_ang_vel_body_rads.y = _ang_vel_target_rads.y;
384
385
// add desired target to yaw
386
_ang_vel_body_rads.z += _ang_vel_target_rads.z;
387
_thrust_error_angle_rad = _att_error_rot_vec_rad.xy().length();
388
}
389
390
void AC_AttitudeControl_Heli::integrate_bf_rate_error_to_angle_errors()
391
{
392
// Integrate the angular velocity error into the attitude error
393
_att_error_rot_vec_rad += (_ang_vel_target_rads - _ahrs.get_gyro()) * _dt_s;
394
395
// Constrain attitude error
396
_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);
397
_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);
398
_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);
399
}
400
401
// Sets desired roll, pitch, and yaw angular rates in body-frame (in radians/s).
402
// This command is used by fully stabilized acro modes.
403
// It applies angular velocity targets in the body frame,
404
// shaped using acceleration limits and passed to the rate controller.
405
// subclass non-passthrough too, for external gyro, no flybar
406
void AC_AttitudeControl_Heli::input_rate_bf_roll_pitch_yaw_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads)
407
{
408
_passthrough_yaw_norm = yaw_rate_bf_rads / radians(45.0);
409
410
AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_rads(roll_rate_bf_rads, pitch_rate_bf_rads, yaw_rate_bf_rads);
411
}
412
413
//
414
// rate controller (body-frame) methods
415
//
416
417
// rate_controller_run - run lowest level rate controller and send outputs to the motors
418
// should be called at 100hz or more
419
void AC_AttitudeControl_Heli::rate_controller_run()
420
{
421
_ang_vel_body_rads += _sysid_ang_vel_body_rads;
422
423
_rate_gyro_rads = _ahrs.get_gyro_latest();
424
_rate_gyro_time_us = AP_HAL::micros64();
425
426
// call rate controllers and send output to motors object
427
// if using a flybar passthrough roll and pitch directly to motors
428
if (_flags_heli.flybar_passthrough) {
429
_motors.set_roll(_passthrough_roll_norm);
430
_motors.set_pitch(_passthrough_pitch_norm);
431
} else {
432
rate_bf_to_motor_roll_pitch(_rate_gyro_rads, _ang_vel_body_rads.x, _ang_vel_body_rads.y);
433
}
434
if (_flags_heli.tail_passthrough) {
435
_motors.set_yaw(_passthrough_yaw_norm);
436
} else {
437
_motors.set_yaw(rate_target_to_motor_yaw(_rate_gyro_rads.z, _ang_vel_body_rads.z));
438
}
439
440
_sysid_ang_vel_body_rads.zero();
441
_actuator_sysid.zero();
442
443
}
444
445
// Update Alt_Hold angle maximum
446
void AC_AttitudeControl_Heli::update_althold_lean_angle_max(float throttle_in)
447
{
448
float althold_lean_angle_max = acosf(constrain_float(throttle_in / AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX, 0.0f, 1.0f));
449
_althold_lean_angle_max_rad = _althold_lean_angle_max_rad + (_dt_s / (_dt_s + _angle_limit_tc)) * (althold_lean_angle_max - _althold_lean_angle_max_rad);
450
}
451
452
//
453
// private methods
454
//
455
456
//
457
// body-frame rate controller
458
//
459
460
// rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target rate in radians/second
461
void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads)
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_s, _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_s, _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_s);
502
yawratevector.y = sinf(-rate_rads.z * _dt_s);
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_s, _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_rad));
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_cd * inverted_factor, -1000.0f,1000.0f);
582
}
583
584
// Sets desired roll and pitch angles (in radians) and yaw rate (in radians/s).
585
// Used when roll/pitch stabilization is needed with manual or autonomous yaw rate control.
586
// Applies acceleration-limited input shaping for smooth transitions and computes body-frame angular velocity targets.
587
void AC_AttitudeControl_Heli::input_euler_angle_roll_pitch_euler_rate_yaw_rad(float euler_roll_angle_rad, float euler_pitch_angle_rad, float euler_yaw_rate_rads)
588
{
589
if (_inverted_flight) {
590
euler_roll_angle_rad = wrap_PI(euler_roll_angle_rad + M_PI);
591
}
592
AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw_rad(euler_roll_angle_rad, euler_pitch_angle_rad, euler_yaw_rate_rads);
593
}
594
595
// Sets desired roll, pitch, and yaw angles (in radians).
596
// Used to follow an absolute attitude setpoint. Input shaping and yaw slew limits are applied.
597
// Outputs are passed to the rate controller via shaped angular velocity targets.
598
void AC_AttitudeControl_Heli::input_euler_angle_roll_pitch_yaw_rad(float euler_roll_angle_rad, float euler_pitch_angle_rad, float euler_yaw_angle_rad, bool slew_yaw)
599
{
600
if (_inverted_flight) {
601
euler_roll_angle_rad = wrap_PI(euler_roll_angle_rad + M_PI);
602
}
603
AC_AttitudeControl::input_euler_angle_roll_pitch_yaw_rad(euler_roll_angle_rad, euler_pitch_angle_rad, euler_yaw_angle_rad, slew_yaw);
604
}
605
606
void AC_AttitudeControl_Heli::set_notch_sample_rate(float sample_rate)
607
{
608
#if AP_FILTER_ENABLED
609
_pid_rate_roll.set_notch_sample_rate(sample_rate);
610
_pid_rate_pitch.set_notch_sample_rate(sample_rate);
611
_pid_rate_yaw.set_notch_sample_rate(sample_rate);
612
#endif
613
}
614
615
// Sets desired thrust vector and heading rate (in radians/s).
616
// Used for tilt-based navigation with independent yaw control.
617
// The thrust vector defines the desired orientation (e.g., pointing direction for vertical thrust),
618
// while the heading rate adjusts yaw. The input is shaped by acceleration and slew limits.
619
void AC_AttitudeControl_Heli::input_thrust_vector_rate_heading_rads(const Vector3f& thrust_vector, float heading_rate_rads, bool slew_yaw)
620
{
621
622
if (!_inverted_flight) {
623
AC_AttitudeControl::input_thrust_vector_rate_heading_rads(thrust_vector, heading_rate_rads, slew_yaw);
624
return;
625
}
626
// convert thrust vector to a roll and pitch angles
627
// this negates the advantage of using thrust vector control, but works just fine
628
Vector3f angle_target = attitude_from_thrust_vector(thrust_vector, _ahrs.yaw).to_vector312();
629
630
angle_target.x = wrap_PI(angle_target.x + M_PI);
631
AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw_rad(angle_target.x, angle_target.y, heading_rate_rads);
632
}
633
634
635
// Sets desired thrust vector and heading (in radians) with heading rate (in radians/s).
636
// Used for advanced attitude control where thrust direction is separated from yaw orientation.
637
// Heading slew is constrained based on configured limits.
638
void AC_AttitudeControl_Heli::input_thrust_vector_heading_rad(const Vector3f& thrust_vector, float heading_angle_rad, float heading_rate_rads)
639
{
640
if (!_inverted_flight) {
641
AC_AttitudeControl::input_thrust_vector_heading_rad(thrust_vector, heading_angle_rad, heading_rate_rads);
642
return;
643
}
644
// convert thrust vector to a roll and pitch angles
645
// this negates the advantage of using thrust vector control, but works just fine
646
Vector3f angle_target = attitude_from_thrust_vector(thrust_vector, _ahrs.yaw).to_vector312();
647
648
angle_target.x = wrap_PI(angle_target.x + M_PI);
649
AC_AttitudeControl::input_euler_angle_roll_pitch_yaw_rad(angle_target.x, angle_target.y, heading_angle_rad, true);
650
}
651
652