Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp
9381 views
1
#include "AC_AttitudeControl.h"
2
#include <AP_HAL/AP_HAL.h>
3
#include <AP_Vehicle/AP_Vehicle.h>
4
#include <AP_Scheduler/AP_Scheduler.h>
5
#include <AP_Vehicle/AP_Vehicle_Type.h>
6
7
extern const AP_HAL::HAL& hal;
8
9
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
10
// default gains for Plane
11
# define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.2f // Soft
12
#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 5.0 // Min lean angle so that vehicle can maintain limited control
13
#define AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL 0
14
#else
15
// default gains for Copter and Sub
16
# define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.15f // Medium
17
#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 10.0 // Min lean angle so that vehicle can maintain limited control
18
#define AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL 1
19
#endif
20
21
// lean angle max (in degrees) for all vehicles
22
#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MAX 80.0 // lean angle max in degrees
23
24
// default angle max for all vehicles
25
#ifndef AC_ATTITUDE_CONTROL_ANGLE_MAX_DEFAULT
26
# define AC_ATTITUDE_CONTROL_ANGLE_MAX_DEFAULT 30.0f // default max lean angle in degrees
27
#endif
28
29
AC_AttitudeControl *AC_AttitudeControl::_singleton;
30
31
// table of user settable parameters
32
const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
33
34
// 0, 1 were RATE_RP_MAX, RATE_Y_MAX
35
36
// @Param: SLEW_YAW
37
// @DisplayName: Yaw target slew rate
38
// @Description: Maximum rate the yaw target can be updated in RTL and Auto flight modes
39
// @Units: cdeg/s
40
// @Range: 500 18000
41
// @Increment: 100
42
// @User: Advanced
43
AP_GROUPINFO("SLEW_YAW", 2, AC_AttitudeControl, _slew_yaw_cds, AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT_CDS),
44
45
// 3 was for ACCEL_RP_MAX
46
47
// @Param: ACCEL_Y_MAX
48
// @DisplayName: Acceleration Max for Yaw
49
// @Description: Maximum acceleration in yaw axis
50
// @Units: cdeg/s/s
51
// @Range: 0 72000
52
// @Values: 0:Disabled, 9000:VerySlow, 18000:Slow, 36000:Medium, 54000:Fast
53
// @Increment: 1000
54
// @User: Advanced
55
AP_GROUPINFO("ACCEL_Y_MAX", 4, AC_AttitudeControl, _accel_yaw_max_cdss, AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS),
56
57
// @Param: RATE_FF_ENAB
58
// @DisplayName: Rate Feedforward Enable
59
// @Description: Controls whether body-frame rate feedforward is enabled or disabled
60
// @Values: 0:Disabled, 1:Enabled
61
// @User: Advanced
62
AP_GROUPINFO("RATE_FF_ENAB", 5, AC_AttitudeControl, _rate_bf_ff_enabled, AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT),
63
64
// @Param: ACCEL_R_MAX
65
// @DisplayName: Acceleration Max for Roll
66
// @Description: Maximum acceleration in roll axis
67
// @Units: cdeg/s/s
68
// @Range: 0 180000
69
// @Increment: 1000
70
// @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast
71
// @User: Advanced
72
AP_GROUPINFO("ACCEL_R_MAX", 6, AC_AttitudeControl, _accel_roll_max_cdss, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS),
73
74
// @Param: ACCEL_P_MAX
75
// @DisplayName: Acceleration Max for Pitch
76
// @Description: Maximum acceleration in pitch axis
77
// @Units: cdeg/s/s
78
// @Range: 0 180000
79
// @Increment: 1000
80
// @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast
81
// @User: Advanced
82
AP_GROUPINFO("ACCEL_P_MAX", 7, AC_AttitudeControl, _accel_pitch_max_cdss, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS),
83
84
// IDs 8,9,10,11 RESERVED (in use on Solo)
85
86
// @Param: ANGLE_BOOST
87
// @DisplayName: Angle Boost
88
// @Description: Angle Boost increases output throttle as the vehicle leans to reduce loss of altitude
89
// @Values: 0:Disabled, 1:Enabled
90
// @User: Advanced
91
AP_GROUPINFO("ANGLE_BOOST", 12, AC_AttitudeControl, _angle_boost_enabled, 1),
92
93
// @Param: ANG_RLL_P
94
// @DisplayName: Roll axis angle controller P gain
95
// @Description: Roll axis angle controller P gain. Converts the error between the desired roll angle and actual angle to a desired roll rate
96
// @Range: 3.000 12.000
97
// @Range{Sub}: 0.0 12.000
98
// @Increment: 0.01
99
// @User: Standard
100
AP_SUBGROUPINFO(_p_angle_roll, "ANG_RLL_", 13, AC_AttitudeControl, AC_P),
101
102
// @Param: ANG_PIT_P
103
// @DisplayName: Pitch axis angle controller P gain
104
// @Description: Pitch axis angle controller P gain. Converts the error between the desired pitch angle and actual angle to a desired pitch rate
105
// @Range: 3.000 12.000
106
// @Range{Sub}: 0.0 12.000
107
// @Increment: 0.01
108
// @User: Standard
109
AP_SUBGROUPINFO(_p_angle_pitch, "ANG_PIT_", 14, AC_AttitudeControl, AC_P),
110
111
// @Param: ANG_YAW_P
112
// @DisplayName: Yaw axis angle controller P gain
113
// @Description: Yaw axis angle controller P gain. Converts the error between the desired yaw angle and actual angle to a desired yaw rate
114
// @Range: 3.000 12.000
115
// @Range{Sub}: 0.0 6.000
116
// @Increment: 0.01
117
// @User: Standard
118
AP_SUBGROUPINFO(_p_angle_yaw, "ANG_YAW_", 15, AC_AttitudeControl, AC_P),
119
120
// @Param: ANG_LIM_TC
121
// @DisplayName: Angle Limit (to maintain altitude) Time Constant
122
// @Description: Angle Limit (to maintain altitude) Time Constant
123
// @Range: 0.5 10.0
124
// @User: Advanced
125
AP_GROUPINFO("ANG_LIM_TC", 16, AC_AttitudeControl, _angle_limit_tc, AC_ATTITUDE_CONTROL_ANGLE_LIMIT_TC_DEFAULT),
126
127
// @Param: RATE_R_MAX
128
// @DisplayName: Angular Velocity Max for Roll
129
// @Description: Maximum angular velocity in roll axis
130
// @Units: deg/s
131
// @Range: 0 1080
132
// @Increment: 1
133
// @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast
134
// @User: Advanced
135
AP_GROUPINFO("RATE_R_MAX", 17, AC_AttitudeControl, _ang_vel_roll_max_degs, 0.0f),
136
137
// @Param: RATE_P_MAX
138
// @DisplayName: Angular Velocity Max for Pitch
139
// @Description: Maximum angular velocity in pitch axis
140
// @Units: deg/s
141
// @Range: 0 1080
142
// @Increment: 1
143
// @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast
144
// @User: Advanced
145
AP_GROUPINFO("RATE_P_MAX", 18, AC_AttitudeControl, _ang_vel_pitch_max_degs, 0.0f),
146
147
// @Param: RATE_Y_MAX
148
// @DisplayName: Angular Velocity Max for Yaw
149
// @Description: Maximum angular velocity in yaw axis
150
// @Units: deg/s
151
// @Range: 0 1080
152
// @Increment: 1
153
// @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast
154
// @User: Advanced
155
AP_GROUPINFO("RATE_Y_MAX", 19, AC_AttitudeControl, _ang_vel_yaw_max_degs, 0.0f),
156
157
// @Param: INPUT_TC
158
// @DisplayName: Attitude control input time constant
159
// @Description: Attitude control input time constant. Low numbers lead to sharper response, higher numbers to softer response
160
// @Units: s
161
// @Range: 0 1
162
// @Increment: 0.01
163
// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
164
// @User: Standard
165
AP_GROUPINFO("INPUT_TC", 20, AC_AttitudeControl, _input_tc, AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT),
166
167
// @Param: LAND_R_MULT
168
// @DisplayName: Landed roll gain multiplier
169
// @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.
170
// @Range: 0.25 1.0
171
// @User: Advanced
172
AP_GROUPINFO("LAND_R_MULT", 21, AC_AttitudeControl, _land_roll_mult, 1.0),
173
174
// @Param: LAND_P_MULT
175
// @DisplayName: Landed pitch gain multiplier
176
// @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.
177
// @Range: 0.25 1.0
178
// @User: Advanced
179
AP_GROUPINFO("LAND_P_MULT", 22, AC_AttitudeControl, _land_pitch_mult, 1.0),
180
181
// @Param: LAND_Y_MULT
182
// @DisplayName: Landed yaw gain multiplier
183
// @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.
184
// @Range: 0.25 1.0
185
// @User: Advanced
186
AP_GROUPINFO("LAND_Y_MULT", 23, AC_AttitudeControl, _land_yaw_mult, 1.0),
187
188
// @Param: ANGLE_MAX
189
// @DisplayName: Angle Max
190
// @Description: Maximum lean angle in all flight modes
191
// @Units: deg
192
// @Increment: 0.1
193
// @Range: 10.0 80.0
194
// @User: Standard
195
AP_GROUPINFO("ANGLE_MAX", 24, AC_AttitudeControl, _angle_max_deg, AC_ATTITUDE_CONTROL_ANGLE_MAX_DEFAULT),
196
197
AP_GROUPEND
198
};
199
200
constexpr Vector3f AC_AttitudeControl::VECTORF_111;
201
202
// get the slew yaw rate limit in rad/s
203
float AC_AttitudeControl::get_slew_yaw_max_rads() const
204
{
205
if (!is_positive(_ang_vel_yaw_max_degs)) {
206
return cd_to_rad(_slew_yaw_cds);
207
}
208
return MIN(radians(_ang_vel_yaw_max_degs), cd_to_rad(_slew_yaw_cds));
209
}
210
211
// get the latest gyro for the purposes of attitude control
212
// Counter-inuitively the lowest latency for rate control is achieved by running rate control
213
// *before* attitude control. This is because you want rate control to run as close as possible
214
// to the time that a gyro sample was read to minimise jitter and control errors. Running rate
215
// control after attitude control might makes sense logically, but the overhead of attitude
216
// control calculations (and other updates) compromises the actual rate control.
217
//
218
// In the case of running rate control in a separate thread, the ordering between rate and attitude
219
// updates is less important, except that gyro sample used should be the latest
220
//
221
// Currently quadplane runs rate control after attitude control, necessitating the following code
222
// to minimise latency.
223
// However this code can be removed once quadplane updates it's structure to run the rate loops before
224
// the Attitude controller.
225
const Vector3f AC_AttitudeControl::get_latest_gyro() const
226
{
227
#if AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL
228
// rate updates happen before attitude updates so the last gyro value is the last rate gyro value
229
// this also allows a separate rate thread to be the source of gyro data
230
return _rate_gyro_rads;
231
#else
232
// rate updates happen after attitude updates so the AHRS must be consulted for the last gyro value
233
return _ahrs.get_gyro_latest();
234
#endif
235
}
236
237
// Ensure attitude controller have zero errors to relax rate controller output
238
void AC_AttitudeControl::relax_attitude_controllers()
239
{
240
// take a copy of the last gyro used by the rate controller before using it
241
Vector3f gyro = get_latest_gyro();
242
// Initialize the attitude variables to the current attitude
243
_ahrs.get_quat_body_to_ned(_attitude_target);
244
_attitude_target.to_euler(_euler_angle_target_rad);
245
_attitude_ang_error.initialise();
246
247
// Initialize the angular rate variables to the current rate
248
_ang_vel_target_rads = gyro;
249
body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);
250
251
// Initialize remaining variables
252
_thrust_error_angle_rad = 0.0f;
253
254
// Reset the PID filters
255
get_rate_roll_pid().reset_filter();
256
get_rate_pitch_pid().reset_filter();
257
get_rate_yaw_pid().reset_filter();
258
259
// Reset the I terms
260
reset_rate_controller_I_terms();
261
// finally update the attitude target
262
_ang_vel_body_rads = gyro;
263
}
264
265
void AC_AttitudeControl::reset_rate_controller_I_terms()
266
{
267
get_rate_roll_pid().reset_I();
268
get_rate_pitch_pid().reset_I();
269
get_rate_yaw_pid().reset_I();
270
}
271
272
// reset rate controller I terms smoothly to zero in 0.5 seconds
273
void AC_AttitudeControl::reset_rate_controller_I_terms_smoothly()
274
{
275
get_rate_roll_pid().relax_integrator(0.0, _dt_s, AC_ATTITUDE_RATE_RELAX_TC);
276
get_rate_pitch_pid().relax_integrator(0.0, _dt_s, AC_ATTITUDE_RATE_RELAX_TC);
277
get_rate_yaw_pid().relax_integrator(0.0, _dt_s, AC_ATTITUDE_RATE_RELAX_TC);
278
}
279
280
// Reduce attitude control gains while landed to stop ground resonance
281
void AC_AttitudeControl::landed_gain_reduction(bool landed)
282
{
283
if (is_positive(_input_tc)) {
284
// use 2.0 x tc to match the response time to 86% commanded
285
const float spool_step = _dt_s / (2.0 * _input_tc);
286
if (landed) {
287
_landed_gain_ratio = MIN(1.0, _landed_gain_ratio + spool_step);
288
} else {
289
_landed_gain_ratio = MAX(0.0, _landed_gain_ratio - spool_step);
290
}
291
} else {
292
_landed_gain_ratio = landed ? 1.0 : 0.0;
293
}
294
Vector3f scale_mult = VECTORF_111 * (1.0 - _landed_gain_ratio) + Vector3f{_land_roll_mult, _land_pitch_mult, _land_yaw_mult} * _landed_gain_ratio;
295
set_PD_scale_mult(scale_mult);
296
set_angle_P_scale_mult(scale_mult);
297
}
298
299
// The attitude controller works around the concept of the desired attitude, target attitude
300
// and measured attitude. The desired attitude is the attitude input into the attitude controller
301
// that expresses where the higher level code would like the aircraft to move to. The target attitude is moved
302
// to the desired attitude with jerk, acceleration, and velocity limits. The target angular velocities are fed
303
// directly into the rate controllers. The angular error between the measured attitude and the target attitude is
304
// fed into the angle controller and the output of the angle controller summed at the input of the rate controllers.
305
// By feeding the target angular velocity directly into the rate controllers the measured and target attitudes
306
// remain very close together.
307
//
308
// All input functions below follow the same procedure
309
// 1. define the desired attitude or attitude change based on the input variables
310
// 2. update the target attitude based on the angular velocity target and the time since the last loop
311
// 3. using the desired attitude and input variables, define the target angular velocity so that it should
312
// move the target attitude towards the desired attitude
313
// 4. if _rate_bf_ff_enabled is not being used then make the target attitude
314
// and target angular velocities equal to the desired attitude and desired angular velocities.
315
// 5. ensure _attitude_target, _euler_angle_target_rad, _euler_rate_target_rads and
316
// _ang_vel_target_rads have been defined. This ensures input modes can be changed without discontinuity.
317
// 6. attitude_controller_run_quat is then run to pass the target angular velocities to the rate controllers and
318
// integrate them into the target attitude. Any errors between the target attitude and the measured attitude are
319
// corrected by first correcting the thrust vector until the angle between the target thrust vector measured
320
// trust vector drops below 2*AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD. At this point the heading is also corrected.
321
322
// Sets an attitude target using a quaternion and a body-frame angular velocity input (rad/s).
323
// The desired quaternion is incrementally advanced each timestep using the (limited) angular velocity input.
324
// If body-frame rate feedforward shaping is enabled, rate/accel targets are generated with acceleration limits
325
// and input time constants; otherwise the targets are set directly.
326
void AC_AttitudeControl::input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_body_rads)
327
{
328
// Update internal attitude target state
329
update_attitude_target();
330
331
// Limit the body-frame angular velocity input
332
ang_vel_limit(ang_vel_body_rads, radians(_ang_vel_roll_max_degs), radians(_ang_vel_pitch_max_degs), radians(_ang_vel_yaw_max_degs));
333
334
// Convert the limited body-frame angular velocity input into the frame used for quaternion integration
335
Vector3f ang_vel_target = attitude_desired_quat * ang_vel_body_rads;
336
337
if (_rate_bf_ff_enabled) {
338
// Compute attitude error (target -> desired) and express as a small-axis-angle vector
339
Quaternion attitude_error_quat = _attitude_target.inverse() * attitude_desired_quat;
340
Vector3f attitude_error_angle;
341
attitude_error_quat.to_axis_angle(attitude_error_angle);
342
343
// Shape the attitude error into angular velocity and acceleration targets with configured
344
// rate and acceleration limits and time constants (roll/pitch use _input_tc, yaw uses _rate_y_tc).
345
attitude_command_model(wrap_PI(attitude_error_angle.x), 0.0, _ang_vel_target_rads.x, _ang_accel_target_rads.x, radians(_ang_vel_roll_max_degs), get_accel_roll_max_radss(), _input_tc, _dt_s);
346
attitude_command_model(wrap_PI(attitude_error_angle.y), 0.0, _ang_vel_target_rads.y, _ang_accel_target_rads.y, radians(_ang_vel_pitch_max_degs), get_accel_pitch_max_radss(), _input_tc, _dt_s);
347
attitude_command_model(wrap_PI(attitude_error_angle.z), 0.0, _ang_vel_target_rads.z, _ang_accel_target_rads.z, radians(_ang_vel_yaw_max_degs), get_accel_yaw_max_radss(), _rate_y_tc, _dt_s);
348
} else {
349
// No shaping: directly set attitude and angular velocity targets
350
_attitude_target = attitude_desired_quat;
351
_ang_vel_target_rads = ang_vel_target;
352
}
353
354
// Update stored Euler-angle representation of the attitude target
355
_attitude_target.to_euler(_euler_angle_target_rad);
356
357
// Convert body-frame angular velocity into euler angle derivative of desired attitude
358
body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);
359
360
// Incrementally advance the desired quaternion using the (limited) angular velocity input
361
Quaternion attitude_desired_update;
362
attitude_desired_update.from_axis_angle(ang_vel_target * _dt_s);
363
attitude_desired_quat = attitude_desired_quat * attitude_desired_update;
364
attitude_desired_quat.normalize();
365
366
// Run quaternion attitude controller
367
attitude_controller_run_quat();
368
}
369
370
// Sets the desired roll and pitch angles (in centidegrees) and yaw rate (in centidegrees/s).
371
// See input_euler_angle_roll_pitch_euler_rate_yaw_rad() for full details.
372
void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw_cd(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)
373
{
374
// Convert from centidegrees on public interface to radians
375
const float euler_roll_angle_rad = cd_to_rad(euler_roll_angle_cd);
376
const float euler_pitch_angle_rad = cd_to_rad(euler_pitch_angle_cd);
377
const float euler_yaw_rate_rads = cd_to_rad(euler_yaw_rate_cds);
378
input_euler_angle_roll_pitch_euler_rate_yaw_rad(euler_roll_angle_rad, euler_pitch_angle_rad, euler_yaw_rate_rads);
379
}
380
381
// Sets the desired roll and pitch angle inputs (radians) and a yaw rate input (radians/s).
382
// Used when roll/pitch stabilization is required while yaw is controlled as a rate.
383
// If body-frame rate feedforward shaping is enabled, shapes Euler rate/acceleration targets
384
// with configured limits and time constants and converts them back to body-frame targets.
385
// Otherwise, updates the attitude target directly and zeros rate/accel feedforward targets.
386
void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw_rad(float euler_roll_angle_rad, float euler_pitch_angle_rad, float euler_yaw_rate_rads)
387
{
388
// update attitude target
389
update_attitude_target();
390
391
// calculate the attitude target euler angles
392
_attitude_target.to_euler(_euler_angle_target_rad);
393
394
// Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)
395
euler_roll_angle_rad += get_roll_trim_rad();
396
397
if (_rate_bf_ff_enabled) {
398
// Convert body-frame angular acceleration limits (roll, pitch, yaw) into equivalent
399
// Euler-angle acceleration limits for the current attitude target.
400
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()});
401
const Vector3f euler_rate_max_rads = euler_accel_limit(_attitude_target, Vector3f{radians(_ang_vel_roll_max_degs), radians(_ang_vel_pitch_max_degs), radians(_ang_vel_yaw_max_degs)});
402
403
// Convert the body-frame angular acceleration target into an equivalent Euler-angle
404
// acceleration target for the current attitude target.
405
Vector3f euler_accel_target_rads;
406
body_to_euler_derivative(_attitude_target, _ang_accel_target_rads, euler_accel_target_rads);
407
408
// Shape Euler roll/pitch angle error into Euler rate/acceleration targets.
409
// The shaper applies Euler rate/acceleration limits and the configured input time constant.
410
attitude_command_model(wrap_PI(euler_roll_angle_rad - _euler_angle_target_rad.x), 0.0, _euler_rate_target_rads.x, euler_accel_target_rads.x, fabsf(euler_rate_max_rads.x), euler_accel.x, _input_tc, _dt_s);
411
attitude_command_model(wrap_PI(euler_pitch_angle_rad - _euler_angle_target_rad.y), 0.0, _euler_rate_target_rads.y, euler_accel_target_rads.y, fabsf(euler_rate_max_rads.y), euler_accel.y, _input_tc, _dt_s);
412
413
// Shape yaw rate input into Euler yaw rate/acceleration targets, applying the configured yaw rate time constant
414
// and limiting Euler acceleration about the yaw axis.
415
attitude_command_model(0.0, euler_yaw_rate_rads, _euler_rate_target_rads.z, euler_accel_target_rads.z, fabsf(euler_rate_max_rads.z), euler_accel.z, _rate_y_tc, _dt_s);
416
417
// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
418
euler_derivative_to_body(_attitude_target, _euler_rate_target_rads, _ang_vel_target_rads);
419
420
// Convert euler angle derivative of desired attitude into a body-frame angular acceleration vector for feedforward
421
euler_derivative_to_body(_attitude_target, euler_accel_target_rads, _ang_accel_target_rads);
422
} else {
423
// No shaping/feedforward: directly update roll/pitch attitude targets and integrate yaw target from yaw rate.
424
_euler_angle_target_rad.x = euler_roll_angle_rad;
425
_euler_angle_target_rad.y = euler_pitch_angle_rad;
426
_euler_angle_target_rad.z += euler_yaw_rate_rads * _dt_s;
427
428
// Compute quaternion target attitude
429
_attitude_target.from_euler(_euler_angle_target_rad.x, _euler_angle_target_rad.y, _euler_angle_target_rad.z);
430
431
// Zero rate and acceleration feedforward targets
432
_euler_rate_target_rads.zero();
433
_ang_vel_target_rads.zero();
434
_ang_accel_target_rads.zero();
435
}
436
437
// Call quaternion attitude controller
438
attitude_controller_run_quat();
439
}
440
441
// Sets the desired roll, pitch, and yaw angles (in centidegrees).
442
// See input_euler_angle_roll_pitch_yaw_rad() for full details.
443
void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw_cd(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)
444
{
445
// Convert from centidegrees on public interface to radians
446
const float euler_roll_angle_rad = cd_to_rad(euler_roll_angle_cd);
447
const float euler_pitch_angle_rad = cd_to_rad(euler_pitch_angle_cd);
448
const float euler_yaw_angle_rad = cd_to_rad(euler_yaw_angle_cd);
449
450
input_euler_angle_roll_pitch_yaw_rad(euler_roll_angle_rad, euler_pitch_angle_rad, euler_yaw_angle_rad, slew_yaw);
451
}
452
453
// Sets the desired roll, pitch, and yaw angle inputs (radians) to follow an absolute attitude setpoint.
454
// Optional yaw slew limiting constrains the rate of change of the yaw target.
455
// If body-frame rate feedforward shaping is enabled, shapes Euler rate/acceleration targets
456
// with configured limits and time constants and converts them back to body-frame targets.
457
// Otherwise, updates the attitude target directly (with optional yaw slew) and zeros rate/accel feedforward targets.
458
void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw_rad(float euler_roll_angle_rad, float euler_pitch_angle_rad, float euler_yaw_angle_rad, bool slew_yaw)
459
{
460
// update attitude target
461
update_attitude_target();
462
463
// calculate the attitude target euler angles
464
_attitude_target.to_euler(_euler_angle_target_rad);
465
466
// Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)
467
euler_roll_angle_rad += get_roll_trim_rad();
468
469
const float slew_yaw_max_rads = get_slew_yaw_max_rads();
470
471
if (_rate_bf_ff_enabled) {
472
// Convert body-frame angular acceleration limits (roll, pitch, yaw) into equivalent
473
// Euler-angle acceleration limits for the current attitude target.
474
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()});
475
476
float yaw_rate_max_rads = radians(_ang_vel_yaw_max_degs);
477
if (slew_yaw) {
478
yaw_rate_max_rads = MIN(yaw_rate_max_rads, slew_yaw_max_rads);
479
}
480
const Vector3f euler_rate_max_rads = euler_accel_limit(_attitude_target, Vector3f{radians(_ang_vel_roll_max_degs), radians(_ang_vel_pitch_max_degs), yaw_rate_max_rads});
481
482
Vector3f euler_accel_target_rads;
483
body_to_euler_derivative(_attitude_target, _ang_accel_target_rads, euler_accel_target_rads);
484
attitude_command_model(wrap_PI(euler_roll_angle_rad - _euler_angle_target_rad.x), 0.0, _euler_rate_target_rads.x, euler_accel_target_rads.x, fabsf(euler_rate_max_rads.x), euler_accel.x, _input_tc, _dt_s);
485
attitude_command_model(wrap_PI(euler_pitch_angle_rad - _euler_angle_target_rad.y), 0.0, _euler_rate_target_rads.y, euler_accel_target_rads.y, fabsf(euler_rate_max_rads.y), euler_accel.y, _input_tc, _dt_s);
486
attitude_command_model(wrap_PI(euler_yaw_angle_rad - _euler_angle_target_rad.z), 0.0, _euler_rate_target_rads.z, euler_accel_target_rads.z, fabsf(euler_rate_max_rads.z), euler_accel.z, _input_tc, _dt_s);
487
488
// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
489
euler_derivative_to_body(_attitude_target, _euler_rate_target_rads, _ang_vel_target_rads);
490
491
// Convert euler angle derivative of desired attitude into a body-frame angular acceleration vector for feedforward
492
euler_derivative_to_body(_attitude_target, euler_accel_target_rads, _ang_accel_target_rads);
493
} else {
494
// No shaping/feedforward: directly update roll/pitch attitude targets and update yaw target
495
// with optional slew limiting, then zero rate/accel feedforward targets.
496
_euler_angle_target_rad.x = euler_roll_angle_rad;
497
_euler_angle_target_rad.y = euler_pitch_angle_rad;
498
499
if (slew_yaw) {
500
// Constrain yaw target change to the configured slew rate.
501
const float yaw_error = wrap_PI(euler_yaw_angle_rad - _euler_angle_target_rad.z);
502
const float yaw_step = constrain_float(yaw_error, -slew_yaw_max_rads * _dt_s, slew_yaw_max_rads * _dt_s);
503
_euler_angle_target_rad.z = wrap_PI(_euler_angle_target_rad.z + yaw_step);
504
} else {
505
_euler_angle_target_rad.z = euler_yaw_angle_rad;
506
}
507
508
// Compute quaternion target attitude
509
_attitude_target.from_euler(_euler_angle_target_rad.x, _euler_angle_target_rad.y, _euler_angle_target_rad.z);
510
511
// Zero rate and acceleration feedforward targets
512
_euler_rate_target_rads.zero();
513
_ang_vel_target_rads.zero();
514
_ang_accel_target_rads.zero();
515
}
516
517
// Call quaternion attitude controller
518
attitude_controller_run_quat();
519
}
520
521
// Sets the desired roll, pitch, and yaw Euler angle rate inputs (radians/s).
522
// If body-frame rate feedforward shaping is enabled, the inputs are shaped using acceleration limits
523
// and time constants to generate Euler rate/acceleration targets, which are then converted into
524
// body-frame angular velocity/acceleration targets for the rate controller.
525
// Otherwise, Euler angle targets are integrated directly from the rate inputs and feedforward targets are zeroed.
526
void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw_rads(float euler_roll_rate_rads, float euler_pitch_rate_rads, float euler_yaw_rate_rads)
527
{
528
// update attitude target
529
update_attitude_target();
530
531
// calculate the attitude target euler angles
532
_attitude_target.to_euler(_euler_angle_target_rad);
533
534
if (_rate_bf_ff_enabled) {
535
// Convert body-frame angular acceleration limits (roll, pitch, yaw) into
536
// equivalent Euler-angle acceleration limits for the current attitude target.
537
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()});
538
539
// Convert the body-frame angular acceleration target into an equivalent Euler-angle
540
// acceleration target for the current attitude target.
541
Vector3f euler_accel_target_rads;
542
body_to_euler_derivative(_attitude_target, _ang_accel_target_rads, euler_accel_target_rads);
543
544
// Shape Euler rate inputs into Euler rate/acceleration targets, applying acceleration limits and time constants.
545
attitude_command_model(0.0, euler_roll_rate_rads, _euler_rate_target_rads.x, euler_accel_target_rads.x, 0.0, euler_accel.x, _rate_rp_tc, _dt_s);
546
attitude_command_model(0.0, euler_pitch_rate_rads, _euler_rate_target_rads.y, euler_accel_target_rads.y, 0.0, euler_accel.y, _rate_rp_tc, _dt_s);
547
attitude_command_model(0.0, euler_yaw_rate_rads, _euler_rate_target_rads.z, euler_accel_target_rads.z, 0.0, euler_accel.z, _rate_y_tc, _dt_s);
548
549
// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
550
euler_derivative_to_body(_attitude_target, _euler_rate_target_rads, _ang_vel_target_rads);
551
552
// Convert euler angle derivative of desired attitude into a body-frame angular acceleration vector for feedforward
553
euler_derivative_to_body(_attitude_target, euler_accel_target_rads, _ang_accel_target_rads);
554
} else {
555
// No shaping/feedforward: integrate Euler angle targets from Euler rate inputs.
556
// Pitch is constrained to ±85 degrees to avoid gimbal lock discontinuities.
557
_euler_angle_target_rad.x = wrap_PI(_euler_angle_target_rad.x + euler_roll_rate_rads * _dt_s);
558
_euler_angle_target_rad.y = constrain_float(_euler_angle_target_rad.y + euler_pitch_rate_rads * _dt_s, radians(-85.0f), radians(85.0f));
559
_euler_angle_target_rad.z = wrap_2PI(_euler_angle_target_rad.z + euler_yaw_rate_rads * _dt_s);
560
561
// Zero rate and acceleration feedforward targets
562
_euler_rate_target_rads.zero();
563
_ang_vel_target_rads.zero();
564
_ang_accel_target_rads.zero();
565
566
// Compute quaternion target attitude
567
_attitude_target.from_euler(_euler_angle_target_rad.x, _euler_angle_target_rad.y, _euler_angle_target_rad.z);
568
}
569
570
// Call quaternion attitude controller
571
attitude_controller_run_quat();
572
}
573
574
// Fully stabilized acro
575
// Sets the desired roll, pitch, and yaw angular rates (in centidegrees/s).
576
// See input_rate_bf_roll_pitch_yaw_rads() for full details.
577
void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_cds(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
578
{
579
// Convert from centidegrees on public interface to radians
580
const float roll_rate_bf_rads = cd_to_rad(roll_rate_bf_cds);
581
const float pitch_rate_bf_rads = cd_to_rad(pitch_rate_bf_cds);
582
const float yaw_rate_bf_rads = cd_to_rad(yaw_rate_bf_cds);
583
584
input_rate_bf_roll_pitch_yaw_rads(roll_rate_bf_rads, pitch_rate_bf_rads, yaw_rate_bf_rads);
585
}
586
587
// Sets the desired roll, pitch, and yaw body-frame angular rate inputs (radians/s).
588
// Used by fully stabilized acro modes.
589
// If body-frame rate feedforward shaping is enabled, the inputs are shaped using acceleration limits
590
// and time constants to generate body-frame angular velocity/acceleration targets for the rate controller.
591
// Otherwise, the attitude target is incrementally rotated using the rate inputs and feedforward targets are zeroed.
592
void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads)
593
{
594
// update attitude target
595
update_attitude_target();
596
597
// calculate the attitude target euler angles
598
_attitude_target.to_euler(_euler_angle_target_rad);
599
600
if (_rate_bf_ff_enabled) {
601
// Shape body-frame rate inputs into body-frame angular velocity/acceleration targets,
602
// applying acceleration limits and configured time constants.
603
attitude_command_model(0.0, roll_rate_bf_rads, _ang_vel_target_rads.x, _ang_accel_target_rads.x, 0.0, get_accel_roll_max_radss(), _rate_rp_tc, _dt_s);
604
attitude_command_model(0.0, pitch_rate_bf_rads, _ang_vel_target_rads.y, _ang_accel_target_rads.y, 0.0, get_accel_pitch_max_radss(), _rate_rp_tc, _dt_s);
605
attitude_command_model(0.0, yaw_rate_bf_rads, _ang_vel_target_rads.z, _ang_accel_target_rads.z, 0.0, get_accel_yaw_max_radss(), _rate_y_tc, _dt_s);
606
607
// Convert body-frame angular velocity into euler angle derivative of desired attitude
608
body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);
609
} else {
610
// No shaping/feedforward: incrementally rotate the attitude target using the body-frame rate inputs.
611
Quaternion attitude_target_update;
612
attitude_target_update.from_axis_angle(Vector3f{roll_rate_bf_rads, pitch_rate_bf_rads, yaw_rate_bf_rads} * _dt_s);
613
_attitude_target = _attitude_target * attitude_target_update;
614
_attitude_target.normalize();
615
616
// Zero rate and acceleration feedforward targets
617
_euler_rate_target_rads.zero();
618
_ang_vel_target_rads.zero();
619
_ang_accel_target_rads.zero();
620
}
621
622
// Call quaternion attitude controller
623
attitude_controller_run_quat();
624
}
625
626
// Sets the desired roll, pitch, and yaw angular rates in body-frame (in centidegrees/s).
627
// See input_rate_bf_roll_pitch_yaw_2_rads() for full details.
628
void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_2_cds(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
629
{
630
// Convert from centidegrees on public interface to radians
631
const float roll_rate_bf_rads = cd_to_rad(roll_rate_bf_cds);
632
const float pitch_rate_bf_rads = cd_to_rad(pitch_rate_bf_cds);
633
const float yaw_rate_bf_rads = cd_to_rad(yaw_rate_bf_cds);
634
635
input_rate_bf_roll_pitch_yaw_2_rads(roll_rate_bf_rads, pitch_rate_bf_rads, yaw_rate_bf_rads);
636
}
637
638
// Sets the desired roll, pitch, and yaw body-frame angular rate inputs (radians/s).
639
// Used by Copter's rate-only acro mode.
640
// Shapes the body-frame rate inputs using acceleration limits and time constants to produce
641
// body-frame angular velocity/acceleration targets for the rate controller.
642
// Attitude targets are updated from the current AHRS attitude to keep target state coherent for mode transitions.
643
void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_2_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads)
644
{
645
// Shape body-frame rate inputs into body-frame angular velocity/acceleration targets,
646
// applying acceleration limits and configured time constants.
647
attitude_command_model(0.0, roll_rate_bf_rads, _ang_vel_target_rads.x, _ang_accel_target_rads.x, 0.0, get_accel_roll_max_radss(), _rate_rp_tc, _dt_s);
648
attitude_command_model(0.0, pitch_rate_bf_rads, _ang_vel_target_rads.y, _ang_accel_target_rads.y, 0.0, get_accel_pitch_max_radss(), _rate_rp_tc, _dt_s);
649
attitude_command_model(0.0, yaw_rate_bf_rads, _ang_vel_target_rads.z, _ang_accel_target_rads.z, 0.0, get_accel_yaw_max_radss(), _rate_y_tc, _dt_s);
650
651
// Update attitude and Euler targets from the current vehicle attitude (used for conditioning mode transitions).
652
_ahrs.get_quat_body_to_ned(_attitude_target);
653
_attitude_target.to_euler(_euler_angle_target_rad);
654
// Convert body-frame angular velocity into euler angle derivative of desired attitude
655
body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);
656
657
// Update body-frame angular velocity target used by the rate controller.
658
_ang_vel_body_rads = _ang_vel_target_rads;
659
}
660
661
// Sets the desired roll, pitch, and yaw angular rates in body-frame (in centidegrees/s).
662
// See input_rate_bf_roll_pitch_yaw_3_rads() for full details.
663
void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3_cds(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
664
{
665
// Convert from centidegrees on public interface to radians
666
const float roll_rate_bf_rads = cd_to_rad(roll_rate_bf_cds);
667
const float pitch_rate_bf_rads = cd_to_rad(pitch_rate_bf_cds);
668
const float yaw_rate_bf_rads = cd_to_rad(yaw_rate_bf_cds);
669
670
input_rate_bf_roll_pitch_yaw_3_rads(roll_rate_bf_rads, pitch_rate_bf_rads, yaw_rate_bf_rads);
671
}
672
673
// Sets the desired roll, pitch, and yaw body-frame angular rate inputs (radians/s).
674
// Used by Plane's acro mode with rate error integration.
675
// Maintains an integrated attitude error quaternion using (target_rate - gyro) and combines it
676
// with shaped rate inputs to form the final body-frame angular velocity target for the rate controller.
677
void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads)
678
{
679
// Extract current integrated attitude error as axis-angle
680
Vector3f attitude_error;
681
_attitude_ang_error.to_axis_angle(attitude_error);
682
683
Quaternion attitude_ang_error_update_quat;
684
685
// Limit the magnitude of the integrated attitude error (prevents windup)
686
float err_mag = attitude_error.length();
687
if (err_mag > AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD) {
688
attitude_error *= AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD / err_mag;
689
_attitude_ang_error.from_axis_angle(attitude_error);
690
}
691
692
// Integrate attitude error using rate error: (target body rates - measured gyro)
693
Vector3f gyro_latest = get_latest_gyro();
694
attitude_ang_error_update_quat.from_axis_angle((_ang_vel_target_rads - gyro_latest) * _dt_s);
695
_attitude_ang_error = attitude_ang_error_update_quat * _attitude_ang_error;
696
_attitude_ang_error.normalize();
697
698
// Shape body-frame rate inputs into body-frame angular velocity/acceleration targets,
699
// applying acceleration limits and configured time constants.
700
attitude_command_model(0.0, roll_rate_bf_rads, _ang_vel_target_rads.x, _ang_accel_target_rads.x, 0.0, get_accel_roll_max_radss(), _rate_rp_tc, _dt_s);
701
attitude_command_model(0.0, pitch_rate_bf_rads, _ang_vel_target_rads.y, _ang_accel_target_rads.y, 0.0, get_accel_pitch_max_radss(), _rate_rp_tc, _dt_s);
702
attitude_command_model(0.0, yaw_rate_bf_rads, _ang_vel_target_rads.z, _ang_accel_target_rads.z, 0.0, get_accel_yaw_max_radss(), _rate_y_tc, _dt_s);
703
704
// Retrieve current vehicle attitude (body to NED)
705
Quaternion attitude_body;
706
_ahrs.get_quat_body_to_ned(attitude_body);
707
708
// Update attitude target by applying the integrated attitude error to the current attitude
709
_attitude_target = attitude_body * _attitude_ang_error;
710
_attitude_target.normalize();
711
712
// Update stored Euler-angle representation of the attitude target
713
_attitude_target.to_euler(_euler_angle_target_rad);
714
715
// Convert body-frame angular velocity into euler angle derivative of desired attitude
716
body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);
717
718
// Compute body-frame angular velocity correction from integrated attitude error and add shaped rate input
719
_attitude_ang_error.to_axis_angle(attitude_error);
720
Vector3f ang_vel_body_rads = update_ang_vel_target_from_att_error(attitude_error);
721
ang_vel_body_rads += _ang_vel_target_rads;
722
723
// Update body-frame angular velocity target used by the rate controller
724
_ang_vel_body_rads = ang_vel_body_rads;
725
}
726
727
/*
728
set the body frame target rates to the specified rates, used by the
729
quadplane code when we want to slave the VTOL controller rates to
730
the fixed wing rates
731
*/
732
733
// Directly sets the body-frame angular rates without smoothing (in centidegrees/s).
734
// See input_rate_bf_roll_pitch_yaw_no_shaping_rads() for full details.
735
void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_no_shaping_cds(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
736
{
737
// Convert from centidegrees on public interface to radians
738
const float roll_rate_bf_rads = cd_to_rad(roll_rate_bf_cds);
739
const float pitch_rate_bf_rads = cd_to_rad(pitch_rate_bf_cds);
740
const float yaw_rate_bf_rads = cd_to_rad(yaw_rate_bf_cds);
741
742
input_rate_bf_roll_pitch_yaw_no_shaping_rads(roll_rate_bf_rads, pitch_rate_bf_rads, yaw_rate_bf_rads);
743
}
744
745
// Directly sets body-frame angular rate targets (radians/s) without shaping.
746
// Used when an external controller (e.g. fixed-wing controller) provides VTOL body rates.
747
// No smoothing, acceleration limiting, or input shaping is applied.
748
void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_no_shaping_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads)
749
{
750
// Set body-frame angular velocity targets directly from inputs
751
_ang_vel_target_rads.x = roll_rate_bf_rads;
752
_ang_vel_target_rads.y = pitch_rate_bf_rads;
753
_ang_vel_target_rads.z = yaw_rate_bf_rads;
754
755
// Update attitude and Euler targets from the current vehicle attitude
756
// (used for mode transitions / logging / target state consistency).
757
_ahrs.get_quat_body_to_ned(_attitude_target);
758
_attitude_target.to_euler(_euler_angle_target_rad);
759
760
// Convert body-frame angular velocity into euler angle derivative of desired attitude
761
body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);
762
763
// Update body-frame angular velocity target used by the rate controller.
764
_ang_vel_body_rads = _ang_vel_target_rads;
765
}
766
767
// Applies a one-time angular offset to the attitude target using body-frame roll, pitch,
768
// and yaw angles (radians).
769
// Used for step-response excitation during autotuning or manual test inputs.
770
// The offset is applied instantaneously; no rate or acceleration shaping is performed.
771
void AC_AttitudeControl::input_angle_step_bf_roll_pitch_yaw_rad(float roll_angle_step_bf_rad, float pitch_angle_step_bf_rad, float yaw_angle_step_bf_rad)
772
{
773
// Apply the requested body-frame angular step to the attitude target
774
Quaternion attitude_target_update;
775
attitude_target_update.from_axis_angle(Vector3f{roll_angle_step_bf_rad, pitch_angle_step_bf_rad, yaw_angle_step_bf_rad});
776
_attitude_target = _attitude_target * attitude_target_update;
777
_attitude_target.normalize();
778
779
// Update stored Euler-angle representation of the attitude target
780
_attitude_target.to_euler(_euler_angle_target_rad);
781
782
// Zero rate and acceleration feedforward targets (pure attitude step)
783
_euler_rate_target_rads.zero();
784
_ang_vel_target_rads.zero();
785
_ang_accel_target_rads.zero();
786
787
// Run quaternion attitude controller
788
attitude_controller_run_quat();
789
}
790
791
// Applies a one-time body-frame angular rate step (radians/s) in roll, pitch, and yaw.
792
// Used to inject discrete disturbances or step inputs for system identification.
793
// This sets the body-frame rate command directly for this update; no shaping is applied.
794
void AC_AttitudeControl::input_rate_step_bf_roll_pitch_yaw_rads(float roll_rate_step_bf_rads, float pitch_rate_step_bf_rads, float yaw_rate_step_bf_rads)
795
{
796
// Update attitude and Euler targets from the current vehicle attitude
797
// (used for mode transitions / logging / target state consistency).
798
_ahrs.get_quat_body_to_ned(_attitude_target);
799
_attitude_target.to_euler(_euler_angle_target_rad);
800
801
// Zero rate and acceleration feedforward targets so the controller cleanly returns to zero rate
802
// after the step input is removed.
803
_ang_vel_target_rads.zero();
804
_ang_accel_target_rads.zero();
805
_euler_rate_target_rads.zero();
806
807
// Apply the requested body-frame angular rate step directly to the rate controller input.
808
_ang_vel_body_rads = Vector3f{roll_rate_step_bf_rads, pitch_rate_step_bf_rads, yaw_rate_step_bf_rads};
809
}
810
811
// Sets the desired thrust vector and a yaw/heading rate input (radians/s).
812
// Used for tilt-based navigation with independent yaw control.
813
// The thrust vector determines the desired tilt (attitude) while the heading rate commands yaw.
814
// Optional yaw slew limiting constrains the heading rate input.
815
void AC_AttitudeControl::input_thrust_vector_rate_heading_rads(const Vector3f& thrust_vector, float heading_rate_rads, bool slew_yaw)
816
{
817
if (slew_yaw) {
818
// Constrain heading rate input using the configured yaw slew rate limit (0 disables limiting).
819
const float slew_yaw_max_rads = get_slew_yaw_max_rads();
820
heading_rate_rads = constrain_float(heading_rate_rads, -slew_yaw_max_rads, slew_yaw_max_rads);
821
}
822
823
// update attitude target
824
update_attitude_target();
825
826
// calculate the attitude target euler angles
827
_attitude_target.to_euler(_euler_angle_target_rad);
828
829
// Convert thrust vector to an attitude quaternion (zero yaw; yaw is commanded separately).
830
Quaternion thrust_vec_quat = attitude_from_thrust_vector(thrust_vector, 0.0f);
831
832
// Compute the attitude correction required to align the current target attitude with the thrust vector.
833
float thrust_vector_diff_angle;
834
Quaternion thrust_vec_correction_quat;
835
Vector3f attitude_error;
836
float returned_thrust_vector_angle;
837
thrust_vector_rotation_angles(thrust_vec_quat, _attitude_target, thrust_vec_correction_quat, attitude_error, returned_thrust_vector_angle, thrust_vector_diff_angle);
838
839
if (_rate_bf_ff_enabled) {
840
// Shape roll/pitch attitude error into body-frame angular velocity/acceleration targets,
841
// applying configured rate/acceleration limits and input time constant.
842
attitude_command_model(attitude_error.x, 0.0, _ang_vel_target_rads.x, _ang_accel_target_rads.x, radians(_ang_vel_roll_max_degs), get_accel_roll_max_radss(), _input_tc, _dt_s);
843
attitude_command_model(attitude_error.y, 0.0, _ang_vel_target_rads.y, _ang_accel_target_rads.y, radians(_ang_vel_pitch_max_degs), get_accel_pitch_max_radss(), _input_tc, _dt_s);
844
845
// Shape yaw rate input into yaw angular velocity/acceleration targets, applying yaw limits and time constant.
846
attitude_command_model(0.0, heading_rate_rads, _ang_vel_target_rads.z, _ang_accel_target_rads.z, radians(_ang_vel_yaw_max_degs), get_accel_yaw_max_radss(), _rate_y_tc, _dt_s);
847
} else {
848
// No shaping/feedforward: directly update the attitude target using the thrust-vector correction and yaw increment.
849
Quaternion yaw_quat;
850
yaw_quat.from_axis_angle(Vector3f{0.0f, 0.0f, heading_rate_rads * _dt_s});
851
_attitude_target = _attitude_target * thrust_vec_correction_quat * yaw_quat;
852
_attitude_target.normalize();
853
854
// Zero rate and acceleration feedforward targets
855
_euler_rate_target_rads.zero();
856
_ang_vel_target_rads.zero();
857
_ang_accel_target_rads.zero();
858
}
859
860
// Convert body-frame angular velocity into euler angle derivative of desired attitude
861
body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);
862
863
// Call quaternion attitude controller
864
attitude_controller_run_quat();
865
}
866
867
// Sets the desired thrust vector, heading angle (radians), and heading rate input (radians/s).
868
// Used when thrust direction (tilt) is commanded independently from yaw/heading.
869
// Heading rate is constrained using the configured yaw slew rate limit (0 disables limiting).
870
void AC_AttitudeControl::input_thrust_vector_heading_rad(const Vector3f& thrust_vector, float heading_angle_rad, float heading_rate_rads)
871
{
872
// Constrain heading rate input using the configured yaw slew rate limit.
873
const float slew_yaw_max_rads = get_slew_yaw_max_rads();
874
heading_rate_rads = constrain_float(heading_rate_rads, -slew_yaw_max_rads, slew_yaw_max_rads);
875
876
// update attitude target
877
update_attitude_target();
878
879
// calculate the attitude target euler angles
880
_attitude_target.to_euler(_euler_angle_target_rad);
881
882
// Convert thrust vector and heading into a desired attitude quaternion.
883
const Quaternion desired_attitude_quat = attitude_from_thrust_vector(thrust_vector, heading_angle_rad);
884
885
if (_rate_bf_ff_enabled) {
886
// Compute attitude error required to move from the current target attitude to the desired attitude.
887
Vector3f attitude_error;
888
float thrust_vector_diff_angle;
889
Quaternion thrust_vec_correction_quat;
890
float returned_thrust_vector_angle;
891
thrust_vector_rotation_angles(desired_attitude_quat, _attitude_target, thrust_vec_correction_quat, attitude_error, returned_thrust_vector_angle, thrust_vector_diff_angle);
892
893
// Shape attitude error and heading rate into body-frame angular velocity/acceleration targets,
894
// applying configured rate/acceleration limits and time constants (roll/pitch use _input_tc, yaw uses _rate_y_tc).
895
attitude_command_model(attitude_error.x, 0.0, _ang_vel_target_rads.x, _ang_accel_target_rads.x, radians(_ang_vel_roll_max_degs), get_accel_roll_max_radss(), _input_tc, _dt_s);
896
attitude_command_model(attitude_error.y, 0.0, _ang_vel_target_rads.y, _ang_accel_target_rads.y, radians(_ang_vel_pitch_max_degs), get_accel_pitch_max_radss(), _input_tc, _dt_s);
897
attitude_command_model(attitude_error.z, heading_rate_rads, _ang_vel_target_rads.z, _ang_accel_target_rads.z, radians(_ang_vel_yaw_max_degs), get_accel_yaw_max_radss(), _rate_y_tc, _dt_s);
898
} else {
899
// No shaping/feedforward: directly set the attitude target to the desired attitude.
900
_attitude_target = desired_attitude_quat;
901
902
// Zero rate and acceleration feedforward targets
903
_euler_rate_target_rads.zero();
904
_ang_vel_target_rads.zero();
905
_ang_accel_target_rads.zero();
906
}
907
908
// Convert body-frame angular velocity into euler angle derivative of desired attitude
909
body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);
910
911
// Call quaternion attitude controller
912
attitude_controller_run_quat();
913
}
914
915
// Command a thrust vector and heading rate
916
void AC_AttitudeControl::input_thrust_vector_heading(const Vector3f& thrust_vector, HeadingCommand heading)
917
{
918
switch (heading.heading_mode) {
919
case HeadingMode::Rate_Only:
920
input_thrust_vector_rate_heading_rads(thrust_vector, heading.yaw_rate_rads);
921
break;
922
case HeadingMode::Angle_Only:
923
input_thrust_vector_heading_rad(thrust_vector, heading.yaw_angle_rad, 0.0);
924
break;
925
case HeadingMode::Angle_And_Rate:
926
input_thrust_vector_heading_rad(thrust_vector, heading.yaw_angle_rad, heading.yaw_rate_rads);
927
break;
928
}
929
}
930
931
Quaternion AC_AttitudeControl::attitude_from_thrust_vector(Vector3f thrust_vector, float heading_angle_rad) const
932
{
933
const Vector3f thrust_vector_up{0.0f, 0.0f, -1.0f};
934
935
if (is_zero(thrust_vector.length_squared())) {
936
thrust_vector = thrust_vector_up;
937
} else {
938
thrust_vector.normalize();
939
}
940
941
// the cross product of the desired and target thrust vector defines the rotation vector
942
Vector3f thrust_vec_cross = thrust_vector_up % thrust_vector;
943
944
// the dot product is used to calculate the angle between the target and desired thrust vectors
945
const float thrust_vector_angle = acosf(constrain_float(thrust_vector_up * thrust_vector, -1.0f, 1.0f));
946
947
// Normalize the thrust rotation vector
948
const float thrust_vector_length = thrust_vec_cross.length();
949
if (is_zero(thrust_vector_length) || is_zero(thrust_vector_angle)) {
950
thrust_vec_cross = thrust_vector_up;
951
} else {
952
thrust_vec_cross /= thrust_vector_length;
953
}
954
955
Quaternion thrust_vec_quat;
956
thrust_vec_quat.from_axis_angle(thrust_vec_cross, thrust_vector_angle);
957
Quaternion yaw_quat;
958
yaw_quat.from_axis_angle(Vector3f{0.0f, 0.0f, 1.0f}, heading_angle_rad);
959
return thrust_vec_quat*yaw_quat;
960
}
961
962
// Calculates the body frame angular velocities to follow the target attitude
963
void AC_AttitudeControl::update_attitude_target()
964
{
965
// rotate target and normalize
966
Quaternion attitude_target_update;
967
attitude_target_update.from_axis_angle(_ang_vel_target_rads * _dt_s);
968
_attitude_target *= attitude_target_update;
969
_attitude_target.normalize();
970
}
971
972
// Calculates the body frame angular velocities to follow the target attitude
973
void AC_AttitudeControl::attitude_controller_run_quat()
974
{
975
// This represents a quaternion rotation in NED frame to the body
976
Quaternion attitude_body;
977
_ahrs.get_quat_body_to_ned(attitude_body);
978
979
// This vector represents the angular error to rotate the thrust vector using x and y and heading using z
980
Vector3f attitude_error;
981
thrust_heading_rotation_angles(_attitude_target, attitude_body, attitude_error, _thrust_angle_rad, _thrust_error_angle_rad);
982
983
// Compute the angular velocity corrections in the body frame from the attitude error
984
Vector3f ang_vel_body_rads = update_ang_vel_target_from_att_error(attitude_error);
985
986
// ensure angular velocity does not go over configured limits
987
ang_vel_limit(ang_vel_body_rads, radians(_ang_vel_roll_max_degs), radians(_ang_vel_pitch_max_degs), radians(_ang_vel_yaw_max_degs));
988
989
// rotation from the target frame to the body frame
990
Quaternion rotation_target_to_body = attitude_body.inverse() * _attitude_target;
991
992
// target angle velocity vector in the body frame
993
Vector3f ang_vel_body_feedforward = rotation_target_to_body * _ang_vel_target_rads;
994
Vector3f gyro = get_latest_gyro();
995
// Correct the thrust vector and smoothly add feedforward and yaw input
996
_feedforward_scalar = 1.0f;
997
if (_thrust_error_angle_rad > AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD * 2.0f) {
998
ang_vel_body_rads.z = gyro.z;
999
} else if (_thrust_error_angle_rad > AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD) {
1000
_feedforward_scalar = (1.0f - (_thrust_error_angle_rad - AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD) / AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD);
1001
ang_vel_body_rads.x += ang_vel_body_feedforward.x * _feedforward_scalar;
1002
ang_vel_body_rads.y += ang_vel_body_feedforward.y * _feedforward_scalar;
1003
ang_vel_body_rads.z += ang_vel_body_feedforward.z;
1004
ang_vel_body_rads.z = gyro.z * (1.0 - _feedforward_scalar) + ang_vel_body_rads.z * _feedforward_scalar;
1005
} else {
1006
ang_vel_body_rads += ang_vel_body_feedforward;
1007
}
1008
1009
// Record error to handle EKF resets
1010
_attitude_ang_error = attitude_body.inverse() * _attitude_target;
1011
// finally update the attitude target
1012
_ang_vel_body_rads = ang_vel_body_rads;
1013
}
1014
1015
// thrust_heading_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion.
1016
// The maximum error in the yaw axis is limited based on static output saturation.
1017
void AC_AttitudeControl::thrust_heading_rotation_angles(Quaternion& attitude_target, const Quaternion& attitude_body, Vector3f& attitude_error_rad, float& thrust_angle_rad, float& thrust_error_angle_rad) const
1018
{
1019
Quaternion thrust_vector_correction;
1020
thrust_vector_rotation_angles(attitude_target, attitude_body, thrust_vector_correction, attitude_error_rad, thrust_angle_rad, thrust_error_angle_rad);
1021
1022
// Todo: Limit roll an pitch error based on output saturation and maximum error.
1023
1024
// Limit Yaw Error based to the maximum that would saturate the output when yaw rate is zero.
1025
Quaternion heading_vec_correction_quat;
1026
1027
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);
1028
if (!is_zero(get_rate_yaw_pid().kP())) {
1029
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_RAD);
1030
if (!is_zero(_p_angle_yaw.kP()) && fabsf(attitude_error_rad.z) > heading_error_max) {
1031
attitude_error_rad.z = constrain_float(wrap_PI(attitude_error_rad.z), -heading_error_max, heading_error_max);
1032
heading_vec_correction_quat.from_axis_angle(Vector3f{0.0f, 0.0f, attitude_error_rad.z});
1033
attitude_target = attitude_body * thrust_vector_correction * heading_vec_correction_quat;
1034
}
1035
}
1036
}
1037
1038
// thrust_vector_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion.
1039
// The first rotation corrects the thrust vector and the second rotation corrects the heading vector.
1040
void AC_AttitudeControl::thrust_vector_rotation_angles(const Quaternion& attitude_target, const Quaternion& attitude_body, Quaternion& thrust_vector_correction, Vector3f& attitude_error_rad, float& thrust_angle_rad, float& thrust_error_angle_rad) const
1041
{
1042
// The direction of thrust is [0,0,-1] is any body-fixed frame, inc. body frame and target frame.
1043
const Vector3f thrust_vector_up{0.0f, 0.0f, -1.0f};
1044
1045
// attitude_target and attitude_body are passive rotations from target / body frames to the NED frame
1046
1047
// Rotating [0,0,-1] by attitude_target expresses (gets a view of) the target thrust vector in the inertial frame
1048
const Vector3f att_target_thrust_vec = attitude_target * thrust_vector_up; // target thrust vector
1049
1050
// Rotating [0,0,-1] by attitude_target expresses (gets a view of) the current thrust vector in the inertial frame
1051
const Vector3f att_body_thrust_vec = attitude_body * thrust_vector_up; // current thrust vector
1052
1053
// the dot product is used to calculate the current lean angle for use of external functions
1054
thrust_angle_rad = acosf(constrain_float(thrust_vector_up * att_body_thrust_vec,-1.0f,1.0f));
1055
1056
// the cross product of the desired and target thrust vector defines the rotation vector
1057
Vector3f thrust_vec_cross = att_body_thrust_vec % att_target_thrust_vec;
1058
1059
// the dot product is used to calculate the angle between the target and desired thrust vectors
1060
thrust_error_angle_rad = acosf(constrain_float(att_body_thrust_vec * att_target_thrust_vec, -1.0f, 1.0f));
1061
1062
// Normalize the thrust rotation vector
1063
float thrust_vector_length = thrust_vec_cross.length();
1064
if (is_zero(thrust_vector_length) || is_zero(thrust_error_angle_rad)) {
1065
thrust_vec_cross = thrust_vector_up;
1066
} else {
1067
thrust_vec_cross /= thrust_vector_length;
1068
}
1069
1070
// thrust_vector_correction is defined relative to the body frame but its axis `thrust_vec_cross` was computed in
1071
// the inertial frame. First rotate it by the inverse of attitude_body to express it back in the body frame
1072
thrust_vec_cross = attitude_body.inverse() * thrust_vec_cross;
1073
thrust_vector_correction.from_axis_angle(thrust_vec_cross, thrust_error_angle_rad);
1074
1075
// calculate the angle error in x and y.
1076
Vector3f rotation_rad;
1077
thrust_vector_correction.to_axis_angle(rotation_rad);
1078
attitude_error_rad.x = rotation_rad.x;
1079
attitude_error_rad.y = rotation_rad.y;
1080
1081
// calculate the remaining rotation required after thrust vector is rotated transformed to the body frame
1082
// heading_vector_correction
1083
Quaternion heading_vec_correction_quat = thrust_vector_correction.inverse() * attitude_body.inverse() * attitude_target;
1084
1085
// calculate the angle error in z (x and y should be zero here).
1086
heading_vec_correction_quat.to_axis_angle(rotation_rad);
1087
attitude_error_rad.z = rotation_rad.z;
1088
}
1089
1090
// calculates the velocity correction from an angle error. The angular velocity has acceleration and
1091
// deceleration limits including basic jerk limiting using _input_tc
1092
void AC_AttitudeControl::attitude_command_model(float error_angle, float desired_ang_vel, float& target_ang_vel, float& target_ang_accel, float max_ang_vel, float accel_max, float input_tc, float dt) const
1093
{
1094
if (!is_positive(dt)) {
1095
return;
1096
}
1097
1098
// protect against divide by zero
1099
if (!is_positive(accel_max)) {
1100
// no acceleration set so default to 1800 degrees/s²
1101
accel_max = radians(1800);
1102
}
1103
1104
if (!is_positive(input_tc)) {
1105
// no acceleration set so default to achieve maximum acceleration in 10 clock cycles
1106
input_tc = dt * 10.0;
1107
}
1108
1109
shape_angle_vel_accel( error_angle, desired_ang_vel, 0.0,
1110
0.0, target_ang_vel, target_ang_accel,
1111
-max_ang_vel, max_ang_vel, accel_max,
1112
accel_max / input_tc, dt, false);
1113
target_ang_vel += target_ang_accel * dt;
1114
}
1115
1116
// calculates the expected angular velocity correction from an angle error based on the AC_AttitudeControl settings.
1117
// This function can be used to predict the delay associated with angle requests.
1118
void AC_AttitudeControl::command_model_rate_predictor(const Vector2f &error_angle_rad, Vector2f& target_ang_vel_rads, Vector2f& target_ang_accel_rads, float dt) const
1119
{
1120
if (_rate_bf_ff_enabled) {
1121
// translate the roll pitch and yaw acceleration limits to the euler axis
1122
attitude_command_model(wrap_PI(error_angle_rad.x), 0.0, target_ang_vel_rads.x, target_ang_accel_rads.x, radians(_ang_vel_roll_max_degs), get_accel_roll_max_radss(), _input_tc, _dt_s);
1123
attitude_command_model(wrap_PI(error_angle_rad.y), 0.0, target_ang_vel_rads.y, target_ang_accel_rads.y, radians(_ang_vel_pitch_max_degs), get_accel_pitch_max_radss(), _input_tc, _dt_s);
1124
} else {
1125
const float angleP_roll = _p_angle_roll.kP() * _angle_P_scale.x;
1126
const float angleP_pitch = _p_angle_pitch.kP() * _angle_P_scale.y;
1127
target_ang_vel_rads.x = angleP_roll * wrap_PI(error_angle_rad.x);
1128
target_ang_vel_rads.y = angleP_pitch * wrap_PI(error_angle_rad.y);
1129
}
1130
// Limit the angular velocity correction
1131
Vector3f ang_vel_rads(target_ang_vel_rads.x, target_ang_vel_rads.y, 0.0f);
1132
ang_vel_limit(ang_vel_rads, radians(_ang_vel_roll_max_degs), radians(_ang_vel_pitch_max_degs), 0.0f);
1133
1134
target_ang_vel_rads.x = ang_vel_rads.x;
1135
target_ang_vel_rads.y = ang_vel_rads.y;
1136
}
1137
1138
// scale I to represent the current angle P
1139
void AC_AttitudeControl::scale_I_to_angle_P()
1140
{
1141
Vector3f i_scale{
1142
_p_angle_roll.kP() * _angle_P_scale.x,
1143
_p_angle_pitch.kP() * _angle_P_scale.y,
1144
_p_angle_yaw.kP() * _angle_P_scale.z
1145
};
1146
set_I_scale_mult(i_scale);
1147
}
1148
1149
// perform any required parameter conversions
1150
void AC_AttitudeControl::convert_parameters()
1151
{
1152
// PARAMETER_CONVERSION - Added: Jan-2026 for 4.7
1153
1154
// return immediately if no conversion is needed
1155
if (_angle_max_deg.configured()) {
1156
return;
1157
}
1158
1159
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
1160
static const AP_Param::ConversionInfo conversion_info_001[] = {
1161
{ 205, 10, AP_PARAM_INT16, "Q_A_ANGLE_MAX" }, // ANGLE_MAX moved to Q_A_ANGLE_MAX
1162
};
1163
#elif APM_BUILD_TYPE(APM_BUILD_ArduSub)
1164
static const AP_Param::ConversionInfo conversion_info_001[] = {
1165
{ 167, 0, AP_PARAM_INT16, "ATC_ANGLE_MAX" }, // ANGLE_MAX moved to ATC_ANGLE_MAX
1166
};
1167
#else
1168
static const AP_Param::ConversionInfo conversion_info_001[] = {
1169
{ 34, 0, AP_PARAM_INT16, "ATC_ANGLE_MAX" }, // ANGLE_MAX moved to ATC_ANGLE_MAX
1170
};
1171
#endif
1172
AP_Param::convert_old_parameters_scaled(conversion_info_001, ARRAY_SIZE(conversion_info_001), 0.01, 0);
1173
}
1174
1175
// limits angular velocity
1176
void AC_AttitudeControl::ang_vel_limit(Vector3f& euler_rad, float ang_vel_roll_max_rads, float ang_vel_pitch_max_rads, float ang_vel_yaw_max_rads) const
1177
{
1178
if (is_zero(ang_vel_roll_max_rads) || is_zero(ang_vel_pitch_max_rads)) {
1179
if (!is_zero(ang_vel_roll_max_rads)) {
1180
euler_rad.x = constrain_float(euler_rad.x, -ang_vel_roll_max_rads, ang_vel_roll_max_rads);
1181
}
1182
if (!is_zero(ang_vel_pitch_max_rads)) {
1183
euler_rad.y = constrain_float(euler_rad.y, -ang_vel_pitch_max_rads, ang_vel_pitch_max_rads);
1184
}
1185
} else {
1186
const Vector2f thrust_vector_ang_vel(euler_rad.x / ang_vel_roll_max_rads, euler_rad.y / ang_vel_pitch_max_rads);
1187
float thrust_vector_length = thrust_vector_ang_vel.length();
1188
if (thrust_vector_length > 1.0f) {
1189
euler_rad.x = thrust_vector_ang_vel.x * ang_vel_roll_max_rads / thrust_vector_length;
1190
euler_rad.y = thrust_vector_ang_vel.y * ang_vel_pitch_max_rads / thrust_vector_length;
1191
}
1192
}
1193
if (!is_zero(ang_vel_yaw_max_rads)) {
1194
euler_rad.z = constrain_float(euler_rad.z, -ang_vel_yaw_max_rads, ang_vel_yaw_max_rads);
1195
}
1196
}
1197
1198
// translates body frame acceleration limits to the euler axis
1199
Vector3f AC_AttitudeControl::euler_accel_limit(const Quaternion &att, const Vector3f &euler_accel)
1200
{
1201
if (!is_positive(euler_accel.x) || !is_positive(euler_accel.y) || !is_positive(euler_accel.z)) {
1202
return Vector3f { euler_accel };
1203
}
1204
1205
const float phi = att.get_euler_roll();
1206
const float theta = att.get_euler_pitch();
1207
1208
const float sin_phi = constrain_float(fabsf(sinf(phi)), 0.1f, 1.0f);
1209
const float cos_phi = constrain_float(fabsf(cosf(phi)), 0.1f, 1.0f);
1210
const float sin_theta = constrain_float(fabsf(sinf(theta)), 0.1f, 1.0f);
1211
const float cos_theta = constrain_float(fabsf(cosf(theta)), 0.1f, 1.0f);
1212
1213
return Vector3f {
1214
euler_accel.x,
1215
MIN(euler_accel.y / cos_phi, euler_accel.z / sin_phi),
1216
MIN(MIN(euler_accel.x / sin_theta, euler_accel.y / (sin_phi * cos_theta)), euler_accel.z / (cos_phi * cos_theta))
1217
};
1218
}
1219
1220
// Sets attitude target to vehicle attitude and sets all rates to zero
1221
// If reset_rate is false rates are not reset to allow the rate controllers to run
1222
void AC_AttitudeControl::reset_target_and_rate(bool reset_rate)
1223
{
1224
// move attitude target to current attitude
1225
_ahrs.get_quat_body_to_ned(_attitude_target);
1226
_attitude_target.to_euler(_euler_angle_target_rad);
1227
1228
if (reset_rate) {
1229
_ang_vel_target_rads.zero();
1230
_ang_accel_target_rads.zero();
1231
_euler_rate_target_rads.zero();
1232
}
1233
}
1234
1235
// Sets yaw target to vehicle heading and sets yaw rate to zero
1236
// If reset_rate is false rates are not reset to allow the rate controllers to run
1237
void AC_AttitudeControl::reset_yaw_target_and_rate(bool reset_rate)
1238
{
1239
// move attitude target to current heading
1240
float yaw_shift = _ahrs.yaw - _euler_angle_target_rad.z;
1241
Quaternion _attitude_target_update;
1242
_attitude_target_update.from_axis_angle(Vector3f{0.0f, 0.0f, yaw_shift});
1243
_attitude_target = _attitude_target_update * _attitude_target;
1244
1245
if (reset_rate) {
1246
// set yaw rate to zero
1247
_euler_rate_target_rads.z = 0.0f;
1248
_ang_accel_target_rads.z = 0.0;
1249
1250
// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
1251
euler_derivative_to_body(_attitude_target, _euler_rate_target_rads, _ang_vel_target_rads);
1252
}
1253
}
1254
1255
// Shifts the target attitude to maintain the current error in the event of an EKF reset
1256
void AC_AttitudeControl::inertial_frame_reset()
1257
{
1258
// Retrieve quaternion body attitude
1259
Quaternion attitude_body;
1260
_ahrs.get_quat_body_to_ned(attitude_body);
1261
1262
// Recalculate the target quaternion
1263
_attitude_target = attitude_body * _attitude_ang_error;
1264
1265
// calculate the attitude target euler angles
1266
_attitude_target.to_euler(_euler_angle_target_rad);
1267
}
1268
1269
// euler_derivative_to_body - transform euler angle derivative to body-frame
1270
// Converts euler derivatives (rate, acceleration, etc.) to body-frame equivalents.
1271
// The same transformation applies regardless of derivative order.
1272
// Uses the kinematic relationship for 321 (yaw-pitch-roll) euler sequence.
1273
void AC_AttitudeControl::euler_derivative_to_body(const Quaternion& att, const Vector3f& euler_derivative_rads, Vector3f& body_derivative_rads)
1274
{
1275
const float theta = att.get_euler_pitch();
1276
const float phi = att.get_euler_roll();
1277
1278
const float sin_theta = sinf(theta);
1279
const float cos_theta = cosf(theta);
1280
const float sin_phi = sinf(phi);
1281
const float cos_phi = cosf(phi);
1282
1283
body_derivative_rads.x = euler_derivative_rads.x - sin_theta * euler_derivative_rads.z;
1284
body_derivative_rads.y = cos_phi * euler_derivative_rads.y + sin_phi * cos_theta * euler_derivative_rads.z;
1285
body_derivative_rads.z = -sin_phi * euler_derivative_rads.y + cos_theta * cos_phi * euler_derivative_rads.z;
1286
}
1287
1288
// body_to_euler_derivative - transform body-frame derivative to euler angle derivative
1289
// Converts body-frame derivatives (rate, acceleration, etc.) to euler equivalents.
1290
// The same transformation applies regardless of derivative order.
1291
// Uses the kinematic relationship for 321 (yaw-pitch-roll) euler sequence.
1292
// Returns false if the vehicle is pitched 90 degrees up or down (gimbal lock)
1293
bool AC_AttitudeControl::body_to_euler_derivative(const Quaternion& att, const Vector3f& body_derivative_rads, Vector3f& euler_derivative_rads)
1294
{
1295
const float theta = att.get_euler_pitch();
1296
const float phi = att.get_euler_roll();
1297
1298
const float sin_theta = sinf(theta);
1299
const float cos_theta = cosf(theta);
1300
const float sin_phi = sinf(phi);
1301
const float cos_phi = cosf(phi);
1302
1303
// 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.
1304
if (is_zero(cos_theta)) {
1305
return false;
1306
}
1307
1308
euler_derivative_rads.x = body_derivative_rads.x + sin_phi * (sin_theta / cos_theta) * body_derivative_rads.y + cos_phi * (sin_theta / cos_theta) * body_derivative_rads.z;
1309
euler_derivative_rads.y = cos_phi * body_derivative_rads.y - sin_phi * body_derivative_rads.z;
1310
euler_derivative_rads.z = (sin_phi / cos_theta) * body_derivative_rads.y + (cos_phi / cos_theta) * body_derivative_rads.z;
1311
return true;
1312
}
1313
1314
// Update rate_target_ang_vel using attitude_error_rot_vec_rad
1315
Vector3f AC_AttitudeControl::update_ang_vel_target_from_att_error(const Vector3f &attitude_error_rot_vec_rad)
1316
{
1317
Vector3f rate_target_ang_vel;
1318
1319
// Compute the roll angular velocity demand from the roll angle error
1320
const float angleP_roll = _p_angle_roll.kP() * _angle_P_scale.x;
1321
if (_use_sqrt_controller && !is_zero(get_accel_roll_max_radss())) {
1322
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_s);
1323
} else {
1324
rate_target_ang_vel.x = angleP_roll * attitude_error_rot_vec_rad.x;
1325
}
1326
1327
// Compute the pitch angular velocity demand from the pitch angle error
1328
const float angleP_pitch = _p_angle_pitch.kP() * _angle_P_scale.y;
1329
if (_use_sqrt_controller && !is_zero(get_accel_pitch_max_radss())) {
1330
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_s);
1331
} else {
1332
rate_target_ang_vel.y = angleP_pitch * attitude_error_rot_vec_rad.y;
1333
}
1334
1335
// Compute the yaw angular velocity demand from the yaw angle error
1336
const float angleP_yaw = _p_angle_yaw.kP() * _angle_P_scale.z;
1337
if (_use_sqrt_controller && !is_zero(get_accel_yaw_max_radss())) {
1338
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_s);
1339
} else {
1340
rate_target_ang_vel.z = angleP_yaw * attitude_error_rot_vec_rad.z;
1341
}
1342
1343
return rate_target_ang_vel;
1344
}
1345
1346
// Enable or disable body-frame feed forward
1347
void AC_AttitudeControl::accel_limiting(bool enable_limits)
1348
{
1349
if (enable_limits) {
1350
// If enabling limits, reload from eeprom or set to defaults
1351
if (is_zero(_accel_roll_max_cdss)) {
1352
_accel_roll_max_cdss.load();
1353
}
1354
if (is_zero(_accel_pitch_max_cdss)) {
1355
_accel_pitch_max_cdss.load();
1356
}
1357
if (is_zero(_accel_yaw_max_cdss)) {
1358
_accel_yaw_max_cdss.load();
1359
}
1360
} else {
1361
_accel_roll_max_cdss.set(0.0f);
1362
_accel_pitch_max_cdss.set(0.0f);
1363
_accel_yaw_max_cdss.set(0.0f);
1364
}
1365
}
1366
1367
// Returns maximum allowable tilt angle (in centidegrees) for pilot input when in altitude hold mode.
1368
// See get_althold_lean_angle_max_rad() for full details.
1369
float AC_AttitudeControl::get_althold_lean_angle_max_cd() const
1370
{
1371
// convert to centi-degrees for public interface
1372
return rad_to_cd(get_althold_lean_angle_max_rad());
1373
}
1374
1375
// Returns maximum allowable tilt angle (in radians) for pilot input when in altitude hold mode.
1376
// Used to limit lean angle based on available thrust margin, prioritising altitude stability.
1377
float AC_AttitudeControl::get_althold_lean_angle_max_rad() const
1378
{
1379
return MAX(_althold_lean_angle_max_rad, radians(AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN));
1380
}
1381
1382
// Return configured tilt angle limit in centidegrees
1383
float AC_AttitudeControl::lean_angle_max_cd() const
1384
{
1385
return constrain_float(_angle_max_deg.get(), AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN, AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MAX) * 100;
1386
}
1387
1388
// Return configured tilt angle limit in radians
1389
float AC_AttitudeControl::lean_angle_max_rad() const
1390
{
1391
return radians(constrain_float(_angle_max_deg.get(), AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN, AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MAX));
1392
}
1393
1394
// Return roll rate step size in centidegrees/s that results in maximum output after 4 time steps
1395
float AC_AttitudeControl::max_rate_step_bf_roll()
1396
{
1397
float dt_average = AP::scheduler().get_filtered_loop_time();
1398
float alpha = MIN(get_rate_roll_pid().get_filt_E_alpha(dt_average), get_rate_roll_pid().get_filt_D_alpha(dt_average));
1399
float alpha_remaining = 1 - alpha;
1400
// todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max
1401
float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);
1402
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_s + get_rate_roll_pid().kP());
1403
if (is_positive(_ang_vel_roll_max_degs)) {
1404
rate_max = MIN(rate_max, get_ang_vel_roll_max_rads());
1405
}
1406
return rate_max;
1407
}
1408
1409
// Return pitch rate step size in centidegrees/s that results in maximum output after 4 time steps
1410
float AC_AttitudeControl::max_rate_step_bf_pitch()
1411
{
1412
const float dt_average = AP::scheduler().get_filtered_loop_time();
1413
const float alpha = MIN(get_rate_pitch_pid().get_filt_E_alpha(dt_average), get_rate_pitch_pid().get_filt_D_alpha(dt_average));
1414
const float alpha_remaining = 1 - alpha;
1415
// todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max
1416
const float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);
1417
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_s + get_rate_pitch_pid().kP());
1418
if (is_positive(_ang_vel_pitch_max_degs)) {
1419
rate_max = MIN(rate_max, get_ang_vel_pitch_max_rads());
1420
}
1421
return rate_max;
1422
}
1423
1424
// Return yaw rate step size in centidegrees/s that results in maximum output after 4 time steps
1425
float AC_AttitudeControl::max_rate_step_bf_yaw()
1426
{
1427
const float dt_average = AP::scheduler().get_filtered_loop_time();
1428
const float alpha = MIN(get_rate_yaw_pid().get_filt_E_alpha(dt_average), get_rate_yaw_pid().get_filt_D_alpha(dt_average));
1429
const float alpha_remaining = 1 - alpha;
1430
// todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max
1431
const float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);
1432
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_s + get_rate_yaw_pid().kP());
1433
if (is_positive(_ang_vel_yaw_max_degs)) {
1434
rate_max = MIN(rate_max, get_ang_vel_yaw_max_rads());
1435
}
1436
return rate_max;
1437
}
1438
1439
bool AC_AttitudeControl::pre_arm_checks(const char *param_prefix,
1440
char *failure_msg,
1441
const uint8_t failure_msg_len)
1442
{
1443
// validate AC_P members:
1444
const struct {
1445
const char *pid_name;
1446
AC_P &p;
1447
} ps[] = {
1448
{ "ANG_PIT", get_angle_pitch_p() },
1449
{ "ANG_RLL", get_angle_roll_p() },
1450
{ "ANG_YAW", get_angle_yaw_p() }
1451
};
1452
for (uint8_t i=0; i<ARRAY_SIZE(ps); i++) {
1453
// all AC_P's must have a positive P value:
1454
if (!is_positive(ps[i].p.kP())) {
1455
hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, ps[i].pid_name);
1456
return false;
1457
}
1458
}
1459
1460
// validate AC_PID members:
1461
const struct {
1462
const char *pid_name;
1463
AC_PID &pid;
1464
} pids[] = {
1465
{ "RAT_RLL", get_rate_roll_pid() },
1466
{ "RAT_PIT", get_rate_pitch_pid() },
1467
{ "RAT_YAW", get_rate_yaw_pid() },
1468
};
1469
for (uint8_t i=0; i<ARRAY_SIZE(pids); i++) {
1470
// if the PID has a positive FF then we just ensure kP and
1471
// kI aren't negative
1472
AC_PID &pid = pids[i].pid;
1473
const char *pid_name = pids[i].pid_name;
1474
if (is_positive(pid.ff())) {
1475
// kP and kI must be non-negative:
1476
if (is_negative(pid.kP())) {
1477
hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be >= 0", param_prefix, pid_name);
1478
return false;
1479
}
1480
if (is_negative(pid.kI())) {
1481
hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_I must be >= 0", param_prefix, pid_name);
1482
return false;
1483
}
1484
} else {
1485
// kP and kI must be positive:
1486
if (!is_positive(pid.kP())) {
1487
hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, pid_name);
1488
return false;
1489
}
1490
if (!is_positive(pid.kI())) {
1491
hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_I must be > 0", param_prefix, pid_name);
1492
return false;
1493
}
1494
}
1495
// never allow a negative D term (but zero is allowed)
1496
if (is_negative(pid.kD())) {
1497
hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_D must be >= 0", param_prefix, pid_name);
1498
return false;
1499
}
1500
}
1501
1502
// validate ANGLE_MAX
1503
if (_angle_max_deg.get() < 10 || _angle_max_deg.get() > 80) {
1504
hal.util->snprintf(failure_msg, failure_msg_len, "%s_ANGLE_MAX must be >= 10 and <= 80", param_prefix);
1505
return false;
1506
}
1507
1508
return true;
1509
}
1510
1511
/*
1512
get the slew rate for roll, pitch and yaw, for oscillation
1513
detection in lua scripts
1514
*/
1515
void AC_AttitudeControl::get_rpy_srate(float &roll_srate, float &pitch_srate, float &yaw_srate)
1516
{
1517
roll_srate = get_rate_roll_pid().get_pid_info().slew_rate;
1518
pitch_srate = get_rate_pitch_pid().get_pid_info().slew_rate;
1519
yaw_srate = get_rate_yaw_pid().get_pid_info().slew_rate;
1520
}
1521
1522