APM:Libraries
AC_AttitudeControl_Heli.cpp
Go to the documentation of this file.
2 #include <AP_HAL/AP_HAL.h>
3 
4 // table of user settable parameters
6  // parameters from parent vehicle
8 
9  // @Param: HOVR_ROL_TRM
10  // @DisplayName: Hover Roll Trim
11  // @Description: Trim the hover roll angle to counter tail rotor thrust in a hover
12  // @Units: cdeg
13  // @Range: 0 1000
14  // @User: Advanced
16 
17  // @Param: RAT_RLL_P
18  // @DisplayName: Roll axis rate controller P gain
19  // @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output
20  // @Range: 0.08 0.35
21  // @Increment: 0.005
22  // @User: Standard
23 
24  // @Param: RAT_RLL_I
25  // @DisplayName: Roll axis rate controller I gain
26  // @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
27  // @Range: 0.01 0.6
28  // @Increment: 0.01
29  // @User: Standard
30 
31  // @Param: RAT_RLL_IMAX
32  // @DisplayName: Roll axis rate controller I gain maximum
33  // @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
34  // @Range: 0 1
35  // @Increment: 0.01
36  // @User: Standard
37 
38  // @Param: RAT_RLL_D
39  // @DisplayName: Roll axis rate controller D gain
40  // @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
41  // @Range: 0.001 0.03
42  // @Increment: 0.001
43  // @User: Standard
44 
45  // @Param: RAT_RLL_FF
46  // @DisplayName: Roll axis rate controller feed forward
47  // @Description: Roll axis rate controller feed forward
48  // @Range: 0 0.5
49  // @Increment: 0.001
50  // @User: Standard
51 
52  // @Param: RAT_RLL_FILT
53  // @DisplayName: Roll axis rate controller input frequency in Hz
54  // @Description: Roll axis rate controller input frequency in Hz
55  // @Units: Hz
56  // @Range: 1 20
57  // @Increment: 1
58  AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 2, AC_AttitudeControl_Heli, AC_HELI_PID),
59 
60  // @Param: RAT_PIT_P
61  // @DisplayName: Pitch axis rate controller P gain
62  // @Description: Pitch axis rate controller P gain. Converts the difference between desired pitch rate and actual pitch rate into a motor speed output
63  // @Range: 0.08 0.35
64  // @Increment: 0.005
65  // @User: Standard
66 
67  // @Param: RAT_PIT_I
68  // @DisplayName: Pitch axis rate controller I gain
69  // @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
70  // @Range: 0.01 0.6
71  // @Increment: 0.01
72  // @User: Standard
73 
74  // @Param: RAT_PIT_IMAX
75  // @DisplayName: Pitch axis rate controller I gain maximum
76  // @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
77  // @Range: 0 1
78  // @Increment: 0.01
79  // @User: Standard
80 
81  // @Param: RAT_PIT_D
82  // @DisplayName: Pitch axis rate controller D gain
83  // @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
84  // @Range: 0.001 0.03
85  // @Increment: 0.001
86  // @User: Standard
87 
88  // @Param: RAT_PIT_FF
89  // @DisplayName: Pitch axis rate controller feed forward
90  // @Description: Pitch axis rate controller feed forward
91  // @Range: 0 0.5
92  // @Increment: 0.001
93  // @User: Standard
94 
95  // @Param: RAT_PIT_FILT
96  // @DisplayName: Pitch axis rate controller input frequency in Hz
97  // @Description: Pitch axis rate controller input frequency in Hz
98  // @Units: Hz
99  // @Range: 1 20
100  // @Increment: 1
101  AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 3, AC_AttitudeControl_Heli, AC_HELI_PID),
102 
103  // @Param: RAT_YAW_P
104  // @DisplayName: Yaw axis rate controller P gain
105  // @Description: Yaw axis rate controller P gain. Converts the difference between desired yaw rate and actual yaw rate into a motor speed output
106  // @Range: 0.180 0.60
107  // @Increment: 0.005
108  // @User: Standard
109 
110  // @Param: RAT_YAW_I
111  // @DisplayName: Yaw axis rate controller I gain
112  // @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
113  // @Range: 0.01 0.06
114  // @Increment: 0.01
115  // @User: Standard
116 
117  // @Param: RAT_YAW_IMAX
118  // @DisplayName: Yaw axis rate controller I gain maximum
119  // @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
120  // @Range: 0 1
121  // @Increment: 0.01
122  // @User: Standard
123 
124  // @Param: RAT_YAW_D
125  // @DisplayName: Yaw axis rate controller D gain
126  // @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
127  // @Range: 0.000 0.02
128  // @Increment: 0.001
129  // @User: Standard
130 
131  // @Param: RAT_YAW_FF
132  // @DisplayName: Yaw axis rate controller feed forward
133  // @Description: Yaw axis rate controller feed forward
134  // @Range: 0 0.5
135  // @Increment: 0.001
136  // @User: Standard
137 
138  // @Param: RAT_YAW_FILT
139  // @DisplayName: Yaw axis rate controller input frequency in Hz
140  // @Description: Yaw axis rate controller input frequency in Hz
141  // @Units: Hz
142  // @Range: 1 20
143  // @Increment: 1
144  AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 4, AC_AttitudeControl_Heli, AC_HELI_PID),
145 
146  // @Param: PIRO_COMP
147  // @DisplayName: Piro Comp Enable
148  // @Description: Pirouette compensation enabled
149  // @Values: 0:Disabled,1:Enabled
150  // @User: Advanced
151  AP_GROUPINFO("PIRO_COMP", 5, AC_AttitudeControl_Heli, _piro_comp_enabled, 0),
152 
154 };
155 
156 // passthrough_bf_roll_pitch_rate_yaw - passthrough the pilots roll and pitch inputs directly to swashplate for flybar acro mode
157 void AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds)
158 {
159  // convert from centidegrees on public interface to radians
160  float yaw_rate_bf_rads = radians(yaw_rate_bf_cds*0.01f);
161 
162  // store roll, pitch and passthroughs
163  // NOTE: this abuses yaw_rate_bf_rads
164  _passthrough_roll = roll_passthrough;
165  _passthrough_pitch = pitch_passthrough;
166  _passthrough_yaw = degrees(yaw_rate_bf_rads)*100.0f;
167 
168  // set rate controller to use pass through
170 
171  // set bf rate targets to current body frame rates (i.e. relax and be ready for vehicle to switch out of acro)
174 
175  // accel limit desired yaw rate
176  if (get_accel_yaw_max_radss() > 0.0f) {
177  float rate_change_limit_rads = get_accel_yaw_max_radss() * _dt;
178  float rate_change_rads = yaw_rate_bf_rads - _attitude_target_ang_vel.z;
179  rate_change_rads = constrain_float(rate_change_rads, -rate_change_limit_rads, rate_change_limit_rads);
180  _attitude_target_ang_vel.z += rate_change_rads;
181  } else {
182  _attitude_target_ang_vel.z = yaw_rate_bf_rads;
183  }
184 
188 
189  // update our earth-frame angle targets
190  Vector3f att_error_euler_rad;
191 
192  // convert angle error rotation vector into 321-intrinsic euler angle difference
193  // NOTE: this results an an approximation linearized about the vehicle's attitude
195  _attitude_target_euler_angle.x = wrap_PI(att_error_euler_rad.x + _ahrs.roll);
196  _attitude_target_euler_angle.y = wrap_PI(att_error_euler_rad.y + _ahrs.pitch);
197  _attitude_target_euler_angle.z = wrap_2PI(att_error_euler_rad.z + _ahrs.yaw);
198  }
199 
200  // handle flipping over pitch axis
201  if (_attitude_target_euler_angle.y > M_PI/2.0f) {
205  }
206  if (_attitude_target_euler_angle.y < -M_PI/2.0f) {
210  }
211 
212  // convert body-frame angle errors to body-frame rate targets
214 
215  // set body-frame roll/pitch rate target to current desired rates which are the vehicle's actual rates
218 
219  // add desired target to yaw
222 }
223 
225 {
226  // Integrate the angular velocity error into the attitude error
228 
229  // Constrain attitude error
233 }
234 
235 // subclass non-passthrough too, for external gyro, no flybar
236 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)
237 {
238  _passthrough_yaw = yaw_rate_bf_cds;
239 
240  AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(roll_rate_bf_cds, pitch_rate_bf_cds, yaw_rate_bf_cds);
241 }
242 
243 //
244 // rate controller (body-frame) methods
245 //
246 
247 // rate_controller_run - run lowest level rate controller and send outputs to the motors
248 // should be called at 100hz or more
250 {
251  Vector3f gyro_latest = _ahrs.get_gyro_latest();
252 
253  // call rate controllers and send output to motors object
254  // if using a flybar passthrough roll and pitch directly to motors
258  } else {
260  }
263  } else {
265  }
266 }
267 
268 // Update Alt_Hold angle maximum
270 {
271  float althold_lean_angle_max = acosf(constrain_float(_throttle_in/AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX, 0.0f, 1.0f));
273 }
274 
275 //
276 // private methods
277 //
278 
279 //
280 // body-frame rate controller
281 //
282 
283 // rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target rate in radians/second
284 void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads)
285 {
286  float roll_pd, roll_i, roll_ff; // used to capture pid values
287  float pitch_pd, pitch_i, pitch_ff; // used to capture pid values
288  float rate_roll_error_rads, rate_pitch_error_rads; // simply target_rate - current_rate
289  float roll_out, pitch_out;
290 
291  // calculate error
292  rate_roll_error_rads = rate_roll_target_rads - rate_rads.x;
293  rate_pitch_error_rads = rate_pitch_target_rads - rate_rads.y;
294 
295  // pass error to PID controller
296  _pid_rate_roll.set_input_filter_all(rate_roll_error_rads);
297  _pid_rate_roll.set_desired_rate(rate_roll_target_rads);
298  _pid_rate_pitch.set_input_filter_all(rate_pitch_error_rads);
299  _pid_rate_pitch.set_desired_rate(rate_pitch_target_rads);
300 
301  // call p and d controllers
302  roll_pd = _pid_rate_roll.get_p() + _pid_rate_roll.get_d();
303  pitch_pd = _pid_rate_pitch.get_p() + _pid_rate_pitch.get_d();
304 
305  // get roll i term
306  roll_i = _pid_rate_roll.get_integrator();
307 
308  // update i term as long as we haven't breached the limits or the I term will certainly reduce
309  if (!_flags_heli.limit_roll || ((roll_i>0&&rate_roll_error_rads<0)||(roll_i<0&&rate_roll_error_rads>0))){
310  if (_flags_heli.leaky_i){
312  }else{
313  roll_i = _pid_rate_roll.get_i();
314  }
315  }
316 
317  // get pitch i term
318  pitch_i = _pid_rate_pitch.get_integrator();
319 
320  // update i term as long as we haven't breached the limits or the I term will certainly reduce
321  if (!_flags_heli.limit_pitch || ((pitch_i>0&&rate_pitch_error_rads<0)||(pitch_i<0&&rate_pitch_error_rads>0))){
322  if (_flags_heli.leaky_i) {
324  }else{
325  pitch_i = _pid_rate_pitch.get_i();
326  }
327  }
328 
329  // For legacy reasons, we convert to centi-degrees before inputting to the feedforward
330  roll_ff = roll_feedforward_filter.apply(_pid_rate_roll.get_ff(rate_roll_target_rads), _dt);
331  pitch_ff = pitch_feedforward_filter.apply(_pid_rate_pitch.get_ff(rate_pitch_target_rads), _dt);
332 
333  // add feed forward and final output
334  roll_out = roll_pd + roll_i + roll_ff;
335  pitch_out = pitch_pd + pitch_i + pitch_ff;
336 
337  // constrain output and update limit flags
338  if (fabsf(roll_out) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX) {
340  _flags_heli.limit_roll = true;
341  }else{
342  _flags_heli.limit_roll = false;
343  }
344  if (fabsf(pitch_out) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX) {
346  _flags_heli.limit_pitch = true;
347  }else{
348  _flags_heli.limit_pitch = false;
349  }
350 
351  // output to motors
352  _motors.set_roll(roll_out);
353  _motors.set_pitch(pitch_out);
354 
355  // Piro-Comp, or Pirouette Compensation is a pre-compensation calculation, which basically rotates the Roll and Pitch Rate I-terms as the
356  // 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
357  // 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.
358  // It does assume that the rotor aerodynamics and mechanics are essentially symmetrical about the main shaft, which is a generally valid assumption.
359  if (_piro_comp_enabled){
360 
361  int32_t piro_roll_i, piro_pitch_i; // used to hold I-terms while doing piro comp
362 
363  piro_roll_i = roll_i;
364  piro_pitch_i = pitch_i;
365 
366  Vector2f yawratevector;
367  yawratevector.x = cosf(-rate_rads.z * _dt);
368  yawratevector.y = sinf(-rate_rads.z * _dt);
369  yawratevector.normalize();
370 
371  roll_i = piro_roll_i * yawratevector.x - piro_pitch_i * yawratevector.y;
372  pitch_i = piro_pitch_i * yawratevector.x + piro_roll_i * yawratevector.y;
373 
376  }
377 
378 }
379 
380 // rate_bf_to_motor_yaw - ask the rate controller to calculate the motor outputs to achieve the target rate in radians/second
381 float AC_AttitudeControl_Heli::rate_target_to_motor_yaw(float rate_yaw_actual_rads, float rate_target_rads)
382 {
383  float pd,i,vff; // used to capture pid values for logging
384  float rate_error_rads; // simply target_rate - current_rate
385  float yaw_out;
386 
387  // calculate error and call pid controller
388  rate_error_rads = rate_target_rads - rate_yaw_actual_rads;
389 
390  // pass error to PID controller
391  _pid_rate_yaw.set_input_filter_all(rate_error_rads);
392  _pid_rate_yaw.set_desired_rate(rate_target_rads);
393 
394  // get p and d
396 
397  // get i term
399 
400  // update i term as long as we haven't breached the limits or the I term will certainly reduce
401  if (!_flags_heli.limit_yaw || ((i>0&&rate_error_rads<0)||(i<0&&rate_error_rads>0))) {
402  if (((AP_MotorsHeli&)_motors).rotor_runup_complete()) {
403  i = _pid_rate_yaw.get_i();
404  } else {
405  i = ((AC_HELI_PID&)_pid_rate_yaw).get_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE); // If motor is not running use leaky I-term to avoid excessive build-up
406  }
407  }
408 
409  // For legacy reasons, we convert to centi-degrees before inputting to the feedforward
411 
412  // add feed forward
413  yaw_out = pd + i + vff;
414 
415  // constrain output and update limit flag
416  if (fabsf(yaw_out) > AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX) {
418  _flags_heli.limit_yaw = true;
419  }else{
420  _flags_heli.limit_yaw = false;
421  }
422 
423  // output to motors
424  return yaw_out;
425 }
426 
427 //
428 // throttle functions
429 //
430 
431 void AC_AttitudeControl_Heli::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)
432 {
433  _throttle_in = throttle_in;
434  update_althold_lean_angle_max(throttle_in);
435  _motors.set_throttle_filter_cutoff(filter_cutoff);
436  _motors.set_throttle(throttle_in);
437  // Clear angle_boost for logging purposes
438  _angle_boost = 0.0f;
439 }
440 
441 // Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
442 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)
443 {
444  if (_inverted_flight) {
445  euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);
446  }
447  AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_rate_cds);
448 }
449 
450 // Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
451 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)
452 {
453  if (_inverted_flight) {
454  euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);
455  }
456  AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_angle_cd, slew_yaw);
457 }
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
Vector3< float > Vector3f
Definition: vector3.h:246
void set_throttle_filter_cutoff(float filt_hz)
struct AC_AttitudeControl_Heli::AttControlHeliFlags _flags_heli
float rate_target_to_motor_yaw(float rate_yaw_actual_rads, float rate_yaw_rads) override
void set_yaw(float yaw_in)
#define AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX
void input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds) override
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
bool ang_vel_to_euler_rate(const Vector3f &euler_rad, const Vector3f &ang_vel_rads, Vector3f &euler_rate_rads)
virtual void input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)
void update_althold_lean_angle_max(float throttle_in) override
float get_d()
Definition: AC_PID.cpp:155
Vector3f get_gyro_latest(void) const
float get_leaky_i(float leak_rate)
get_leaky_i - replacement for get_i but output is leaded at leak_rate
Definition: AC_HELI_PID.cpp:60
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
Definition: AP_Math.cpp:111
void input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw) override
static const struct AP_Param::GroupInfo var_info[]
#define AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD
void set_integrator(float i)
Definition: AC_PID.h:77
Vector3f update_ang_vel_target_from_att_error(Vector3f attitude_error_rot_vec_rad)
const Vector3f & get_gyro(void) const
Definition: AP_AHRS_View.h:38
T y
Definition: vector2.h:37
Heli PID control class.
Definition: AC_HELI_PID.h:16
LowPassFilterFloat yaw_velocity_feedforward_filter
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
ArduCopter attitude control library for traditional helicopters.
#define f(i)
#define AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT
T y
Definition: vector3.h:67
T z
Definition: vector3.h:67
void rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads)
#define AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE
float get_ff(float requested_rate)
Definition: AC_PID.cpp:162
#define AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX
void set_throttle(float throttle_in)
void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override
virtual void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
void passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds) override
void set_desired_rate(float desired)
Definition: AC_PID.h:80
Vector3f _attitude_target_euler_angle
virtual void input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
float wrap_2PI(const T radian)
Definition: AP_Math.cpp:167
#define AP_NESTEDGROUPINFO(clazz, idx)
Definition: AP_Param.h:105
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void normalize()
Definition: vector2.h:140
void set_input_filter_all(float input)
Definition: AC_PID.cpp:87
void set_pitch(float pitch_in)
void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) override
LowPassFilterFloat pitch_feedforward_filter
#define AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX
void set_roll(float roll_in)
float get_integrator() const
Definition: AC_PID.h:76
float get_i()
Definition: AC_PID.cpp:140
#define degrees(x)
Definition: moduletest.c:23
#define M_PI
Definition: definitions.h:10
LowPassFilterFloat roll_feedforward_filter
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
Definition: AP_Param.h:109
float get_accel_yaw_max_radss() const
float get_p()
Definition: AC_PID.cpp:134
const AP_AHRS_View & _ahrs
#define AP_GROUPEND
Definition: AP_Param.h:121
T x
Definition: vector3.h:67
T apply(T sample, float dt)