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.cpp
Views: 1798
1
#include "AC_AttitudeControl.h"
2
#include <AP_HAL/AP_HAL.h>
3
#include <AP_Vehicle/AP_Vehicle_Type.h>
4
#include <AP_Scheduler/AP_Scheduler.h>
5
6
extern const AP_HAL::HAL& hal;
7
8
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
9
// default gains for Plane
10
# define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.2f // Soft
11
#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 5.0 // Min lean angle so that vehicle can maintain limited control
12
#define AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL 0
13
#else
14
// default gains for Copter and Sub
15
# define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.15f // Medium
16
#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 10.0 // Min lean angle so that vehicle can maintain limited control
17
#define AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL 1
18
#endif
19
20
AC_AttitudeControl *AC_AttitudeControl::_singleton;
21
22
// table of user settable parameters
23
const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
24
25
// 0, 1 were RATE_RP_MAX, RATE_Y_MAX
26
27
// @Param: SLEW_YAW
28
// @DisplayName: Yaw target slew rate
29
// @Description: Maximum rate the yaw target can be updated in RTL and Auto flight modes
30
// @Units: cdeg/s
31
// @Range: 500 18000
32
// @Increment: 100
33
// @User: Advanced
34
AP_GROUPINFO("SLEW_YAW", 2, AC_AttitudeControl, _slew_yaw, AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT_CDS),
35
36
// 3 was for ACCEL_RP_MAX
37
38
// @Param: ACCEL_Y_MAX
39
// @DisplayName: Acceleration Max for Yaw
40
// @Description: Maximum acceleration in yaw axis
41
// @Units: cdeg/s/s
42
// @Range: 0 72000
43
// @Values: 0:Disabled, 9000:VerySlow, 18000:Slow, 36000:Medium, 54000:Fast
44
// @Increment: 1000
45
// @User: Advanced
46
AP_GROUPINFO("ACCEL_Y_MAX", 4, AC_AttitudeControl, _accel_yaw_max, AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS),
47
48
// @Param: RATE_FF_ENAB
49
// @DisplayName: Rate Feedforward Enable
50
// @Description: Controls whether body-frame rate feedforward is enabled or disabled
51
// @Values: 0:Disabled, 1:Enabled
52
// @User: Advanced
53
AP_GROUPINFO("RATE_FF_ENAB", 5, AC_AttitudeControl, _rate_bf_ff_enabled, AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT),
54
55
// @Param: ACCEL_R_MAX
56
// @DisplayName: Acceleration Max for Roll
57
// @Description: Maximum acceleration in roll axis
58
// @Units: cdeg/s/s
59
// @Range: 0 180000
60
// @Increment: 1000
61
// @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast
62
// @User: Advanced
63
AP_GROUPINFO("ACCEL_R_MAX", 6, AC_AttitudeControl, _accel_roll_max, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS),
64
65
// @Param: ACCEL_P_MAX
66
// @DisplayName: Acceleration Max for Pitch
67
// @Description: Maximum acceleration in pitch axis
68
// @Units: cdeg/s/s
69
// @Range: 0 180000
70
// @Increment: 1000
71
// @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast
72
// @User: Advanced
73
AP_GROUPINFO("ACCEL_P_MAX", 7, AC_AttitudeControl, _accel_pitch_max, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS),
74
75
// IDs 8,9,10,11 RESERVED (in use on Solo)
76
77
// @Param: ANGLE_BOOST
78
// @DisplayName: Angle Boost
79
// @Description: Angle Boost increases output throttle as the vehicle leans to reduce loss of altitude
80
// @Values: 0:Disabled, 1:Enabled
81
// @User: Advanced
82
AP_GROUPINFO("ANGLE_BOOST", 12, AC_AttitudeControl, _angle_boost_enabled, 1),
83
84
// @Param: ANG_RLL_P
85
// @DisplayName: Roll axis angle controller P gain
86
// @Description: Roll axis angle controller P gain. Converts the error between the desired roll angle and actual angle to a desired roll rate
87
// @Range: 3.000 12.000
88
// @Range{Sub}: 0.0 12.000
89
// @User: Standard
90
AP_SUBGROUPINFO(_p_angle_roll, "ANG_RLL_", 13, AC_AttitudeControl, AC_P),
91
92
// @Param: ANG_PIT_P
93
// @DisplayName: Pitch axis angle controller P gain
94
// @Description: Pitch axis angle controller P gain. Converts the error between the desired pitch angle and actual angle to a desired pitch rate
95
// @Range: 3.000 12.000
96
// @Range{Sub}: 0.0 12.000
97
// @User: Standard
98
AP_SUBGROUPINFO(_p_angle_pitch, "ANG_PIT_", 14, AC_AttitudeControl, AC_P),
99
100
// @Param: ANG_YAW_P
101
// @DisplayName: Yaw axis angle controller P gain
102
// @Description: Yaw axis angle controller P gain. Converts the error between the desired yaw angle and actual angle to a desired yaw rate
103
// @Range: 3.000 12.000
104
// @Range{Sub}: 0.0 6.000
105
// @User: Standard
106
AP_SUBGROUPINFO(_p_angle_yaw, "ANG_YAW_", 15, AC_AttitudeControl, AC_P),
107
108
// @Param: ANG_LIM_TC
109
// @DisplayName: Angle Limit (to maintain altitude) Time Constant
110
// @Description: Angle Limit (to maintain altitude) Time Constant
111
// @Range: 0.5 10.0
112
// @User: Advanced
113
AP_GROUPINFO("ANG_LIM_TC", 16, AC_AttitudeControl, _angle_limit_tc, AC_ATTITUDE_CONTROL_ANGLE_LIMIT_TC_DEFAULT),
114
115
// @Param: RATE_R_MAX
116
// @DisplayName: Angular Velocity Max for Roll
117
// @Description: Maximum angular velocity in roll axis
118
// @Units: deg/s
119
// @Range: 0 1080
120
// @Increment: 1
121
// @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast
122
// @User: Advanced
123
AP_GROUPINFO("RATE_R_MAX", 17, AC_AttitudeControl, _ang_vel_roll_max, 0.0f),
124
125
// @Param: RATE_P_MAX
126
// @DisplayName: Angular Velocity Max for Pitch
127
// @Description: Maximum angular velocity in pitch axis
128
// @Units: deg/s
129
// @Range: 0 1080
130
// @Increment: 1
131
// @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast
132
// @User: Advanced
133
AP_GROUPINFO("RATE_P_MAX", 18, AC_AttitudeControl, _ang_vel_pitch_max, 0.0f),
134
135
// @Param: RATE_Y_MAX
136
// @DisplayName: Angular Velocity Max for Yaw
137
// @Description: Maximum angular velocity in yaw axis
138
// @Units: deg/s
139
// @Range: 0 1080
140
// @Increment: 1
141
// @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast
142
// @User: Advanced
143
AP_GROUPINFO("RATE_Y_MAX", 19, AC_AttitudeControl, _ang_vel_yaw_max, 0.0f),
144
145
// @Param: INPUT_TC
146
// @DisplayName: Attitude control input time constant
147
// @Description: Attitude control input time constant. Low numbers lead to sharper response, higher numbers to softer response
148
// @Units: s
149
// @Range: 0 1
150
// @Increment: 0.01
151
// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
152
// @User: Standard
153
AP_GROUPINFO("INPUT_TC", 20, AC_AttitudeControl, _input_tc, AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT),
154
155
// @Param: LAND_R_MULT
156
// @DisplayName: Landed roll gain multiplier
157
// @Description: Roll gain multiplier active when landed. A factor of 1.0 means no reduction in gain while landed. Reduce this factor to reduce ground oscitation in the roll axis.
158
// @Range: 0.25 1.0
159
// @User: Advanced
160
AP_GROUPINFO("LAND_R_MULT", 21, AC_AttitudeControl, _land_roll_mult, 1.0),
161
162
// @Param: LAND_P_MULT
163
// @DisplayName: Landed pitch gain multiplier
164
// @Description: Pitch gain multiplier active when landed. A factor of 1.0 means no reduction in gain while landed. Reduce this factor to reduce ground oscitation in the pitch axis.
165
// @Range: 0.25 1.0
166
// @User: Advanced
167
AP_GROUPINFO("LAND_P_MULT", 22, AC_AttitudeControl, _land_pitch_mult, 1.0),
168
169
// @Param: LAND_Y_MULT
170
// @DisplayName: Landed yaw gain multiplier
171
// @Description: Yaw gain multiplier active when landed. A factor of 1.0 means no reduction in gain while landed. Reduce this factor to reduce ground oscitation in the yaw axis.
172
// @Range: 0.25 1.0
173
// @User: Advanced
174
AP_GROUPINFO("LAND_Y_MULT", 23, AC_AttitudeControl, _land_yaw_mult, 1.0),
175
176
AP_GROUPEND
177
};
178
179
constexpr Vector3f AC_AttitudeControl::VECTORF_111;
180
181
// get the slew yaw rate limit in deg/s
182
float AC_AttitudeControl::get_slew_yaw_max_degs() const
183
{
184
if (!is_positive(_ang_vel_yaw_max)) {
185
return _slew_yaw * 0.01;
186
}
187
return MIN(_ang_vel_yaw_max, _slew_yaw * 0.01);
188
}
189
190
// get the latest gyro for the purposes of attitude control
191
// Counter-inuitively the lowest latency for rate control is achieved by running rate control
192
// *before* attitude control. This is because you want rate control to run as close as possible
193
// to the time that a gyro sample was read to minimise jitter and control errors. Running rate
194
// control after attitude control might makes sense logically, but the overhead of attitude
195
// control calculations (and other updates) compromises the actual rate control.
196
//
197
// In the case of running rate control in a separate thread, the ordering between rate and attitude
198
// updates is less important, except that gyro sample used should be the latest
199
//
200
// Currently quadplane runs rate control after attitude control, necessitating the following code
201
// to minimise latency.
202
// However this code can be removed once quadplane updates it's structure to run the rate loops before
203
// the Attitude controller.
204
const Vector3f AC_AttitudeControl::get_latest_gyro() const
205
{
206
#if AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL
207
// rate updates happen before attitude updates so the last gyro value is the last rate gyro value
208
// this also allows a separate rate thread to be the source of gyro data
209
return _rate_gyro;
210
#else
211
// rate updates happen after attitude updates so the AHRS must be consulted for the last gyro value
212
return _ahrs.get_gyro_latest();
213
#endif
214
}
215
216
// Ensure attitude controller have zero errors to relax rate controller output
217
void AC_AttitudeControl::relax_attitude_controllers()
218
{
219
// take a copy of the last gyro used by the rate controller before using it
220
Vector3f gyro = get_latest_gyro();
221
// Initialize the attitude variables to the current attitude
222
_ahrs.get_quat_body_to_ned(_attitude_target);
223
_attitude_target.to_euler(_euler_angle_target);
224
_attitude_ang_error.initialise();
225
226
// Initialize the angular rate variables to the current rate
227
_ang_vel_target = gyro;
228
ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);
229
230
// Initialize remaining variables
231
_thrust_error_angle = 0.0f;
232
233
// Reset the PID filters
234
get_rate_roll_pid().reset_filter();
235
get_rate_pitch_pid().reset_filter();
236
get_rate_yaw_pid().reset_filter();
237
238
// Reset the I terms
239
reset_rate_controller_I_terms();
240
// finally update the attitude target
241
_ang_vel_body = gyro;
242
}
243
244
void AC_AttitudeControl::reset_rate_controller_I_terms()
245
{
246
get_rate_roll_pid().reset_I();
247
get_rate_pitch_pid().reset_I();
248
get_rate_yaw_pid().reset_I();
249
}
250
251
// reset rate controller I terms smoothly to zero in 0.5 seconds
252
void AC_AttitudeControl::reset_rate_controller_I_terms_smoothly()
253
{
254
get_rate_roll_pid().relax_integrator(0.0, _dt, AC_ATTITUDE_RATE_RELAX_TC);
255
get_rate_pitch_pid().relax_integrator(0.0, _dt, AC_ATTITUDE_RATE_RELAX_TC);
256
get_rate_yaw_pid().relax_integrator(0.0, _dt, AC_ATTITUDE_RATE_RELAX_TC);
257
}
258
259
// Reduce attitude control gains while landed to stop ground resonance
260
void AC_AttitudeControl::landed_gain_reduction(bool landed)
261
{
262
if (is_positive(_input_tc)) {
263
// use 2.0 x tc to match the response time to 86% commanded
264
const float spool_step = _dt / (2.0 * _input_tc);
265
if (landed) {
266
_landed_gain_ratio = MIN(1.0, _landed_gain_ratio + spool_step);
267
} else {
268
_landed_gain_ratio = MAX(0.0, _landed_gain_ratio - spool_step);
269
}
270
} else {
271
_landed_gain_ratio = landed ? 1.0 : 0.0;
272
}
273
Vector3f scale_mult = VECTORF_111 * (1.0 - _landed_gain_ratio) + Vector3f(_land_roll_mult, _land_pitch_mult, _land_yaw_mult) * _landed_gain_ratio;
274
set_PD_scale_mult(scale_mult);
275
set_angle_P_scale_mult(scale_mult);
276
}
277
278
// The attitude controller works around the concept of the desired attitude, target attitude
279
// and measured attitude. The desired attitude is the attitude input into the attitude controller
280
// that expresses where the higher level code would like the aircraft to move to. The target attitude is moved
281
// to the desired attitude with jerk, acceleration, and velocity limits. The target angular velocities are fed
282
// directly into the rate controllers. The angular error between the measured attitude and the target attitude is
283
// fed into the angle controller and the output of the angle controller summed at the input of the rate controllers.
284
// By feeding the target angular velocity directly into the rate controllers the measured and target attitudes
285
// remain very close together.
286
//
287
// All input functions below follow the same procedure
288
// 1. define the desired attitude or attitude change based on the input variables
289
// 2. update the target attitude based on the angular velocity target and the time since the last loop
290
// 3. using the desired attitude and input variables, define the target angular velocity so that it should
291
// move the target attitude towards the desired attitude
292
// 4. if _rate_bf_ff_enabled is not being used then make the target attitude
293
// and target angular velocities equal to the desired attitude and desired angular velocities.
294
// 5. ensure _attitude_target, _euler_angle_target, _euler_rate_target and
295
// _ang_vel_target have been defined. This ensures input modes can be changed without discontinuity.
296
// 6. attitude_controller_run_quat is then run to pass the target angular velocities to the rate controllers and
297
// integrate them into the target attitude. Any errors between the target attitude and the measured attitude are
298
// corrected by first correcting the thrust vector until the angle between the target thrust vector measured
299
// trust vector drops below 2*AC_ATTITUDE_THRUST_ERROR_ANGLE. At this point the heading is also corrected.
300
301
// Command a Quaternion attitude with feedforward and smoothing
302
// attitude_desired_quat: is updated on each time_step by the integral of the body frame angular velocity
303
void AC_AttitudeControl::input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_body)
304
{
305
// update attitude target
306
update_attitude_target();
307
308
// Limit the angular velocity
309
ang_vel_limit(ang_vel_body, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));
310
Vector3f ang_vel_target = attitude_desired_quat * ang_vel_body;
311
312
if (_rate_bf_ff_enabled) {
313
Quaternion attitude_error_quat = _attitude_target.inverse() * attitude_desired_quat;
314
Vector3f attitude_error_angle;
315
attitude_error_quat.to_axis_angle(attitude_error_angle);
316
317
// When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler
318
// angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration
319
// and an exponential decay specified by _input_tc at the end.
320
_ang_vel_target.x = input_shaping_angle(wrap_PI(attitude_error_angle.x), _input_tc, get_accel_roll_max_radss(), _ang_vel_target.x, ang_vel_target.x, radians(_ang_vel_roll_max), _dt);
321
_ang_vel_target.y = input_shaping_angle(wrap_PI(attitude_error_angle.y), _input_tc, get_accel_pitch_max_radss(), _ang_vel_target.y, ang_vel_target.y, radians(_ang_vel_pitch_max), _dt);
322
_ang_vel_target.z = input_shaping_angle(wrap_PI(attitude_error_angle.z), _input_tc, get_accel_yaw_max_radss(), _ang_vel_target.z, ang_vel_target.z, radians(_ang_vel_yaw_max), _dt);
323
} else {
324
_attitude_target = attitude_desired_quat;
325
_ang_vel_target = ang_vel_target;
326
}
327
328
// calculate the attitude target euler angles
329
_attitude_target.to_euler(_euler_angle_target);
330
331
// Convert body-frame angular velocity into euler angle derivative of desired attitude
332
ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);
333
334
// rotate target and normalize
335
Quaternion attitude_desired_update;
336
attitude_desired_update.from_axis_angle(ang_vel_target * _dt);
337
attitude_desired_quat = attitude_desired_quat * attitude_desired_update;
338
attitude_desired_quat.normalize();
339
340
// Call quaternion attitude controller
341
attitude_controller_run_quat();
342
}
343
344
// Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
345
void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)
346
{
347
// Convert from centidegrees on public interface to radians
348
float euler_roll_angle = radians(euler_roll_angle_cd * 0.01f);
349
float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f);
350
float euler_yaw_rate = radians(euler_yaw_rate_cds * 0.01f);
351
352
// update attitude target
353
update_attitude_target();
354
355
// calculate the attitude target euler angles
356
_attitude_target.to_euler(_euler_angle_target);
357
358
// Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)
359
euler_roll_angle += get_roll_trim_rad();
360
361
if (_rate_bf_ff_enabled) {
362
// translate the roll pitch and yaw acceleration limits to the euler axis
363
const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()});
364
365
// When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler
366
// angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration
367
// and an exponential decay specified by smoothing_gain at the end.
368
_euler_rate_target.x = input_shaping_angle(wrap_PI(euler_roll_angle - _euler_angle_target.x), _input_tc, euler_accel.x, _euler_rate_target.x, _dt);
369
_euler_rate_target.y = input_shaping_angle(wrap_PI(euler_pitch_angle - _euler_angle_target.y), _input_tc, euler_accel.y, _euler_rate_target.y, _dt);
370
371
// When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing
372
// the output rate towards the input rate.
373
_euler_rate_target.z = input_shaping_ang_vel(_euler_rate_target.z, euler_yaw_rate, euler_accel.z, _dt, _rate_y_tc);
374
375
// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
376
euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target);
377
// Limit the angular velocity
378
ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));
379
// Convert body-frame angular velocity into euler angle derivative of desired attitude
380
ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);
381
} else {
382
// When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.
383
_euler_angle_target.x = euler_roll_angle;
384
_euler_angle_target.y = euler_pitch_angle;
385
_euler_angle_target.z += euler_yaw_rate * _dt;
386
// Compute quaternion target attitude
387
_attitude_target.from_euler(_euler_angle_target.x, _euler_angle_target.y, _euler_angle_target.z);
388
389
// Set rate feedforward requests to zero
390
_euler_rate_target.zero();
391
_ang_vel_target.zero();
392
}
393
394
// Call quaternion attitude controller
395
attitude_controller_run_quat();
396
}
397
398
// Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
399
void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)
400
{
401
// Convert from centidegrees on public interface to radians
402
float euler_roll_angle = radians(euler_roll_angle_cd * 0.01f);
403
float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f);
404
float euler_yaw_angle = radians(euler_yaw_angle_cd * 0.01f);
405
406
// update attitude target
407
update_attitude_target();
408
409
// calculate the attitude target euler angles
410
_attitude_target.to_euler(_euler_angle_target);
411
412
// Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)
413
euler_roll_angle += get_roll_trim_rad();
414
415
const float slew_yaw_max_rads = get_slew_yaw_max_rads();
416
if (_rate_bf_ff_enabled) {
417
// translate the roll pitch and yaw acceleration limits to the euler axis
418
const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()});
419
420
// When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler
421
// angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration
422
// and an exponential decay specified by _input_tc at the end.
423
_euler_rate_target.x = input_shaping_angle(wrap_PI(euler_roll_angle - _euler_angle_target.x), _input_tc, euler_accel.x, _euler_rate_target.x, _dt);
424
_euler_rate_target.y = input_shaping_angle(wrap_PI(euler_pitch_angle - _euler_angle_target.y), _input_tc, euler_accel.y, _euler_rate_target.y, _dt);
425
_euler_rate_target.z = input_shaping_angle(wrap_PI(euler_yaw_angle - _euler_angle_target.z), _input_tc, euler_accel.z, _euler_rate_target.z, _dt);
426
if (slew_yaw) {
427
_euler_rate_target.z = constrain_float(_euler_rate_target.z, -slew_yaw_max_rads, slew_yaw_max_rads);
428
}
429
430
// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
431
euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target);
432
// Limit the angular velocity
433
ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));
434
// Convert body-frame angular velocity into euler angle derivative of desired attitude
435
ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);
436
} else {
437
// When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.
438
_euler_angle_target.x = euler_roll_angle;
439
_euler_angle_target.y = euler_pitch_angle;
440
if (slew_yaw) {
441
// Compute constrained angle error
442
float angle_error = constrain_float(wrap_PI(euler_yaw_angle - _euler_angle_target.z), -slew_yaw_max_rads * _dt, slew_yaw_max_rads * _dt);
443
// Update attitude target from constrained angle error
444
_euler_angle_target.z = wrap_PI(angle_error + _euler_angle_target.z);
445
} else {
446
_euler_angle_target.z = euler_yaw_angle;
447
}
448
// Compute quaternion target attitude
449
_attitude_target.from_euler(_euler_angle_target.x, _euler_angle_target.y, _euler_angle_target.z);
450
451
// Set rate feedforward requests to zero
452
_euler_rate_target.zero();
453
_ang_vel_target.zero();
454
}
455
456
// Call quaternion attitude controller
457
attitude_controller_run_quat();
458
}
459
460
// Command an euler roll, pitch, and yaw rate with angular velocity feedforward and smoothing
461
void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds)
462
{
463
// Convert from centidegrees on public interface to radians
464
float euler_roll_rate = radians(euler_roll_rate_cds * 0.01f);
465
float euler_pitch_rate = radians(euler_pitch_rate_cds * 0.01f);
466
float euler_yaw_rate = radians(euler_yaw_rate_cds * 0.01f);
467
468
// update attitude target
469
update_attitude_target();
470
471
// calculate the attitude target euler angles
472
_attitude_target.to_euler(_euler_angle_target);
473
474
if (_rate_bf_ff_enabled) {
475
// translate the roll pitch and yaw acceleration limits to the euler axis
476
const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()});
477
478
// When acceleration limiting is enabled, the input shaper constrains angular acceleration, slewing
479
// the output rate towards the input rate.
480
_euler_rate_target.x = input_shaping_ang_vel(_euler_rate_target.x, euler_roll_rate, euler_accel.x, _dt, _rate_rp_tc);
481
_euler_rate_target.y = input_shaping_ang_vel(_euler_rate_target.y, euler_pitch_rate, euler_accel.y, _dt, _rate_rp_tc);
482
_euler_rate_target.z = input_shaping_ang_vel(_euler_rate_target.z, euler_yaw_rate, euler_accel.z, _dt, _rate_y_tc);
483
484
// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
485
euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target);
486
} else {
487
// When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.
488
// Pitch angle is restricted to +- 85.0 degrees to avoid gimbal lock discontinuities.
489
_euler_angle_target.x = wrap_PI(_euler_angle_target.x + euler_roll_rate * _dt);
490
_euler_angle_target.y = constrain_float(_euler_angle_target.y + euler_pitch_rate * _dt, radians(-85.0f), radians(85.0f));
491
_euler_angle_target.z = wrap_2PI(_euler_angle_target.z + euler_yaw_rate * _dt);
492
493
// Set rate feedforward requests to zero
494
_euler_rate_target.zero();
495
_ang_vel_target.zero();
496
497
// Compute quaternion target attitude
498
_attitude_target.from_euler(_euler_angle_target.x, _euler_angle_target.y, _euler_angle_target.z);
499
}
500
501
// Call quaternion attitude controller
502
attitude_controller_run_quat();
503
}
504
505
// Fully stabilized acro
506
// Command an angular velocity with angular velocity feedforward and smoothing
507
void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
508
{
509
// Convert from centidegrees on public interface to radians
510
float roll_rate_rads = radians(roll_rate_bf_cds * 0.01f);
511
float pitch_rate_rads = radians(pitch_rate_bf_cds * 0.01f);
512
float yaw_rate_rads = radians(yaw_rate_bf_cds * 0.01f);
513
514
// update attitude target
515
update_attitude_target();
516
517
// calculate the attitude target euler angles
518
_attitude_target.to_euler(_euler_angle_target);
519
520
if (_rate_bf_ff_enabled) {
521
// Compute acceleration-limited body frame rates
522
// When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing
523
// the output rate towards the input rate.
524
_ang_vel_target.x = input_shaping_ang_vel(_ang_vel_target.x, roll_rate_rads, get_accel_roll_max_radss(), _dt, _rate_rp_tc);
525
_ang_vel_target.y = input_shaping_ang_vel(_ang_vel_target.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt, _rate_rp_tc);
526
_ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt, _rate_y_tc);
527
528
// Convert body-frame angular velocity into euler angle derivative of desired attitude
529
ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);
530
} else {
531
// When feedforward is not enabled, the quaternion is calculated and is input into the target and the feedforward rate is zeroed.
532
Quaternion attitude_target_update;
533
attitude_target_update.from_axis_angle(Vector3f{roll_rate_rads, pitch_rate_rads, yaw_rate_rads} * _dt);
534
_attitude_target = _attitude_target * attitude_target_update;
535
_attitude_target.normalize();
536
537
// Set rate feedforward requests to zero
538
_euler_rate_target.zero();
539
_ang_vel_target.zero();
540
}
541
542
// Call quaternion attitude controller
543
attitude_controller_run_quat();
544
}
545
546
// Rate-only acro with no attitude feedback - used only by Copter rate-only acro
547
// Command an angular velocity with angular velocity smoothing using rate loops only with no attitude loop stabilization
548
void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
549
{
550
// Convert from centidegrees on public interface to radians
551
float roll_rate_rads = radians(roll_rate_bf_cds * 0.01f);
552
float pitch_rate_rads = radians(pitch_rate_bf_cds * 0.01f);
553
float yaw_rate_rads = radians(yaw_rate_bf_cds * 0.01f);
554
555
// Compute acceleration-limited body frame rates
556
// When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing
557
// the output rate towards the input rate.
558
_ang_vel_target.x = input_shaping_ang_vel(_ang_vel_target.x, roll_rate_rads, get_accel_roll_max_radss(), _dt, _rate_rp_tc);
559
_ang_vel_target.y = input_shaping_ang_vel(_ang_vel_target.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt, _rate_rp_tc);
560
_ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt, _rate_y_tc);
561
562
// Update the unused targets attitude based on current attitude to condition mode change
563
_ahrs.get_quat_body_to_ned(_attitude_target);
564
_attitude_target.to_euler(_euler_angle_target);
565
// Convert body-frame angular velocity into euler angle derivative of desired attitude
566
ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);
567
568
// finally update the attitude target
569
_ang_vel_body = _ang_vel_target;
570
}
571
572
// Acro with attitude feedback that does not rely on attitude - used only by Plane acro
573
// Command an angular velocity with angular velocity smoothing using rate loops only with integrated rate error stabilization
574
void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
575
{
576
// Convert from centidegrees on public interface to radians
577
float roll_rate_rads = radians(roll_rate_bf_cds * 0.01f);
578
float pitch_rate_rads = radians(pitch_rate_bf_cds * 0.01f);
579
float yaw_rate_rads = radians(yaw_rate_bf_cds * 0.01f);
580
581
// Update attitude error
582
Vector3f attitude_error;
583
_attitude_ang_error.to_axis_angle(attitude_error);
584
585
Quaternion attitude_ang_error_update_quat;
586
// limit the integrated error angle
587
float err_mag = attitude_error.length();
588
if (err_mag > AC_ATTITUDE_THRUST_ERROR_ANGLE) {
589
attitude_error *= AC_ATTITUDE_THRUST_ERROR_ANGLE / err_mag;
590
_attitude_ang_error.from_axis_angle(attitude_error);
591
}
592
593
Vector3f gyro_latest = get_latest_gyro();
594
attitude_ang_error_update_quat.from_axis_angle((_ang_vel_target - gyro_latest) * _dt);
595
_attitude_ang_error = attitude_ang_error_update_quat * _attitude_ang_error;
596
_attitude_ang_error.normalize();
597
598
// Compute acceleration-limited body frame rates
599
// When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing
600
// the output rate towards the input rate.
601
_ang_vel_target.x = input_shaping_ang_vel(_ang_vel_target.x, roll_rate_rads, get_accel_roll_max_radss(), _dt, _rate_rp_tc);
602
_ang_vel_target.y = input_shaping_ang_vel(_ang_vel_target.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt, _rate_rp_tc);
603
_ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt, _rate_y_tc);
604
605
// Retrieve quaternion body attitude
606
Quaternion attitude_body;
607
_ahrs.get_quat_body_to_ned(attitude_body);
608
609
// Update the unused targets attitude based on current attitude to condition mode change
610
_attitude_target = attitude_body * _attitude_ang_error;
611
_attitude_target.normalize();
612
613
// calculate the attitude target euler angles
614
_attitude_target.to_euler(_euler_angle_target);
615
616
// Convert body-frame angular velocity into euler angle derivative of desired attitude
617
ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);
618
619
// Compute the angular velocity target from the integrated rate error
620
_attitude_ang_error.to_axis_angle(attitude_error);
621
Vector3f ang_vel_body = update_ang_vel_target_from_att_error(attitude_error);
622
ang_vel_body += _ang_vel_target;
623
624
// finally update the attitude target
625
_ang_vel_body = ang_vel_body;
626
}
627
628
// Command an angular step (i.e change) in body frame angle
629
// Used to command a step in angle without exciting the orthogonal axis during autotune
630
void AC_AttitudeControl::input_angle_step_bf_roll_pitch_yaw(float roll_angle_step_bf_cd, float pitch_angle_step_bf_cd, float yaw_angle_step_bf_cd)
631
{
632
// Convert from centidegrees on public interface to radians
633
float roll_step_rads = radians(roll_angle_step_bf_cd * 0.01f);
634
float pitch_step_rads = radians(pitch_angle_step_bf_cd * 0.01f);
635
float yaw_step_rads = radians(yaw_angle_step_bf_cd * 0.01f);
636
637
// rotate attitude target by desired step
638
Quaternion attitude_target_update;
639
attitude_target_update.from_axis_angle(Vector3f{roll_step_rads, pitch_step_rads, yaw_step_rads});
640
_attitude_target = _attitude_target * attitude_target_update;
641
_attitude_target.normalize();
642
643
// calculate the attitude target euler angles
644
_attitude_target.to_euler(_euler_angle_target);
645
646
// Set rate feedforward requests to zero
647
_euler_rate_target.zero();
648
_ang_vel_target.zero();
649
650
// Call quaternion attitude controller
651
attitude_controller_run_quat();
652
}
653
654
// Command an rate step (i.e change) in body frame rate
655
// Used to command a step in rate without exciting the orthogonal axis during autotune
656
// Done as a single thread-safe function to avoid intermediate zero values being seen by the attitude controller
657
void AC_AttitudeControl::input_rate_step_bf_roll_pitch_yaw(float roll_rate_step_bf_cd, float pitch_rate_step_bf_cd, float yaw_rate_step_bf_cd)
658
{
659
// Update the unused targets attitude based on current attitude to condition mode change
660
_ahrs.get_quat_body_to_ned(_attitude_target);
661
_attitude_target.to_euler(_euler_angle_target);
662
// Set the target angular velocity to be zero to minimize target overshoot after the rate step finishes
663
_ang_vel_target.zero();
664
// Convert body-frame angular velocity into euler angle derivative of desired attitude
665
_euler_rate_target.zero();
666
667
Vector3f ang_vel_body {roll_rate_step_bf_cd, pitch_rate_step_bf_cd, yaw_rate_step_bf_cd};
668
ang_vel_body = ang_vel_body * 0.01f * DEG_TO_RAD;
669
// finally update the attitude target
670
_ang_vel_body = ang_vel_body;
671
}
672
673
// Command a thrust vector and heading rate
674
void AC_AttitudeControl::input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds, bool slew_yaw)
675
{
676
// Convert from centidegrees on public interface to radians
677
float heading_rate = radians(heading_rate_cds * 0.01f);
678
if (slew_yaw) {
679
// a zero _angle_vel_yaw_max means that setting is disabled
680
const float slew_yaw_max_rads = get_slew_yaw_max_rads();
681
heading_rate = constrain_float(heading_rate, -slew_yaw_max_rads, slew_yaw_max_rads);
682
}
683
684
// update attitude target
685
update_attitude_target();
686
687
// calculate the attitude target euler angles
688
_attitude_target.to_euler(_euler_angle_target);
689
690
// convert thrust vector to a quaternion attitude
691
Quaternion thrust_vec_quat = attitude_from_thrust_vector(thrust_vector, 0.0f);
692
693
// calculate the angle error in x and y.
694
float thrust_vector_diff_angle;
695
Quaternion thrust_vec_correction_quat;
696
Vector3f attitude_error;
697
float returned_thrust_vector_angle;
698
thrust_vector_rotation_angles(thrust_vec_quat, _attitude_target, thrust_vec_correction_quat, attitude_error, returned_thrust_vector_angle, thrust_vector_diff_angle);
699
700
if (_rate_bf_ff_enabled) {
701
// When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing
702
// the output rate towards the input rate.
703
_ang_vel_target.x = input_shaping_angle(attitude_error.x, _input_tc, get_accel_roll_max_radss(), _ang_vel_target.x, _dt);
704
_ang_vel_target.y = input_shaping_angle(attitude_error.y, _input_tc, get_accel_pitch_max_radss(), _ang_vel_target.y, _dt);
705
706
// When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing
707
// the output rate towards the input rate.
708
_ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, heading_rate, get_accel_yaw_max_radss(), _dt, _rate_y_tc);
709
710
// Limit the angular velocity
711
ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));
712
} else {
713
Quaternion yaw_quat;
714
yaw_quat.from_axis_angle(Vector3f{0.0f, 0.0f, heading_rate * _dt});
715
_attitude_target = _attitude_target * thrust_vec_correction_quat * yaw_quat;
716
717
// Set rate feedforward requests to zero
718
_euler_rate_target.zero();
719
_ang_vel_target.zero();
720
}
721
722
// Convert body-frame angular velocity into euler angle derivative of desired attitude
723
ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);
724
725
// Call quaternion attitude controller
726
attitude_controller_run_quat();
727
}
728
729
// Command a thrust vector, heading and heading rate
730
void AC_AttitudeControl::input_thrust_vector_heading(const Vector3f& thrust_vector, float heading_angle_cd, float heading_rate_cds)
731
{
732
// a zero _angle_vel_yaw_max means that setting is disabled
733
const float slew_yaw_max_rads = get_slew_yaw_max_rads();
734
735
// Convert from centidegrees on public interface to radians
736
float heading_rate = constrain_float(radians(heading_rate_cds * 0.01f), -slew_yaw_max_rads, slew_yaw_max_rads);
737
float heading_angle = radians(heading_angle_cd * 0.01f);
738
739
// update attitude target
740
update_attitude_target();
741
742
// calculate the attitude target euler angles
743
_attitude_target.to_euler(_euler_angle_target);
744
745
// convert thrust vector and heading to a quaternion attitude
746
const Quaternion desired_attitude_quat = attitude_from_thrust_vector(thrust_vector, heading_angle);
747
748
if (_rate_bf_ff_enabled) {
749
// calculate the angle error in x and y.
750
Vector3f attitude_error;
751
float thrust_vector_diff_angle;
752
Quaternion thrust_vec_correction_quat;
753
float returned_thrust_vector_angle;
754
thrust_vector_rotation_angles(desired_attitude_quat, _attitude_target, thrust_vec_correction_quat, attitude_error, returned_thrust_vector_angle, thrust_vector_diff_angle);
755
756
// When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing
757
// the output rate towards the input rate.
758
_ang_vel_target.x = input_shaping_angle(attitude_error.x, _input_tc, get_accel_roll_max_radss(), _ang_vel_target.x, _dt);
759
_ang_vel_target.y = input_shaping_angle(attitude_error.y, _input_tc, get_accel_pitch_max_radss(), _ang_vel_target.y, _dt);
760
_ang_vel_target.z = input_shaping_angle(attitude_error.z, _input_tc, get_accel_yaw_max_radss(), _ang_vel_target.z, heading_rate, slew_yaw_max_rads, _dt);
761
762
// Limit the angular velocity
763
ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), slew_yaw_max_rads);
764
} else {
765
// set persisted quaternion target attitude
766
_attitude_target = desired_attitude_quat;
767
768
// Set rate feedforward requests to zero
769
_euler_rate_target.zero();
770
_ang_vel_target.zero();
771
}
772
773
// Convert body-frame angular velocity into euler angle derivative of desired attitude
774
ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);
775
776
// Call quaternion attitude controller
777
attitude_controller_run_quat();
778
}
779
780
// Command a thrust vector and heading rate
781
void AC_AttitudeControl::input_thrust_vector_heading(const Vector3f& thrust_vector, HeadingCommand heading)
782
{
783
switch (heading.heading_mode) {
784
case HeadingMode::Rate_Only:
785
input_thrust_vector_rate_heading(thrust_vector, heading.yaw_rate_cds);
786
break;
787
case HeadingMode::Angle_Only:
788
input_thrust_vector_heading(thrust_vector, heading.yaw_angle_cd, 0.0);
789
break;
790
case HeadingMode::Angle_And_Rate:
791
input_thrust_vector_heading(thrust_vector, heading.yaw_angle_cd, heading.yaw_rate_cds);
792
break;
793
}
794
}
795
796
Quaternion AC_AttitudeControl::attitude_from_thrust_vector(Vector3f thrust_vector, float heading_angle) const
797
{
798
const Vector3f thrust_vector_up{0.0f, 0.0f, -1.0f};
799
800
if (is_zero(thrust_vector.length_squared())) {
801
thrust_vector = thrust_vector_up;
802
} else {
803
thrust_vector.normalize();
804
}
805
806
// the cross product of the desired and target thrust vector defines the rotation vector
807
Vector3f thrust_vec_cross = thrust_vector_up % thrust_vector;
808
809
// the dot product is used to calculate the angle between the target and desired thrust vectors
810
const float thrust_vector_angle = acosf(constrain_float(thrust_vector_up * thrust_vector, -1.0f, 1.0f));
811
812
// Normalize the thrust rotation vector
813
const float thrust_vector_length = thrust_vec_cross.length();
814
if (is_zero(thrust_vector_length) || is_zero(thrust_vector_angle)) {
815
thrust_vec_cross = thrust_vector_up;
816
} else {
817
thrust_vec_cross /= thrust_vector_length;
818
}
819
820
Quaternion thrust_vec_quat;
821
thrust_vec_quat.from_axis_angle(thrust_vec_cross, thrust_vector_angle);
822
Quaternion yaw_quat;
823
yaw_quat.from_axis_angle(Vector3f{0.0f, 0.0f, 1.0f}, heading_angle);
824
return thrust_vec_quat*yaw_quat;
825
}
826
827
// Calculates the body frame angular velocities to follow the target attitude
828
void AC_AttitudeControl::update_attitude_target()
829
{
830
// rotate target and normalize
831
Quaternion attitude_target_update;
832
attitude_target_update.from_axis_angle(_ang_vel_target * _dt);
833
_attitude_target *= attitude_target_update;
834
_attitude_target.normalize();
835
}
836
837
// Calculates the body frame angular velocities to follow the target attitude
838
void AC_AttitudeControl::attitude_controller_run_quat()
839
{
840
// This represents a quaternion rotation in NED frame to the body
841
Quaternion attitude_body;
842
_ahrs.get_quat_body_to_ned(attitude_body);
843
844
// This vector represents the angular error to rotate the thrust vector using x and y and heading using z
845
Vector3f attitude_error;
846
thrust_heading_rotation_angles(_attitude_target, attitude_body, attitude_error, _thrust_angle, _thrust_error_angle);
847
848
// Compute the angular velocity corrections in the body frame from the attitude error
849
Vector3f ang_vel_body = update_ang_vel_target_from_att_error(attitude_error);
850
851
// ensure angular velocity does not go over configured limits
852
ang_vel_limit(ang_vel_body, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));
853
854
// rotation from the target frame to the body frame
855
Quaternion rotation_target_to_body = attitude_body.inverse() * _attitude_target;
856
857
// target angle velocity vector in the body frame
858
Vector3f ang_vel_body_feedforward = rotation_target_to_body * _ang_vel_target;
859
Vector3f gyro = get_latest_gyro();
860
// Correct the thrust vector and smoothly add feedforward and yaw input
861
_feedforward_scalar = 1.0f;
862
if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE * 2.0f) {
863
ang_vel_body.z = gyro.z;
864
} else if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE) {
865
_feedforward_scalar = (1.0f - (_thrust_error_angle - AC_ATTITUDE_THRUST_ERROR_ANGLE) / AC_ATTITUDE_THRUST_ERROR_ANGLE);
866
ang_vel_body.x += ang_vel_body_feedforward.x * _feedforward_scalar;
867
ang_vel_body.y += ang_vel_body_feedforward.y * _feedforward_scalar;
868
ang_vel_body.z += ang_vel_body_feedforward.z;
869
ang_vel_body.z = gyro.z * (1.0 - _feedforward_scalar) + ang_vel_body.z * _feedforward_scalar;
870
} else {
871
ang_vel_body += ang_vel_body_feedforward;
872
}
873
874
// Record error to handle EKF resets
875
_attitude_ang_error = attitude_body.inverse() * _attitude_target;
876
// finally update the attitude target
877
_ang_vel_body = ang_vel_body;
878
}
879
880
// thrust_heading_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion.
881
// The maximum error in the yaw axis is limited based on static output saturation.
882
void AC_AttitudeControl::thrust_heading_rotation_angles(Quaternion& attitude_target, const Quaternion& attitude_body, Vector3f& attitude_error, float& thrust_angle, float& thrust_error_angle) const
883
{
884
Quaternion thrust_vector_correction;
885
thrust_vector_rotation_angles(attitude_target, attitude_body, thrust_vector_correction, attitude_error, thrust_angle, thrust_error_angle);
886
887
// Todo: Limit roll an pitch error based on output saturation and maximum error.
888
889
// Limit Yaw Error based to the maximum that would saturate the output when yaw rate is zero.
890
Quaternion heading_vec_correction_quat;
891
892
float heading_accel_max = constrain_float(get_accel_yaw_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS);
893
if (!is_zero(get_rate_yaw_pid().kP())) {
894
float heading_error_max = MIN(inv_sqrt_controller(1.0 / get_rate_yaw_pid().kP(), _p_angle_yaw.kP(), heading_accel_max), AC_ATTITUDE_YAW_MAX_ERROR_ANGLE);
895
if (!is_zero(_p_angle_yaw.kP()) && fabsf(attitude_error.z) > heading_error_max) {
896
attitude_error.z = constrain_float(wrap_PI(attitude_error.z), -heading_error_max, heading_error_max);
897
heading_vec_correction_quat.from_axis_angle(Vector3f{0.0f, 0.0f, attitude_error.z});
898
attitude_target = attitude_body * thrust_vector_correction * heading_vec_correction_quat;
899
}
900
}
901
}
902
903
// thrust_vector_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion.
904
// The first rotation corrects the thrust vector and the second rotation corrects the heading vector.
905
void AC_AttitudeControl::thrust_vector_rotation_angles(const Quaternion& attitude_target, const Quaternion& attitude_body, Quaternion& thrust_vector_correction, Vector3f& attitude_error, float& thrust_angle, float& thrust_error_angle) const
906
{
907
// The direction of thrust is [0,0,-1] is any body-fixed frame, inc. body frame and target frame.
908
const Vector3f thrust_vector_up{0.0f, 0.0f, -1.0f};
909
910
// attitude_target and attitude_body are passive rotations from target / body frames to the NED frame
911
912
// Rotating [0,0,-1] by attitude_target expresses (gets a view of) the target thrust vector in the inertial frame
913
Vector3f att_target_thrust_vec = attitude_target * thrust_vector_up; // target thrust vector
914
915
// Rotating [0,0,-1] by attitude_target expresses (gets a view of) the current thrust vector in the inertial frame
916
Vector3f att_body_thrust_vec = attitude_body * thrust_vector_up; // current thrust vector
917
918
// the dot product is used to calculate the current lean angle for use of external functions
919
thrust_angle = acosf(constrain_float(thrust_vector_up * att_body_thrust_vec,-1.0f,1.0f));
920
921
// the cross product of the desired and target thrust vector defines the rotation vector
922
Vector3f thrust_vec_cross = att_body_thrust_vec % att_target_thrust_vec;
923
924
// the dot product is used to calculate the angle between the target and desired thrust vectors
925
thrust_error_angle = acosf(constrain_float(att_body_thrust_vec * att_target_thrust_vec, -1.0f, 1.0f));
926
927
// Normalize the thrust rotation vector
928
float thrust_vector_length = thrust_vec_cross.length();
929
if (is_zero(thrust_vector_length) || is_zero(thrust_error_angle)) {
930
thrust_vec_cross = thrust_vector_up;
931
} else {
932
thrust_vec_cross /= thrust_vector_length;
933
}
934
935
// thrust_vector_correction is defined relative to the body frame but its axis `thrust_vec_cross` was computed in
936
// the inertial frame. First rotate it by the inverse of attitude_body to express it back in the body frame
937
thrust_vec_cross = attitude_body.inverse() * thrust_vec_cross;
938
thrust_vector_correction.from_axis_angle(thrust_vec_cross, thrust_error_angle);
939
940
// calculate the angle error in x and y.
941
Vector3f rotation;
942
thrust_vector_correction.to_axis_angle(rotation);
943
attitude_error.x = rotation.x;
944
attitude_error.y = rotation.y;
945
946
// calculate the remaining rotation required after thrust vector is rotated transformed to the body frame
947
// heading_vector_correction
948
Quaternion heading_vec_correction_quat = thrust_vector_correction.inverse() * attitude_body.inverse() * attitude_target;
949
950
// calculate the angle error in z (x and y should be zero here).
951
heading_vec_correction_quat.to_axis_angle(rotation);
952
attitude_error.z = rotation.z;
953
}
954
955
// calculates the velocity correction from an angle error. The angular velocity has acceleration and
956
// deceleration limits including basic jerk limiting using _input_tc
957
float AC_AttitudeControl::input_shaping_angle(float error_angle, float input_tc, float accel_max, float target_ang_vel, float desired_ang_vel, float max_ang_vel, float dt)
958
{
959
// Calculate the velocity as error approaches zero with acceleration limited by accel_max_radss
960
desired_ang_vel += sqrt_controller(error_angle, 1.0f / MAX(input_tc, 0.01f), accel_max, dt);
961
if (is_positive(max_ang_vel)) {
962
desired_ang_vel = constrain_float(desired_ang_vel, -max_ang_vel, max_ang_vel);
963
}
964
965
// Acceleration is limited directly to smooth the beginning of the curve.
966
return input_shaping_ang_vel(target_ang_vel, desired_ang_vel, accel_max, dt, 0.0f);
967
}
968
969
// Shapes the velocity request based on a rate time constant. The angular acceleration and deceleration is limited.
970
float AC_AttitudeControl::input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt, float input_tc)
971
{
972
if (is_positive(input_tc)) {
973
// Calculate the acceleration to smoothly achieve rate. Jerk is not limited.
974
float error_rate = desired_ang_vel - target_ang_vel;
975
float desired_ang_accel = sqrt_controller(error_rate, 1.0f / MAX(input_tc, 0.01f), 0.0f, dt);
976
desired_ang_vel = target_ang_vel + desired_ang_accel * dt;
977
}
978
// Acceleration is limited directly to smooth the beginning of the curve.
979
if (is_positive(accel_max)) {
980
float delta_ang_vel = accel_max * dt;
981
return constrain_float(desired_ang_vel, target_ang_vel - delta_ang_vel, target_ang_vel + delta_ang_vel);
982
} else {
983
return desired_ang_vel;
984
}
985
}
986
987
// calculates the expected angular velocity correction from an angle error based on the AC_AttitudeControl settings.
988
// This function can be used to predict the delay associated with angle requests.
989
void AC_AttitudeControl::input_shaping_rate_predictor(const Vector2f &error_angle, Vector2f& target_ang_vel, float dt) const
990
{
991
if (_rate_bf_ff_enabled) {
992
// translate the roll pitch and yaw acceleration limits to the euler axis
993
target_ang_vel.x = input_shaping_angle(wrap_PI(error_angle.x), _input_tc, get_accel_roll_max_radss(), target_ang_vel.x, dt);
994
target_ang_vel.y = input_shaping_angle(wrap_PI(error_angle.y), _input_tc, get_accel_pitch_max_radss(), target_ang_vel.y, dt);
995
} else {
996
const float angleP_roll = _p_angle_roll.kP() * _angle_P_scale.x;
997
const float angleP_pitch = _p_angle_pitch.kP() * _angle_P_scale.y;
998
target_ang_vel.x = angleP_roll * wrap_PI(error_angle.x);
999
target_ang_vel.y = angleP_pitch * wrap_PI(error_angle.y);
1000
}
1001
// Limit the angular velocity correction
1002
Vector3f ang_vel(target_ang_vel.x, target_ang_vel.y, 0.0f);
1003
ang_vel_limit(ang_vel, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), 0.0f);
1004
1005
target_ang_vel.x = ang_vel.x;
1006
target_ang_vel.y = ang_vel.y;
1007
}
1008
1009
// limits angular velocity
1010
void AC_AttitudeControl::ang_vel_limit(Vector3f& euler_rad, float ang_vel_roll_max, float ang_vel_pitch_max, float ang_vel_yaw_max) const
1011
{
1012
if (is_zero(ang_vel_roll_max) || is_zero(ang_vel_pitch_max)) {
1013
if (!is_zero(ang_vel_roll_max)) {
1014
euler_rad.x = constrain_float(euler_rad.x, -ang_vel_roll_max, ang_vel_roll_max);
1015
}
1016
if (!is_zero(ang_vel_pitch_max)) {
1017
euler_rad.y = constrain_float(euler_rad.y, -ang_vel_pitch_max, ang_vel_pitch_max);
1018
}
1019
} else {
1020
Vector2f thrust_vector_ang_vel(euler_rad.x / ang_vel_roll_max, euler_rad.y / ang_vel_pitch_max);
1021
float thrust_vector_length = thrust_vector_ang_vel.length();
1022
if (thrust_vector_length > 1.0f) {
1023
euler_rad.x = thrust_vector_ang_vel.x * ang_vel_roll_max / thrust_vector_length;
1024
euler_rad.y = thrust_vector_ang_vel.y * ang_vel_pitch_max / thrust_vector_length;
1025
}
1026
}
1027
if (!is_zero(ang_vel_yaw_max)) {
1028
euler_rad.z = constrain_float(euler_rad.z, -ang_vel_yaw_max, ang_vel_yaw_max);
1029
}
1030
}
1031
1032
// translates body frame acceleration limits to the euler axis
1033
Vector3f AC_AttitudeControl::euler_accel_limit(const Quaternion &att, const Vector3f &euler_accel)
1034
{
1035
if (!is_positive(euler_accel.x) || !is_positive(euler_accel.y) || !is_positive(euler_accel.z)) {
1036
return Vector3f { euler_accel };
1037
}
1038
1039
const float phi = att.get_euler_roll();
1040
const float theta = att.get_euler_pitch();
1041
1042
const float sin_phi = constrain_float(fabsf(sinf(phi)), 0.1f, 1.0f);
1043
const float cos_phi = constrain_float(fabsf(cosf(phi)), 0.1f, 1.0f);
1044
const float sin_theta = constrain_float(fabsf(sinf(theta)), 0.1f, 1.0f);
1045
const float cos_theta = constrain_float(fabsf(cosf(theta)), 0.1f, 1.0f);
1046
1047
return Vector3f {
1048
euler_accel.x,
1049
MIN(euler_accel.y / cos_phi, euler_accel.z / sin_phi),
1050
MIN(MIN(euler_accel.x / sin_theta, euler_accel.y / (sin_phi * cos_theta)), euler_accel.z / (cos_phi * cos_theta))
1051
};
1052
}
1053
1054
// Sets attitude target to vehicle attitude and sets all rates to zero
1055
// If reset_rate is false rates are not reset to allow the rate controllers to run
1056
void AC_AttitudeControl::reset_target_and_rate(bool reset_rate)
1057
{
1058
// move attitude target to current attitude
1059
_ahrs.get_quat_body_to_ned(_attitude_target);
1060
_attitude_target.to_euler(_euler_angle_target);
1061
1062
if (reset_rate) {
1063
_ang_vel_target.zero();
1064
_euler_rate_target.zero();
1065
}
1066
}
1067
1068
// Sets yaw target to vehicle heading and sets yaw rate to zero
1069
// If reset_rate is false rates are not reset to allow the rate controllers to run
1070
void AC_AttitudeControl::reset_yaw_target_and_rate(bool reset_rate)
1071
{
1072
// move attitude target to current heading
1073
float yaw_shift = _ahrs.yaw - _euler_angle_target.z;
1074
Quaternion _attitude_target_update;
1075
_attitude_target_update.from_axis_angle(Vector3f{0.0f, 0.0f, yaw_shift});
1076
_attitude_target = _attitude_target_update * _attitude_target;
1077
1078
if (reset_rate) {
1079
// set yaw rate to zero
1080
_euler_rate_target.z = 0.0f;
1081
1082
// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
1083
euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target);
1084
}
1085
}
1086
1087
// Shifts the target attitude to maintain the current error in the event of an EKF reset
1088
void AC_AttitudeControl::inertial_frame_reset()
1089
{
1090
// Retrieve quaternion body attitude
1091
Quaternion attitude_body;
1092
_ahrs.get_quat_body_to_ned(attitude_body);
1093
1094
// Recalculate the target quaternion
1095
_attitude_target = attitude_body * _attitude_ang_error;
1096
1097
// calculate the attitude target euler angles
1098
_attitude_target.to_euler(_euler_angle_target);
1099
}
1100
1101
// Convert a 321-intrinsic euler angle derivative to an angular velocity vector
1102
void AC_AttitudeControl::euler_rate_to_ang_vel(const Quaternion& att, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads)
1103
{
1104
const float theta = att.get_euler_pitch();
1105
const float phi = att.get_euler_roll();
1106
1107
const float sin_theta = sinf(theta);
1108
const float cos_theta = cosf(theta);
1109
const float sin_phi = sinf(phi);
1110
const float cos_phi = cosf(phi);
1111
1112
ang_vel_rads.x = euler_rate_rads.x - sin_theta * euler_rate_rads.z;
1113
ang_vel_rads.y = cos_phi * euler_rate_rads.y + sin_phi * cos_theta * euler_rate_rads.z;
1114
ang_vel_rads.z = -sin_phi * euler_rate_rads.y + cos_theta * cos_phi * euler_rate_rads.z;
1115
}
1116
1117
// Convert an angular velocity vector to a 321-intrinsic euler angle derivative
1118
// Returns false if the vehicle is pitched 90 degrees up or down
1119
bool AC_AttitudeControl::ang_vel_to_euler_rate(const Quaternion& att, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads)
1120
{
1121
const float theta = att.get_euler_pitch();
1122
const float phi = att.get_euler_roll();
1123
1124
const float sin_theta = sinf(theta);
1125
const float cos_theta = cosf(theta);
1126
const float sin_phi = sinf(phi);
1127
const float cos_phi = cosf(phi);
1128
1129
// When the vehicle pitches all the way up or all the way down, the euler angles become discontinuous. In this case, we just return false.
1130
if (is_zero(cos_theta)) {
1131
return false;
1132
}
1133
1134
euler_rate_rads.x = ang_vel_rads.x + sin_phi * (sin_theta / cos_theta) * ang_vel_rads.y + cos_phi * (sin_theta / cos_theta) * ang_vel_rads.z;
1135
euler_rate_rads.y = cos_phi * ang_vel_rads.y - sin_phi * ang_vel_rads.z;
1136
euler_rate_rads.z = (sin_phi / cos_theta) * ang_vel_rads.y + (cos_phi / cos_theta) * ang_vel_rads.z;
1137
return true;
1138
}
1139
1140
// Update rate_target_ang_vel using attitude_error_rot_vec_rad
1141
Vector3f AC_AttitudeControl::update_ang_vel_target_from_att_error(const Vector3f &attitude_error_rot_vec_rad)
1142
{
1143
Vector3f rate_target_ang_vel;
1144
1145
// Compute the roll angular velocity demand from the roll angle error
1146
const float angleP_roll = _p_angle_roll.kP() * _angle_P_scale.x;
1147
if (_use_sqrt_controller && !is_zero(get_accel_roll_max_radss())) {
1148
rate_target_ang_vel.x = sqrt_controller(attitude_error_rot_vec_rad.x, angleP_roll, constrain_float(get_accel_roll_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS), _dt);
1149
} else {
1150
rate_target_ang_vel.x = angleP_roll * attitude_error_rot_vec_rad.x;
1151
}
1152
1153
// Compute the pitch angular velocity demand from the pitch angle error
1154
const float angleP_pitch = _p_angle_pitch.kP() * _angle_P_scale.y;
1155
if (_use_sqrt_controller && !is_zero(get_accel_pitch_max_radss())) {
1156
rate_target_ang_vel.y = sqrt_controller(attitude_error_rot_vec_rad.y, angleP_pitch, constrain_float(get_accel_pitch_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS), _dt);
1157
} else {
1158
rate_target_ang_vel.y = angleP_pitch * attitude_error_rot_vec_rad.y;
1159
}
1160
1161
// Compute the yaw angular velocity demand from the yaw angle error
1162
const float angleP_yaw = _p_angle_yaw.kP() * _angle_P_scale.z;
1163
if (_use_sqrt_controller && !is_zero(get_accel_yaw_max_radss())) {
1164
rate_target_ang_vel.z = sqrt_controller(attitude_error_rot_vec_rad.z, angleP_yaw, constrain_float(get_accel_yaw_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS), _dt);
1165
} else {
1166
rate_target_ang_vel.z = angleP_yaw * attitude_error_rot_vec_rad.z;
1167
}
1168
1169
// reset angle P scaling, saving used value
1170
_angle_P_scale_used = _angle_P_scale;
1171
_angle_P_scale = VECTORF_111;
1172
1173
return rate_target_ang_vel;
1174
}
1175
1176
// Enable or disable body-frame feed forward
1177
void AC_AttitudeControl::accel_limiting(bool enable_limits)
1178
{
1179
if (enable_limits) {
1180
// If enabling limits, reload from eeprom or set to defaults
1181
if (is_zero(_accel_roll_max)) {
1182
_accel_roll_max.load();
1183
}
1184
if (is_zero(_accel_pitch_max)) {
1185
_accel_pitch_max.load();
1186
}
1187
if (is_zero(_accel_yaw_max)) {
1188
_accel_yaw_max.load();
1189
}
1190
} else {
1191
_accel_roll_max.set(0.0f);
1192
_accel_pitch_max.set(0.0f);
1193
_accel_yaw_max.set(0.0f);
1194
}
1195
}
1196
1197
// Return tilt angle limit for pilot input that prioritises altitude hold over lean angle
1198
float AC_AttitudeControl::get_althold_lean_angle_max_cd() const
1199
{
1200
// convert to centi-degrees for public interface
1201
return MAX(ToDeg(_althold_lean_angle_max), AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN) * 100.0f;
1202
}
1203
1204
// Return roll rate step size in centidegrees/s that results in maximum output after 4 time steps
1205
float AC_AttitudeControl::max_rate_step_bf_roll()
1206
{
1207
float dt_average = AP::scheduler().get_filtered_loop_time();
1208
float alpha = MIN(get_rate_roll_pid().get_filt_E_alpha(dt_average), get_rate_roll_pid().get_filt_D_alpha(dt_average));
1209
float alpha_remaining = 1 - alpha;
1210
// todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max
1211
float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);
1212
float rate_max = 2.0f * throttle_hover * AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX / ((alpha_remaining * alpha_remaining * alpha_remaining * alpha * get_rate_roll_pid().kD()) / _dt + get_rate_roll_pid().kP());
1213
if (is_positive(_ang_vel_roll_max)) {
1214
rate_max = MIN(rate_max, get_ang_vel_roll_max_rads());
1215
}
1216
return rate_max;
1217
}
1218
1219
// Return pitch rate step size in centidegrees/s that results in maximum output after 4 time steps
1220
float AC_AttitudeControl::max_rate_step_bf_pitch()
1221
{
1222
float dt_average = AP::scheduler().get_filtered_loop_time();
1223
float alpha = MIN(get_rate_pitch_pid().get_filt_E_alpha(dt_average), get_rate_pitch_pid().get_filt_D_alpha(dt_average));
1224
float alpha_remaining = 1 - alpha;
1225
// todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max
1226
float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);
1227
float rate_max = 2.0f * throttle_hover * AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX / ((alpha_remaining * alpha_remaining * alpha_remaining * alpha * get_rate_pitch_pid().kD()) / _dt + get_rate_pitch_pid().kP());
1228
if (is_positive(_ang_vel_pitch_max)) {
1229
rate_max = MIN(rate_max, get_ang_vel_pitch_max_rads());
1230
}
1231
return rate_max;
1232
}
1233
1234
// Return yaw rate step size in centidegrees/s that results in maximum output after 4 time steps
1235
float AC_AttitudeControl::max_rate_step_bf_yaw()
1236
{
1237
float dt_average = AP::scheduler().get_filtered_loop_time();
1238
float alpha = MIN(get_rate_yaw_pid().get_filt_E_alpha(dt_average), get_rate_yaw_pid().get_filt_D_alpha(dt_average));
1239
float alpha_remaining = 1 - alpha;
1240
// todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max
1241
float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);
1242
float rate_max = 2.0f * throttle_hover * AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX / ((alpha_remaining * alpha_remaining * alpha_remaining * alpha * get_rate_yaw_pid().kD()) / _dt + get_rate_yaw_pid().kP());
1243
if (is_positive(_ang_vel_yaw_max)) {
1244
rate_max = MIN(rate_max, get_ang_vel_yaw_max_rads());
1245
}
1246
return rate_max;
1247
}
1248
1249
bool AC_AttitudeControl::pre_arm_checks(const char *param_prefix,
1250
char *failure_msg,
1251
const uint8_t failure_msg_len)
1252
{
1253
// validate AC_P members:
1254
const struct {
1255
const char *pid_name;
1256
AC_P &p;
1257
} ps[] = {
1258
{ "ANG_PIT", get_angle_pitch_p() },
1259
{ "ANG_RLL", get_angle_roll_p() },
1260
{ "ANG_YAW", get_angle_yaw_p() }
1261
};
1262
for (uint8_t i=0; i<ARRAY_SIZE(ps); i++) {
1263
// all AC_P's must have a positive P value:
1264
if (!is_positive(ps[i].p.kP())) {
1265
hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, ps[i].pid_name);
1266
return false;
1267
}
1268
}
1269
1270
// validate AC_PID members:
1271
const struct {
1272
const char *pid_name;
1273
AC_PID &pid;
1274
} pids[] = {
1275
{ "RAT_RLL", get_rate_roll_pid() },
1276
{ "RAT_PIT", get_rate_pitch_pid() },
1277
{ "RAT_YAW", get_rate_yaw_pid() },
1278
};
1279
for (uint8_t i=0; i<ARRAY_SIZE(pids); i++) {
1280
// if the PID has a positive FF then we just ensure kP and
1281
// kI aren't negative
1282
AC_PID &pid = pids[i].pid;
1283
const char *pid_name = pids[i].pid_name;
1284
if (is_positive(pid.ff())) {
1285
// kP and kI must be non-negative:
1286
if (is_negative(pid.kP())) {
1287
hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be >= 0", param_prefix, pid_name);
1288
return false;
1289
}
1290
if (is_negative(pid.kI())) {
1291
hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_I must be >= 0", param_prefix, pid_name);
1292
return false;
1293
}
1294
} else {
1295
// kP and kI must be positive:
1296
if (!is_positive(pid.kP())) {
1297
hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, pid_name);
1298
return false;
1299
}
1300
if (!is_positive(pid.kI())) {
1301
hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_I must be > 0", param_prefix, pid_name);
1302
return false;
1303
}
1304
}
1305
// never allow a negative D term (but zero is allowed)
1306
if (is_negative(pid.kD())) {
1307
hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_D must be >= 0", param_prefix, pid_name);
1308
return false;
1309
}
1310
}
1311
return true;
1312
}
1313
1314
/*
1315
get the slew rate for roll, pitch and yaw, for oscillation
1316
detection in lua scripts
1317
*/
1318
void AC_AttitudeControl::get_rpy_srate(float &roll_srate, float &pitch_srate, float &yaw_srate)
1319
{
1320
roll_srate = get_rate_roll_pid().get_pid_info().slew_rate;
1321
pitch_srate = get_rate_pitch_pid().get_pid_info().slew_rate;
1322
yaw_srate = get_rate_yaw_pid().get_pid_info().slew_rate;
1323
}
1324
1325