APM:Libraries
AC_AttitudeControl_Sub.cpp
Go to the documentation of this file.
2 #include <AP_HAL/AP_HAL.h>
3 #include <AP_Math/AP_Math.h>
4 
5 // table of user settable parameters
7  // parameters from parent vehicle
9 
10  // @Param: RAT_RLL_P
11  // @DisplayName: Roll axis rate controller P gain
12  // @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output
13  // @Range: 0.0 0.30
14  // @Increment: 0.005
15  // @User: Standard
16 
17  // @Param: RAT_RLL_I
18  // @DisplayName: Roll axis rate controller I gain
19  // @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
20  // @Range: 0.0 0.5
21  // @Increment: 0.01
22  // @User: Standard
23 
24  // @Param: RAT_RLL_IMAX
25  // @DisplayName: Roll axis rate controller I gain maximum
26  // @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
27  // @Range: 0 1
28  // @Increment: 0.01
29  // @Units: %
30  // @User: Standard
31 
32  // @Param: RAT_RLL_D
33  // @DisplayName: Roll axis rate controller D gain
34  // @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
35  // @Range: 0.0 0.02
36  // @Increment: 0.001
37  // @User: Standard
38 
39  // @Param: RAT_RLL_FF
40  // @DisplayName: Roll axis rate controller feed forward
41  // @Description: Roll axis rate controller feed forward
42  // @Range: 0 0.5
43  // @Increment: 0.001
44  // @User: Standard
45 
46  // @Param: RAT_RLL_FILT
47  // @DisplayName: Roll axis rate controller input frequency in Hz
48  // @Description: Roll axis rate controller input frequency in Hz
49  // @Range: 1 100
50  // @Increment: 1
51  // @Units: Hz
52  // @User: Standard
53  AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Sub, AC_PID),
54 
55  // @Param: RAT_PIT_P
56  // @DisplayName: Pitch axis rate controller P gain
57  // @Description: Pitch axis rate controller P gain. Converts the difference between desired pitch rate and actual pitch rate into a motor speed output
58  // @Range: 0.0 0.30
59  // @Increment: 0.005
60  // @User: Standard
61 
62  // @Param: RAT_PIT_I
63  // @DisplayName: Pitch axis rate controller I gain
64  // @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
65  // @Range: 0.0 0.5
66  // @Increment: 0.01
67  // @User: Standard
68 
69  // @Param: RAT_PIT_IMAX
70  // @DisplayName: Pitch axis rate controller I gain maximum
71  // @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
72  // @Range: 0 1
73  // @Increment: 0.01
74  // @Units: %
75  // @User: Standard
76 
77  // @Param: RAT_PIT_D
78  // @DisplayName: Pitch axis rate controller D gain
79  // @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
80  // @Range: 0.0 0.02
81  // @Increment: 0.001
82  // @User: Standard
83 
84  // @Param: RAT_PIT_FF
85  // @DisplayName: Pitch axis rate controller feed forward
86  // @Description: Pitch axis rate controller feed forward
87  // @Range: 0 0.5
88  // @Increment: 0.001
89  // @User: Standard
90 
91  // @Param: RAT_PIT_FILT
92  // @DisplayName: Pitch axis rate controller input frequency in Hz
93  // @Description: Pitch axis rate controller input frequency in Hz
94  // @Range: 1 100
95  // @Increment: 1
96  // @Units: Hz
97  // @User: Standard
98  AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Sub, AC_PID),
99 
100  // @Param: RAT_YAW_P
101  // @DisplayName: Yaw axis rate controller P gain
102  // @Description: Yaw axis rate controller P gain. Converts the difference between desired yaw rate and actual yaw rate into a motor speed output
103  // @Range: 0.0 0.50
104  // @Increment: 0.005
105  // @User: Standard
106 
107  // @Param: RAT_YAW_I
108  // @DisplayName: Yaw axis rate controller I gain
109  // @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
110  // @Range: 0.0 0.05
111  // @Increment: 0.01
112  // @User: Standard
113 
114  // @Param: RAT_YAW_IMAX
115  // @DisplayName: Yaw axis rate controller I gain maximum
116  // @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
117  // @Range: 0 1
118  // @Increment: 0.01
119  // @Units: %
120  // @User: Standard
121 
122  // @Param: RAT_YAW_D
123  // @DisplayName: Yaw axis rate controller D gain
124  // @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
125  // @Range: 0.000 0.02
126  // @Increment: 0.001
127  // @User: Standard
128 
129  // @Param: RAT_YAW_FF
130  // @DisplayName: Yaw axis rate controller feed forward
131  // @Description: Yaw axis rate controller feed forward
132  // @Range: 0 0.5
133  // @Increment: 0.001
134  // @User: Standard
135 
136  // @Param: RAT_YAW_FILT
137  // @DisplayName: Yaw axis rate controller input frequency in Hz
138  // @Description: Yaw axis rate controller input frequency in Hz
139  // @Range: 1 100
140  // @Increment: 1
141  // @Units: Hz
142  // @User: Standard
143  AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Sub, AC_PID),
144 
145  // @Param: THR_MIX_MIN
146  // @DisplayName: Throttle Mix Minimum
147  // @Description: Throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
148  // @Range: 0.1 0.25
149  // @User: Advanced
150  AP_GROUPINFO("THR_MIX_MIN", 4, AC_AttitudeControl_Sub, _thr_mix_min, AC_ATTITUDE_CONTROL_MIN_DEFAULT),
151 
152  // @Param: THR_MIX_MAX
153  // @DisplayName: Throttle Mix Maximum
154  // @Description: Throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)
155  // @Range: 0.5 0.9
156  // @User: Advanced
157  AP_GROUPINFO("THR_MIX_MAX", 5, AC_AttitudeControl_Sub, _thr_mix_max, AC_ATTITUDE_CONTROL_MAX_DEFAULT),
158 
159  // @Param: THR_MIX_MAN
160  // @DisplayName: Throttle Mix Manual
161  // @Description: Throttle vs attitude control prioritisation used during manual flight (higher values mean we prioritise attitude control over throttle)
162  // @Range: 0.5 0.9
163  // @User: Advanced
164  AP_GROUPINFO("THR_MIX_MAN", 6, AC_AttitudeControl_Sub, _thr_mix_man, AC_ATTITUDE_CONTROL_MAN_DEFAULT),
165 
167 };
168 
170  AC_AttitudeControl(ahrs, aparm, motors, dt),
171  _motors_multi(motors),
175 {
177 
178  // Sub-specific defaults for parent class
179  _p_angle_roll.kP().set_default(AC_ATC_SUB_ANGLE_P);
180  _p_angle_pitch.kP().set_default(AC_ATC_SUB_ANGLE_P);
181  _p_angle_yaw.kP().set_default(AC_ATC_SUB_ANGLE_P);
182 
184 }
185 
186 // Update Alt_Hold angle maximum
188 {
189  // calc maximum tilt angle based on throttle
190  float thr_max = _motors_multi.get_throttle_thrust_max();
191 
192  // divide by zero check
193  if (is_zero(thr_max)) {
195  return;
196  }
197 
198  float althold_lean_angle_max = acosf(constrain_float(_throttle_in/(AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX * thr_max), 0.0f, 1.0f));
200 }
201 
202 void AC_AttitudeControl_Sub::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)
203 {
204  _throttle_in = throttle_in;
205  update_althold_lean_angle_max(throttle_in);
206  _motors.set_throttle_filter_cutoff(filter_cutoff);
207  if (apply_angle_boost) {
208  // Apply angle boost
209  throttle_in = get_throttle_boosted(throttle_in);
210  }else{
211  // Clear angle_boost for logging purposes
212  _angle_boost = 0.0f;
213  }
214  _motors.set_throttle(throttle_in);
216 }
217 
218 // returns a throttle including compensation for roll/pitch angle
219 // throttle value should be 0 ~ 1
221 {
222  if (!_angle_boost_enabled) {
223  _angle_boost = 0;
224  return throttle_in;
225  }
226  // inverted_factor is 1 for tilt angles below 60 degrees
227  // inverted_factor reduces from 1 to 0 for tilt angles between 60 and 90 degrees
228 
229  float cos_tilt = _ahrs.cos_pitch() * _ahrs.cos_roll();
230  float inverted_factor = constrain_float(2.0f*cos_tilt, 0.0f, 1.0f);
231  float boost_factor = 1.0f/constrain_float(cos_tilt, 0.5f, 1.0f);
232 
233  float throttle_out = throttle_in*inverted_factor*boost_factor;
234  _angle_boost = constrain_float(throttle_out - throttle_in,-1.0f,1.0f);
235  return throttle_out;
236 }
237 
238 // returns a throttle including compensation for roll/pitch angle
239 // throttle value should be 0 ~ 1
241 {
242  throttle_in = constrain_float(throttle_in, 0.0f, 1.0f);
243  return MAX(throttle_in, throttle_in*MAX(0.0f,1.0f-_throttle_rpy_mix)+_motors.get_throttle_hover()*_throttle_rpy_mix);
244 }
245 
246 // update_throttle_rpy_mix - slew set_throttle_rpy_mix to requested value
248 {
249  // slew _throttle_rpy_mix to _throttle_rpy_mix_desired
251  // increase quickly (i.e. from 0.1 to 0.9 in 0.4 seconds)
254  // reduce more slowly (from 0.9 to 0.1 in 1.6 seconds)
256  }
258 }
259 
261 {
262  // move throttle vs attitude mixing towards desired (called from here because this is conveniently called on every iteration)
264 
265  Vector3f gyro_latest = _ahrs.get_gyro_latest();
269 
271 }
272 
273 // sanity check parameters. should be called once before takeoff
275 {
276  // sanity check throttle mix parameters
277  if (_thr_mix_man < 0.1f || _thr_mix_man > 4.0f) {
278  // parameter description recommends thr-mix-man be no higher than 0.9 but we allow up to 4.0
279  // which can be useful for very high powered copters with very low hover throttle
281  }
282  if (_thr_mix_min < 0.1f || _thr_mix_min > 0.25f) {
284  }
285  if (_thr_mix_max < 0.5f || _thr_mix_max > AC_ATTITUDE_CONTROL_MAX) {
286  // parameter description recommends thr-mix-max be no higher than 0.9 but we allow up to 5.0
287  // which can be useful for very high powered copters with very low hover throttle
289  }
290  if (_thr_mix_min > _thr_mix_max) {
293  }
294 }
#define AC_ATC_SUB_RATE_YAW_IMAX
void set_throttle_filter_cutoff(float filt_hz)
#define AC_ATTITUDE_CONTROL_MAN_DEFAULT
#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
void set_throttle_avg_max(float throttle_avg_max)
void set_yaw(float yaw_in)
#define AC_ATC_SUB_ACCEL_Y_MAX
#define AC_ATC_SUB_RATE_YAW_I
#define AC_ATC_SUB_RATE_RP_FILT_HZ
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float rate_target_to_motor_roll(float rate_actual_rads, float rate_target_rads)
Vector3f get_gyro_latest(void) const
void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override
#define MIN(a, b)
Definition: usb_conf.h:215
#define AC_ATC_SUB_RATE_RP_P
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
AP_MotorsMatrix motors(400)
#define AC_ATC_SUB_RATE_RP_IMAX
#define AC_ATC_SUB_ANGLE_P
float get_throttle_avg_max(float throttle_in)
ArduSub attitude control library.
static const struct AP_Param::GroupInfo var_info[]
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
T y
Definition: vector3.h:67
#define AC_ATTITUDE_CONTROL_MIN_DEFAULT
float get_throttle_thrust_max() const
#define AC_ATC_SUB_RATE_YAW_D
T z
Definition: vector3.h:67
#define AC_ATC_SUB_RATE_RP_D
#define AC_ATTITUDE_CONTROL_MAX
virtual float get_throttle_hover() const =0
void set_throttle(float throttle_in)
float get_throttle_boosted(float throttle_in)
#define AC_ATC_SUB_RATE_YAW_FILT_HZ
AP_MotorsMulticopter & _motors_multi
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
float rate_target_to_motor_pitch(float rate_actual_rads, float rate_target_rads)
#define AC_ATTITUDE_CONTROL_MAX_DEFAULT
#define AP_NESTEDGROUPINFO(clazz, idx)
Definition: AP_Param.h:105
#define AC_ATC_SUB_RATE_RP_I
void set_pitch(float pitch_in)
virtual float rate_target_to_motor_yaw(float rate_actual_rads, float rate_target_rads)
void control_monitor_update(void)
void set_roll(float roll_in)
#define AC_ATC_SUB_RATE_YAW_P
Copter PID control class.
Definition: AC_PID.h:17
void update_althold_lean_angle_max(float throttle_in) override
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
Definition: AP_Param.h:109
AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter &motors, float dt)
AP_Float & kP()
Definition: AC_P.h:58
const AP_AHRS_View & _ahrs
#define AP_GROUPEND
Definition: AP_Param.h:121
T x
Definition: vector3.h:67
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214