APM:Libraries
AC_AttitudeControl_Heli.h
Go to the documentation of this file.
1 #pragma once
2 
5 
6 #include "AC_AttitudeControl.h"
8 #include <AC_PID/AC_HELI_PID.h>
9 #include <Filter/Filter.h>
10 
11 // default rate controller PID gains
12 #define AC_ATC_HELI_RATE_RP_P 0.024f
13 #define AC_ATC_HELI_RATE_RP_I 0.6f
14 #define AC_ATC_HELI_RATE_RP_D 0.001f
15 #define AC_ATC_HELI_RATE_RP_IMAX 1.0f
16 #define AC_ATC_HELI_RATE_RP_FF 0.060f
17 #define AC_ATC_HELI_RATE_RP_FILT_HZ 20.0f
18 #define AC_ATC_HELI_RATE_YAW_P 0.18f
19 #define AC_ATC_HELI_RATE_YAW_I 0.12f
20 #define AC_ATC_HELI_RATE_YAW_D 0.003f
21 #define AC_ATC_HELI_RATE_YAW_IMAX 1.0f
22 #define AC_ATC_HELI_RATE_YAW_FF 0.024f
23 #define AC_ATC_HELI_RATE_YAW_FILT_HZ 20.0f
24 
25 #define AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX 0.95f // Heli's use 95% of max collective before limiting frame angle
26 #define AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE 0.02f
27 #define AC_ATTITUDE_HELI_RATE_RP_FF_FILTER 10.0f
28 #define AC_ATTITUDE_HELI_RATE_Y_VFF_FILTER 10.0f
29 #define AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT 300
30 #define AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD ToRad(30.0f)
31 
33 public:
35  const AP_Vehicle::MultiCopter &aparm,
37  float dt) :
38  AC_AttitudeControl(ahrs, aparm, motors, dt),
46  {
48 
49  // initialise flags
50  _flags_heli.limit_roll = false;
51  _flags_heli.limit_pitch = false;
52  _flags_heli.limit_yaw = false;
53  _flags_heli.leaky_i = true;
56  _flags_heli.do_piro_comp = false;
57  }
58 
59  // pid accessors
63 
64  // passthrough_bf_roll_pitch_rate_yaw - roll and pitch are passed through directly, body-frame rate target for yaw
65  void passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds) override;
66 
67  // Integrate vehicle rate into _att_error_rot_vec_rad
69 
70  // subclass non-passthrough too, for external gyro, no flybar
71  void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) override;
72 
73  // rate_controller_run - run lowest level body-frame rate controller and send outputs to the motors
74  // should be called at 100hz or more
75  virtual void rate_controller_run();
76 
77  // Update Alt_Hold angle maximum
78  void update_althold_lean_angle_max(float throttle_in) override;
79 
80  // use_leaky_i - controls whether we use leaky i term for body-frame to motor output stage
81  void use_leaky_i(bool leaky_i) override { _flags_heli.leaky_i = leaky_i; }
82 
83  // use_flybar_passthrough - controls whether we pass-through
84  // control inputs to swash-plate and tail
85  void use_flybar_passthrough(bool passthrough, bool tail_passthrough) override {
86  _flags_heli.flybar_passthrough = passthrough;
87  _flags_heli.tail_passthrough = tail_passthrough;
88  }
89 
90  // do_piro_comp - controls whether piro-comp is active or not
91  void do_piro_comp(bool piro_comp) { _flags_heli.do_piro_comp = piro_comp; }
92 
93  // set_hover_roll_scalar - scales Hover Roll Trim parameter. To be used by vehicle code according to vehicle condition.
94  void set_hover_roll_trim_scalar(float scalar) override {_hover_roll_trim_scalar = constrain_float(scalar, 0.0f, 1.0f);}
95 
96  // Set output throttle
97  void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override;
98 
99  // Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
100  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;
101 
102  // Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
103  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;
104 
105  // enable/disable inverted flight
106  void set_inverted_flight(bool inverted) override {
107  _inverted_flight = inverted;
108  }
109 
110  // user settable parameters
111  static const struct AP_Param::GroupInfo var_info[];
112 
113 private:
114 
115  // To-Do: move these limits flags into the heli motors class
117  uint8_t limit_roll : 1; // 1 if we have requested larger roll angle than swash can physically move
118  uint8_t limit_pitch : 1; // 1 if we have requested larger pitch angle than swash can physically move
119  uint8_t limit_yaw : 1; // 1 if we have requested larger yaw angle than tail servo can physically move
120  uint8_t leaky_i : 1; // 1 if we should use leaky i term for body-frame rate to motor stage
121  uint8_t flybar_passthrough : 1; // 1 if we should pass through pilots roll & pitch input directly to swash-plate
122  uint8_t tail_passthrough : 1; // 1 if we should pass through pilots yaw input to tail
123  uint8_t do_piro_comp : 1; // 1 if we should do pirouette compensation on roll/pitch
124  } _flags_heli;
125 
126  //
127  // body-frame rate controller
128  //
129  // rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target body-frame rate (in radians/sec) for roll, pitch and yaw
130  // outputs are sent directly to motor class
131  void rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads);
132  float rate_target_to_motor_yaw(float rate_yaw_actual_rads, float rate_yaw_rads) override;
133 
134  //
135  // throttle methods
136  //
137 
138  // pass through for roll and pitch
141 
142  // pass through for yaw if tail_passthrough is set
144 
145  // get_roll_trim - angle in centi-degrees to be added to roll angle. Used by helicopter to counter tail rotor thrust in hover
147 
148  // internal variables
149  float _hover_roll_trim_scalar = 0; // scalar used to suppress Hover Roll Trim
150 
151 
152  // This represents an euler axis-angle rotation vector from the vehicles
153  // estimated attitude to the reference (setpoint) attitude used in the attitude
154  // controller, in radians in the vehicle body frame of reference.
156 
157  // parameters
158  AP_Int8 _piro_comp_enabled; // Flybar present or not. Affects attitude controller used during ACRO flight mode
159  AP_Int16 _hover_roll_trim; // Angle in centi-degrees used to counter tail rotor thrust in hover
163 
164  // LPF filters to act on Rate Feedforward terms to linearize output.
165  // Due to complicated aerodynamic effects, feedforwards acting too fast can lead
166  // to jerks on rate change requests.
171 
172 };
#define AC_ATC_HELI_RATE_RP_FF
#define AC_ATC_HELI_RATE_RP_P
struct AC_AttitudeControl_Heli::AttControlHeliFlags _flags_heli
float rate_target_to_motor_yaw(float rate_yaw_actual_rads, float rate_yaw_rads) override
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
AC_AttitudeControl_Heli(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsHeli &motors, float dt)
void set_inverted_flight(bool inverted) override
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
void update_althold_lean_angle_max(float throttle_in) override
#define AC_ATC_HELI_RATE_YAW_FILT_HZ
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[]
AP_MotorsMatrix motors(400)
#define AC_ATC_HELI_RATE_YAW_D
Heli PID control class.
Definition: AC_HELI_PID.h:16
#define AC_ATC_HELI_RATE_RP_IMAX
#define AC_ATC_HELI_RATE_RP_I
LowPassFilterFloat yaw_velocity_feedforward_filter
ArduCopter attitude control library.
Helicopter Specific Rate PID algorithm, with EEPROM-backed storage of constants.
#define AC_ATTITUDE_HELI_RATE_Y_VFF_FILTER
#define f(i)
#define AC_ATC_HELI_RATE_YAW_I
void use_leaky_i(bool leaky_i) override
#define AC_ATC_HELI_RATE_RP_D
void rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads)
#define AC_ATC_HELI_RATE_RP_FILT_HZ
void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override
void set_hover_roll_trim_scalar(float scalar) override
void passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds) override
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void use_flybar_passthrough(bool passthrough, bool tail_passthrough) override
void do_piro_comp(bool piro_comp)
#define AC_ATC_HELI_RATE_YAW_P
Motor control class for Traditional Heli.
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
Copter PID control class.
Definition: AC_PID.h:17
LowPassFilterFloat roll_feedforward_filter
#define AC_ATC_HELI_RATE_YAW_FF
#define AC_ATTITUDE_HELI_RATE_RP_FF_FILTER
LowPassFilterFloat yaw_acceleration_feedforward_filter
#define AC_ATC_HELI_RATE_YAW_IMAX
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214