APM:Libraries
AC_AttitudeControl.cpp
Go to the documentation of this file.
1 #include "AC_AttitudeControl.h"
2 #include <AP_HAL/AP_HAL.h>
3 #include <AP_Math/AP_Math.h>
4 
5 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
6  // default gains for Plane
7  # define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.2f // Soft
8 #else
9  // default gains for Copter and Sub
10  # define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.15f // Medium
11 #endif
12 
13 // table of user settable parameters
15 
16  // 0, 1 were RATE_RP_MAX, RATE_Y_MAX
17 
18  // @Param: SLEW_YAW
19  // @DisplayName: Yaw target slew rate
20  // @Description: Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes
21  // @Units: cdeg/s
22  // @Range: 500 18000
23  // @Increment: 100
24  // @User: Advanced
26 
27  // 3 was for ACCEL_RP_MAX
28 
29  // @Param: ACCEL_Y_MAX
30  // @DisplayName: Acceleration Max for Yaw
31  // @Description: Maximum acceleration in yaw axis
32  // @Units: cdeg/s/s
33  // @Range: 0 72000
34  // @Values: 0:Disabled, 9000:VerySlow, 18000:Slow, 36000:Medium, 54000:Fast
35  // @Increment: 1000
36  // @User: Advanced
38 
39  // @Param: RATE_FF_ENAB
40  // @DisplayName: Rate Feedforward Enable
41  // @Description: Controls whether body-frame rate feedfoward is enabled or disabled
42  // @Values: 0:Disabled, 1:Enabled
43  // @User: Advanced
44  AP_GROUPINFO("RATE_FF_ENAB", 5, AC_AttitudeControl, _rate_bf_ff_enabled, AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT),
45 
46  // @Param: ACCEL_R_MAX
47  // @DisplayName: Acceleration Max for Roll
48  // @Description: Maximum acceleration in roll axis
49  // @Units: cdeg/s/s
50  // @Range: 0 180000
51  // @Increment: 1000
52  // @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast
53  // @User: Advanced
55 
56  // @Param: ACCEL_P_MAX
57  // @DisplayName: Acceleration Max for Pitch
58  // @Description: Maximum acceleration in pitch axis
59  // @Units: cdeg/s/s
60  // @Range: 0 180000
61  // @Increment: 1000
62  // @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast
63  // @User: Advanced
65 
66  // IDs 8,9,10,11 RESERVED (in use on Solo)
67 
68  // @Param: ANGLE_BOOST
69  // @DisplayName: Angle Boost
70  // @Description: Angle Boost increases output throttle as the vehicle leans to reduce loss of altitude
71  // @Values: 0:Disabled, 1:Enabled
72  // @User: Advanced
73  AP_GROUPINFO("ANGLE_BOOST", 12, AC_AttitudeControl, _angle_boost_enabled, 1),
74 
75  // @Param: ANG_RLL_P
76  // @DisplayName: Roll axis angle controller P gain
77  // @Description: Roll axis angle controller P gain. Converts the error between the desired roll angle and actual angle to a desired roll rate
78  // @Range: 3.000 12.000
79  // @Range{Sub}: 0.0 12.000
80  // @User: Standard
81  AP_SUBGROUPINFO(_p_angle_roll, "ANG_RLL_", 13, AC_AttitudeControl, AC_P),
82 
83  // @Param: ANG_PIT_P
84  // @DisplayName: Pitch axis angle controller P gain
85  // @Description: Pitch axis angle controller P gain. Converts the error between the desired pitch angle and actual angle to a desired pitch rate
86  // @Range: 3.000 12.000
87  // @Range{Sub}: 0.0 12.000
88  // @User: Standard
89  AP_SUBGROUPINFO(_p_angle_pitch, "ANG_PIT_", 14, AC_AttitudeControl, AC_P),
90 
91  // @Param: ANG_YAW_P
92  // @DisplayName: Yaw axis angle controller P gain
93  // @Description: Yaw axis angle controller P gain. Converts the error between the desired yaw angle and actual angle to a desired yaw rate
94  // @Range: 3.000 6.000
95  // @Range{Sub}: 0.0 6.000
96  // @User: Standard
97  AP_SUBGROUPINFO(_p_angle_yaw, "ANG_YAW_", 15, AC_AttitudeControl, AC_P),
98 
99  // @Param: ANG_LIM_TC
100  // @DisplayName: Angle Limit (to maintain altitude) Time Constant
101  // @Description: Angle Limit (to maintain altitude) Time Constant
102  // @Range: 0.5 10.0
103  // @User: Advanced
105 
106  // @Param: RATE_R_MAX
107  // @DisplayName: Angular Velocity Max for Roll
108  // @Description: Maximum angular velocity in roll axis
109  // @Units: deg/s
110  // @Range: 0 1080
111  // @Increment: 1
112  // @Values: 0:Disabled, 360:Slow, 720:Medium, 1080:Fast
113  // @User: Advanced
114  AP_GROUPINFO("RATE_R_MAX", 17, AC_AttitudeControl, _ang_vel_roll_max, 0.0f),
115 
116  // @Param: RATE_P_MAX
117  // @DisplayName: Angular Velocity Max for Pitch
118  // @Description: Maximum angular velocity in pitch axis
119  // @Units: deg/s
120  // @Range: 0 1080
121  // @Increment: 1
122  // @Values: 0:Disabled, 360:Slow, 720:Medium, 1080:Fast
123  // @User: Advanced
124  AP_GROUPINFO("RATE_P_MAX", 18, AC_AttitudeControl, _ang_vel_pitch_max, 0.0f),
125 
126  // @Param: RATE_Y_MAX
127  // @DisplayName: Angular Velocity Max for Pitch
128  // @Description: Maximum angular velocity in pitch axis
129  // @Units: deg/s
130  // @Range: 0 1080
131  // @Increment: 1
132  // @Values: 0:Disabled, 360:Slow, 720:Medium, 1080:Fast
133  // @User: Advanced
134  AP_GROUPINFO("RATE_Y_MAX", 19, AC_AttitudeControl, _ang_vel_yaw_max, 0.0f),
135 
136  // @Param: INPUT_TC
137  // @DisplayName: Attitude control input time constant (aka smoothing)
138  // @Description: Attitude control input time constant. Low numbers lead to sharper response, higher numbers to softer response
139  // @Units: s
140  // @Range: 0 1
141  // @Increment: 0.01
142  // @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
143  // @User: Standard
145 
147 };
148 
149 // Set output throttle and disable stabilization
150 void AC_AttitudeControl::set_throttle_out_unstabilized(float throttle_in, bool reset_attitude_control, float filter_cutoff)
151 {
152  _throttle_in = throttle_in;
153  _motors.set_throttle_filter_cutoff(filter_cutoff);
154  if (reset_attitude_control) {
156  }
157  _motors.set_throttle(throttle_in);
158  _angle_boost = 0.0f;
159 }
160 
161 // Ensure attitude controller have zero errors to relax rate controller output
163 {
164  // TODO add _ahrs.get_quaternion()
168 
169  // Set reference angular velocity used in angular velocity controller equal
170  // to the input angular velocity and reset the angular velocity integrators.
171  // This zeros the output of the angular velocity controller.
176 }
177 
179 {
183 }
184 
185 // The attitude controller works around the concept of the desired attitude, target attitude
186 // and measured attitude. The desired attitude is the attitude input into the attitude controller
187 // that expresses where the higher level code would like the aircraft to move to. The target attitude is moved
188 // to the desired attitude with jerk, acceleration, and velocity limits. The target angular velocities are fed
189 // directly into the rate controllers. The angular error between the measured attitude and the target attitude is
190 // fed into the angle controller and the output of the angle controller summed at the input of the rate controllers.
191 // By feeding the target angular velocity directly into the rate controllers the measured and target attitudes
192 // remain very close together.
193 //
194 // All input functions below follow the same procedure
195 // 1. define the desired attitude the aircraft should attempt to achieve using the input variables
196 // 2. using the desired attitude and input variables, define the target angular velocity so that it should
197 // move the target attitude towards the desired attitude
198 // 3. if _rate_bf_ff_enabled is not being used then make the target attitude
199 // and target angular velocities equal to the desired attitude and desired angular velocities.
200 // 4. ensure _attitude_target_quat, _attitude_target_euler_angle, _attitude_target_euler_rate and
201 // _attitude_target_ang_vel have been defined. This ensures input modes can be changed without discontinuity.
202 // 5. attitude_controller_run_quat is then run to pass the target angular velocities to the rate controllers and
203 // integrate them into the target attitude. Any errors between the target attitude and the measured attitude are
204 // corrected by first correcting the thrust vector until the angle between the target thrust vector measured
205 // trust vector drops below 2*AC_ATTITUDE_THRUST_ERROR_ANGLE. At this point the heading is also corrected.
206 
207 
208 
209 // Command a Quaternion attitude with feedforward and smoothing
211 {
212  // calculate the attitude target euler angles
214 
215  Quaternion attitude_error_quat = _attitude_target_quat.inverse() * attitude_desired_quat;
216  Vector3f attitude_error_angle;
217  attitude_error_quat.to_axis_angle(attitude_error_angle);
218 
219  if (_rate_bf_ff_enabled) {
220  // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler
221  // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration
222  // and an exponential decay specified by _input_tc at the end.
226 
227  // Limit the angular velocity
229  // Convert body-frame angular velocity into euler angle derivative of desired attitude
231  } else {
232  _attitude_target_quat = attitude_desired_quat;
233 
234  // Set rate feedforward requests to zero
235  _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
236  _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
237  }
238 
239  // Call quaternion attitude controller
241 }
242 
243 // Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
244 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)
245 {
246  // Convert from centidegrees on public interface to radians
247  float euler_roll_angle = radians(euler_roll_angle_cd*0.01f);
248  float euler_pitch_angle = radians(euler_pitch_angle_cd*0.01f);
249  float euler_yaw_rate = radians(euler_yaw_rate_cds*0.01f);
250 
251  // calculate the attitude target euler angles
253 
254  // Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)
255  euler_roll_angle += get_roll_trim_rad();
256 
257  if (_rate_bf_ff_enabled) {
258  // translate the roll pitch and yaw acceleration limits to the euler axis
260 
261  // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler
262  // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration
263  // and an exponential decay specified by smoothing_gain at the end.
266 
267  // When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing
268  // the output rate towards the input rate.
270 
271  // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
273  // Limit the angular velocity
275  // Convert body-frame angular velocity into euler angle derivative of desired attitude
277  } else {
278  // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.
279  _attitude_target_euler_angle.x = euler_roll_angle;
280  _attitude_target_euler_angle.y = euler_pitch_angle;
281  _attitude_target_euler_angle.z += euler_yaw_rate*_dt;
282  // Compute quaternion target attitude
284 
285  // Set rate feedforward requests to zero
286  _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
287  _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
288  }
289 
290  // Call quaternion attitude controller
292 }
293 
294 // Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
295 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)
296 {
297  // Convert from centidegrees on public interface to radians
298  float euler_roll_angle = radians(euler_roll_angle_cd*0.01f);
299  float euler_pitch_angle = radians(euler_pitch_angle_cd*0.01f);
300  float euler_yaw_angle = radians(euler_yaw_angle_cd*0.01f);
301 
302  // calculate the attitude target euler angles
304 
305  // Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)
306  euler_roll_angle += get_roll_trim_rad();
307 
308  if (_rate_bf_ff_enabled) {
309  // translate the roll pitch and yaw acceleration limits to the euler axis
311 
312  // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler
313  // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration
314  // and an exponential decay specified by _input_tc at the end.
318  if (slew_yaw) {
320  }
321 
322  // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
324  // Limit the angular velocity
326  // Convert body-frame angular velocity into euler angle derivative of desired attitude
328  } else {
329  // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.
330  _attitude_target_euler_angle.x = euler_roll_angle;
331  _attitude_target_euler_angle.y = euler_pitch_angle;
332  if (slew_yaw) {
333  // Compute constrained angle error
335  // Update attitude target from constrained angle error
337  } else {
338  _attitude_target_euler_angle.z = euler_yaw_angle;
339  }
340  // Compute quaternion target attitude
342 
343  // Set rate feedforward requests to zero
344  _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
345  _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
346  }
347 
348  // Call quaternion attitude controller
350 }
351 
352 // Command an euler roll, pitch, and yaw rate with angular velocity feedforward and smoothing
353 void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds)
354 {
355  // Convert from centidegrees on public interface to radians
356  float euler_roll_rate = radians(euler_roll_rate_cds*0.01f);
357  float euler_pitch_rate = radians(euler_pitch_rate_cds*0.01f);
358  float euler_yaw_rate = radians(euler_yaw_rate_cds*0.01f);
359 
360  // calculate the attitude target euler angles
362 
363  if (_rate_bf_ff_enabled) {
364  // translate the roll pitch and yaw acceleration limits to the euler axis
366 
367  // When acceleration limiting is enabled, the input shaper constrains angular acceleration, slewing
368  // the output rate towards the input rate.
372 
373  // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
375  } else {
376  // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.
377  // Pitch angle is restricted to +- 85.0 degrees to avoid gimbal lock discontinuities.
381 
382  // Set rate feedforward requests to zero
383  _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
384  _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
385 
386  // Compute quaternion target attitude
388  }
389 
390  // Call quaternion attitude controller
392 }
393 
394 // Command an angular velocity with angular velocity feedforward and smoothing
395 void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
396 {
397  // Convert from centidegrees on public interface to radians
398  float roll_rate_rads = radians(roll_rate_bf_cds*0.01f);
399  float pitch_rate_rads = radians(pitch_rate_bf_cds*0.01f);
400  float yaw_rate_rads = radians(yaw_rate_bf_cds*0.01f);
401 
402  // calculate the attitude target euler angles
404 
405  if (_rate_bf_ff_enabled) {
406  // Compute acceleration-limited body frame rates
407  // When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing
408  // the output rate towards the input rate.
412 
413  // Convert body-frame angular velocity into euler angle derivative of desired attitude
415  } else {
416  // When feedforward is not enabled, the quaternion is calculated and is input into the target and the feedforward rate is zeroed.
417  Quaternion attitude_target_update_quat;
418  attitude_target_update_quat.from_axis_angle(Vector3f(roll_rate_rads * _dt, pitch_rate_rads * _dt, yaw_rate_rads * _dt));
419  _attitude_target_quat = _attitude_target_quat * attitude_target_update_quat;
421 
422  // Set rate feedforward requests to zero
423  _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
424  _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
425  }
426 
427  // Call quaternion attitude controller
429 }
430 
431 // Command an angular velocity with angular velocity smoothing using rate loops only with no attitude loop stabilization
432 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)
433 {
434  // Convert from centidegrees on public interface to radians
435  float roll_rate_rads = radians(roll_rate_bf_cds*0.01f);
436  float pitch_rate_rads = radians(pitch_rate_bf_cds*0.01f);
437  float yaw_rate_rads = radians(yaw_rate_bf_cds*0.01f);
438 
439  // Compute acceleration-limited body frame rates
440  // When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing
441  // the output rate towards the input rate.
445 
446  // Update the unused targets attitude based on current attitude to condition mode change
449  // Convert body-frame angular velocity into euler angle derivative of desired attitude
452 }
453 
454 // Command an angular velocity with angular velocity smoothing using rate loops only with integrated rate error stabilization
455 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)
456 {
457  // Convert from centidegrees on public interface to radians
458  float roll_rate_rads = radians(roll_rate_bf_cds*0.01f);
459  float pitch_rate_rads = radians(pitch_rate_bf_cds*0.01f);
460  float yaw_rate_rads = radians(yaw_rate_bf_cds*0.01f);
461 
462  // Update attitude error
463  Vector3f gyro_latest = _ahrs.get_gyro_latest();
464  Quaternion attitude_ang_error_update_quat;
465  attitude_ang_error_update_quat.from_axis_angle(Vector3f((_attitude_target_ang_vel.x-gyro_latest.x) * _dt, (_attitude_target_ang_vel.y-gyro_latest.y) * _dt, (_attitude_target_ang_vel.z-gyro_latest.z) * _dt));
466  _attitude_ang_error = attitude_ang_error_update_quat * _attitude_ang_error;
467 
468  // Compute acceleration-limited body frame rates
469  // When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing
470  // the output rate towards the input rate.
474 
475  // Retrieve quaternion vehicle attitude
476  // TODO add _ahrs.get_quaternion()
477  Quaternion attitude_vehicle_quat;
478  attitude_vehicle_quat.from_rotation_matrix(_ahrs.get_rotation_body_to_ned());
479 
480  // Update the unused targets attitude based on current attitude to condition mode change
481  _attitude_target_quat = attitude_vehicle_quat*_attitude_ang_error;
482 
483  // calculate the attitude target euler angles
485 
486  // Convert body-frame angular velocity into euler angle derivative of desired attitude
488 
489  // Compute the angular velocity target from the integrated rate error
490  Vector3f attitude_error_vector;
491  _attitude_ang_error.to_axis_angle(attitude_error_vector);
494 
495  // ensure Quaternions stay normalized
496  _attitude_ang_error.normalize();
497 }
498 
499 // Command an angular step (i.e change) in body frame angle
500 // Used to command a step in angle without exciting the orthogonal axis during autotune
501 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)
502 {
503  // Convert from centidegrees on public interface to radians
504  float roll_step_rads = radians(roll_angle_step_bf_cd*0.01f);
505  float pitch_step_rads = radians(pitch_angle_step_bf_cd*0.01f);
506  float yaw_step_rads = radians(yaw_angle_step_bf_cd*0.01f);
507 
508  // rotate attitude target by desired step
509  Quaternion attitude_target_update_quat;
510  attitude_target_update_quat.from_axis_angle(Vector3f(roll_step_rads, pitch_step_rads, yaw_step_rads));
511  _attitude_target_quat = _attitude_target_quat * attitude_target_update_quat;
513 
514  // calculate the attitude target euler angles
516 
517  // Set rate feedforward requests to zero
518  _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
519  _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
520 
521  // Call quaternion attitude controller
523 }
524 
525 // Calculates the body frame angular velocities to follow the target attitude
527 {
528  // Retrieve quaternion vehicle attitude
529  // TODO add _ahrs.get_quaternion()
530  Quaternion attitude_vehicle_quat;
531  attitude_vehicle_quat.from_rotation_matrix(_ahrs.get_rotation_body_to_ned());
532 
533  // Compute attitude error
534  Vector3f attitude_error_vector;
535  thrust_heading_rotation_angles(_attitude_target_quat, attitude_vehicle_quat, attitude_error_vector, _thrust_error_angle);
536 
537  // Compute the angular velocity target from the attitude error
539 
540  // Add feedforward term that attempts to ensure that roll and pitch errors rotate with the body frame rather than the reference frame.
541  // todo: this should probably be a matrix that couples yaw as well.
542  _rate_target_ang_vel.x += attitude_error_vector.y * _ahrs.get_gyro().z;
543  _rate_target_ang_vel.y += -attitude_error_vector.x * _ahrs.get_gyro().z;
544 
546 
547  // Add the angular velocity feedforward, rotated into vehicle frame
549  Quaternion to_to_from_quat = attitude_vehicle_quat.inverse() * _attitude_target_quat;
550  Quaternion desired_ang_vel_quat = to_to_from_quat.inverse()*attitude_target_ang_vel_quat*to_to_from_quat;
551 
552  // Correct the thrust vector and smoothly add feedforward and yaw input
557  _rate_target_ang_vel.x += desired_ang_vel_quat.q2*feedforward_scalar;
558  _rate_target_ang_vel.y += desired_ang_vel_quat.q3*feedforward_scalar;
559  _rate_target_ang_vel.z += desired_ang_vel_quat.q4;
560  _rate_target_ang_vel.z = _ahrs.get_gyro().z*(1.0-feedforward_scalar) + _rate_target_ang_vel.z*feedforward_scalar;
561  } else {
562  _rate_target_ang_vel.x += desired_ang_vel_quat.q2;
563  _rate_target_ang_vel.y += desired_ang_vel_quat.q3;
564  _rate_target_ang_vel.z += desired_ang_vel_quat.q4;
565  }
566 
567  if (_rate_bf_ff_enabled) {
568  // rotate target and normalize
569  Quaternion attitude_target_update_quat;
571  _attitude_target_quat = _attitude_target_quat * attitude_target_update_quat;
573  }
574 
575  // ensure Quaternions stay normalized
577 
578  // Record error to handle EKF resets
579  _attitude_ang_error = attitude_vehicle_quat.inverse() * _attitude_target_quat;
580 }
581 
582 // thrust_heading_rotation_angles - calculates two ordered rotations to move the att_from_quat quaternion to the att_to_quat quaternion.
583 // The first rotation corrects the thrust vector and the second rotation corrects the heading vector.
584 void AC_AttitudeControl::thrust_heading_rotation_angles(Quaternion& att_to_quat, const Quaternion& att_from_quat, Vector3f& att_diff_angle, float& thrust_vec_dot)
585 {
586  Matrix3f att_to_rot_matrix; // rotation from the target body frame to the inertial frame.
587  att_to_quat.rotation_matrix(att_to_rot_matrix);
588  Vector3f att_to_thrust_vec = att_to_rot_matrix*Vector3f(0.0f,0.0f,1.0f);
589 
590  Matrix3f att_from_rot_matrix; // rotation from the current body frame to the inertial frame.
591  att_from_quat.rotation_matrix(att_from_rot_matrix);
592  Vector3f att_from_thrust_vec = att_from_rot_matrix*Vector3f(0.0f,0.0f,1.0f);
593 
594  // the cross product of the desired and target thrust vector defines the rotation vector
595  Vector3f thrust_vec_cross = att_from_thrust_vec % att_to_thrust_vec;
596 
597  // the dot product is used to calculate the angle between the target and desired thrust vectors
598  thrust_vec_dot = acosf(constrain_float(att_from_thrust_vec * att_to_thrust_vec,-1.0f,1.0f));
599 
600  // Normalize the thrust rotation vector
601  float thrust_vector_length = thrust_vec_cross.length();
602  if(is_zero(thrust_vector_length) || is_zero(thrust_vec_dot)){
603  thrust_vec_cross = Vector3f(0,0,1);
604  thrust_vec_dot = 0.0f;
605  }else{
606  thrust_vec_cross /= thrust_vector_length;
607  }
608  Quaternion thrust_vec_correction_quat;
609  thrust_vec_correction_quat.from_axis_angle(thrust_vec_cross, thrust_vec_dot);
610 
611  // Rotate thrust_vec_correction_quat to the att_from frame
612  thrust_vec_correction_quat = att_from_quat.inverse()*thrust_vec_correction_quat*att_from_quat;
613 
614  // calculate the remaining rotation required after thrust vector is rotated transformed to the att_from frame
615  Quaternion yaw_vec_correction_quat = thrust_vec_correction_quat.inverse()*att_from_quat.inverse()*att_to_quat;
616 
617  // calculate the angle error in x and y.
618  Vector3f rotation;
619  thrust_vec_correction_quat.to_axis_angle(rotation);
620  att_diff_angle.x = rotation.x;
621  att_diff_angle.y = rotation.y;
622 
623  // calculate the angle error in z (x and y should be zero here).
624  yaw_vec_correction_quat.to_axis_angle(rotation);
625  att_diff_angle.z = rotation.z;
626 
627  // Todo: Limit roll an pitch error based on output saturation and maximum error.
628 
629  // Limit Yaw Error based on maximum acceleration - Update to include output saturation and maximum error.
630  // Currently the limit is based on the maximum acceleration using the linear part of the SQRT controller.
631  // This should be updated to be based on an angle limit, saturation, or unlimited based on user defined parameters.
632  if(!is_zero(_p_angle_yaw.kP()) && fabsf(att_diff_angle.z) > AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS/_p_angle_yaw.kP()){
634  yaw_vec_correction_quat.from_axis_angle(Vector3f(0.0f,0.0f,att_diff_angle.z));
635  att_to_quat = att_from_quat*thrust_vec_correction_quat*yaw_vec_correction_quat;
636  }
637 }
638 
639 // calculates the velocity correction from an angle error. The angular velocity has acceleration and
640 // deceleration limits including basic jerk limiting using _input_tc
641 float AC_AttitudeControl::input_shaping_angle(float error_angle, float input_tc, float accel_max, float target_ang_vel, float dt)
642 {
643  // Calculate the velocity as error approaches zero with acceleration limited by accel_max_radss
644  float desired_ang_vel = sqrt_controller(error_angle, 1.0f / MAX(input_tc, 0.01f), accel_max, dt);
645 
646  // Acceleration is limited directly to smooth the beginning of the curve.
647  return input_shaping_ang_vel(target_ang_vel, desired_ang_vel, accel_max, dt);
648 }
649 
650 // limits the acceleration and deceleration of a velocity request
651 float AC_AttitudeControl::input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt)
652 {
653  // Acceleration is limited directly to smooth the beginning of the curve.
654  if (is_positive(accel_max)) {
655  float delta_ang_vel = accel_max * dt;
656  return constrain_float(desired_ang_vel, target_ang_vel-delta_ang_vel, target_ang_vel+delta_ang_vel);
657  } else {
658  return desired_ang_vel;
659  }
660 }
661 
662 // calculates the expected angular velocity correction from an angle error based on the AC_AttitudeControl settings.
663 // This function can be used to predict the delay associated with angle requests.
664 void AC_AttitudeControl::input_shaping_rate_predictor(Vector2f error_angle, Vector2f& target_ang_vel, float dt) const
665 {
666  if (_rate_bf_ff_enabled) {
667  // translate the roll pitch and yaw acceleration limits to the euler axis
668  target_ang_vel.x = input_shaping_angle(wrap_PI(error_angle.x), _input_tc, get_accel_roll_max_radss(), target_ang_vel.x, dt);
669  target_ang_vel.y = input_shaping_angle(wrap_PI(error_angle.y), _input_tc, get_accel_pitch_max_radss(), target_ang_vel.y, dt);
670  } else {
671  target_ang_vel.x = _p_angle_roll.get_p(wrap_PI(error_angle.x));
672  target_ang_vel.y = _p_angle_pitch.get_p(wrap_PI(error_angle.y));
673  }
674  // Limit the angular velocity correction
675  Vector3f ang_vel(target_ang_vel.x, target_ang_vel.y, 0.0f);
677 
678  target_ang_vel.x = ang_vel.x;
679  target_ang_vel.y = ang_vel.y;
680 }
681 
682 // limits angular velocity
683 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
684 {
685  if (is_zero(ang_vel_roll_max) || is_zero(ang_vel_pitch_max)) {
686  if (!is_zero(ang_vel_roll_max)) {
687  euler_rad.x = constrain_float(euler_rad.x, -ang_vel_roll_max, ang_vel_roll_max);
688  }
689  if (!is_zero(ang_vel_pitch_max)) {
690  euler_rad.y = constrain_float(euler_rad.y, -ang_vel_pitch_max, ang_vel_pitch_max);
691  }
692  } else {
693  Vector2f thrust_vector_ang_vel(euler_rad.x/ang_vel_roll_max, euler_rad.y/ang_vel_pitch_max);
694  float thrust_vector_length = thrust_vector_ang_vel.length();
695  if (thrust_vector_length > 1.0f) {
696  euler_rad.x = thrust_vector_ang_vel.x * ang_vel_roll_max / thrust_vector_length;
697  euler_rad.y = thrust_vector_ang_vel.y * ang_vel_pitch_max / thrust_vector_length;
698  }
699  }
700  if (!is_zero(ang_vel_yaw_max)) {
701  euler_rad.z = constrain_float(euler_rad.z, -ang_vel_yaw_max, ang_vel_yaw_max);
702  }
703 }
704 
705 // translates body frame acceleration limits to the euler axis
707 {
708  float sin_phi = constrain_float(fabsf(sinf(euler_rad.x)), 0.1f, 1.0f);
709  float cos_phi = constrain_float(fabsf(cosf(euler_rad.x)), 0.1f, 1.0f);
710  float sin_theta = constrain_float(fabsf(sinf(euler_rad.y)), 0.1f, 1.0f);
711 
712  Vector3f rot_accel;
713  if(is_zero(euler_accel.x) || is_zero(euler_accel.y) || is_zero(euler_accel.z) || is_negative(euler_accel.x) || is_negative(euler_accel.y) || is_negative(euler_accel.z)) {
714  rot_accel.x = euler_accel.x;
715  rot_accel.y = euler_accel.y;
716  rot_accel.z = euler_accel.z;
717  } else {
718  rot_accel.x = euler_accel.x;
719  rot_accel.y = MIN(euler_accel.y/cos_phi, euler_accel.z/sin_phi);
720  rot_accel.z = MIN(MIN(euler_accel.x/sin_theta, euler_accel.y/sin_phi), euler_accel.z/cos_phi);
721  }
722  return rot_accel;
723 }
724 
725 // Shifts earth frame yaw target by yaw_shift_cd. yaw_shift_cd should be in centidegrees and is added to the current target heading
727 {
728  float yaw_shift = radians(yaw_shift_cd*0.01f);
729  Quaternion _attitude_target_update_quat;
730  _attitude_target_update_quat.from_axis_angle(Vector3f(0.0f, 0.0f, yaw_shift));
731  _attitude_target_quat = _attitude_target_update_quat*_attitude_target_quat;
732 }
733 
734 // Shifts earth frame yaw target by yaw_shift_cd. yaw_shift_cd should be in centidegrees and is added to the current target heading
736 {
737  // Retrieve quaternion vehicle attitude
738  // TODO add _ahrs.get_quaternion()
739  Quaternion attitude_vehicle_quat;
740  attitude_vehicle_quat.from_rotation_matrix(_ahrs.get_rotation_body_to_ned());
741 
742  // Recalculate the target quaternion
743  _attitude_target_quat = attitude_vehicle_quat * _attitude_ang_error;
744 
745  // calculate the attitude target euler angles
747 }
748 
749 // Convert a 321-intrinsic euler angle derivative to an angular velocity vector
750 void AC_AttitudeControl::euler_rate_to_ang_vel(const Vector3f& euler_rad, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads)
751 {
752  float sin_theta = sinf(euler_rad.y);
753  float cos_theta = cosf(euler_rad.y);
754  float sin_phi = sinf(euler_rad.x);
755  float cos_phi = cosf(euler_rad.x);
756 
757  ang_vel_rads.x = euler_rate_rads.x - sin_theta * euler_rate_rads.z;
758  ang_vel_rads.y = cos_phi * euler_rate_rads.y + sin_phi * cos_theta * euler_rate_rads.z;
759  ang_vel_rads.z = -sin_phi * euler_rate_rads.y + cos_theta * cos_phi * euler_rate_rads.z;
760 }
761 
762 // Convert an angular velocity vector to a 321-intrinsic euler angle derivative
763 // Returns false if the vehicle is pitched 90 degrees up or down
764 bool AC_AttitudeControl::ang_vel_to_euler_rate(const Vector3f& euler_rad, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads)
765 {
766  float sin_theta = sinf(euler_rad.y);
767  float cos_theta = cosf(euler_rad.y);
768  float sin_phi = sinf(euler_rad.x);
769  float cos_phi = cosf(euler_rad.x);
770 
771  // 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.
772  if (is_zero(cos_theta)) {
773  return false;
774  }
775 
776  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;
777  euler_rate_rads.y = cos_phi * ang_vel_rads.y - sin_phi * ang_vel_rads.z;
778  euler_rate_rads.z = (sin_phi / cos_theta) * ang_vel_rads.y + (cos_phi / cos_theta) * ang_vel_rads.z;
779  return true;
780 }
781 
782 // Update rate_target_ang_vel using attitude_error_rot_vec_rad
784 {
785  Vector3f rate_target_ang_vel;
786  // Compute the roll angular velocity demand from the roll angle error
787  if (_use_sqrt_controller) {
789  }else{
790  rate_target_ang_vel.x = _p_angle_roll.kP() * attitude_error_rot_vec_rad.x;
791  }
792  // todo: Add Angular Velocity Limit
793 
794  // Compute the pitch angular velocity demand from the roll angle error
795  if (_use_sqrt_controller) {
797  }else{
798  rate_target_ang_vel.y = _p_angle_pitch.kP() * attitude_error_rot_vec_rad.y;
799  }
800  // todo: Add Angular Velocity Limit
801 
802  // Compute the yaw angular velocity demand from the roll angle error
803  if (_use_sqrt_controller) {
805  }else{
806  rate_target_ang_vel.z = _p_angle_yaw.kP() * attitude_error_rot_vec_rad.z;
807  }
808  // todo: Add Angular Velocity Limit
809  return rate_target_ang_vel;
810 }
811 
812 // Run the roll angular velocity PID controller and return the output
813 float AC_AttitudeControl::rate_target_to_motor_roll(float rate_actual_rads, float rate_target_rads)
814 {
815  float rate_error_rads = rate_target_rads - rate_actual_rads;
816 
817  // pass error to PID controller
818  get_rate_roll_pid().set_input_filter_d(rate_error_rads);
819  get_rate_roll_pid().set_desired_rate(rate_target_rads);
820 
821  float integrator = get_rate_roll_pid().get_integrator();
822 
823  // Ensure that integrator can only be reduced if the output is saturated
824  if (!_motors.limit.roll_pitch || ((is_positive(integrator) && is_negative(rate_error_rads)) || (is_negative(integrator) && is_positive(rate_error_rads)))) {
825  integrator = get_rate_roll_pid().get_i();
826  }
827 
828  // Compute output in range -1 ~ +1
829  float output = get_rate_roll_pid().get_p() + integrator + get_rate_roll_pid().get_d() + get_rate_roll_pid().get_ff(rate_target_rads);
830 
831  // Constrain output
832  return constrain_float(output, -1.0f, 1.0f);
833 }
834 
835 // Run the pitch angular velocity PID controller and return the output
836 float AC_AttitudeControl::rate_target_to_motor_pitch(float rate_actual_rads, float rate_target_rads)
837 {
838  float rate_error_rads = rate_target_rads - rate_actual_rads;
839 
840  // pass error to PID controller
841  get_rate_pitch_pid().set_input_filter_d(rate_error_rads);
842  get_rate_pitch_pid().set_desired_rate(rate_target_rads);
843 
844  float integrator = get_rate_pitch_pid().get_integrator();
845 
846  // Ensure that integrator can only be reduced if the output is saturated
847  if (!_motors.limit.roll_pitch || ((is_positive(integrator) && is_negative(rate_error_rads)) || (is_negative(integrator) && is_positive(rate_error_rads)))) {
848  integrator = get_rate_pitch_pid().get_i();
849  }
850 
851  // Compute output in range -1 ~ +1
852  float output = get_rate_pitch_pid().get_p() + integrator + get_rate_pitch_pid().get_d() + get_rate_pitch_pid().get_ff(rate_target_rads);
853 
854  // Constrain output
855  return constrain_float(output, -1.0f, 1.0f);
856 }
857 
858 // Run the yaw angular velocity PID controller and return the output
859 float AC_AttitudeControl::rate_target_to_motor_yaw(float rate_actual_rads, float rate_target_rads)
860 {
861  float rate_error_rads = rate_target_rads - rate_actual_rads;
862 
863  // pass error to PID controller
864  get_rate_yaw_pid().set_input_filter_all(rate_error_rads);
865  get_rate_yaw_pid().set_desired_rate(rate_target_rads);
866 
867  float integrator = get_rate_yaw_pid().get_integrator();
868 
869  // Ensure that integrator can only be reduced if the output is saturated
870  if (!_motors.limit.yaw || ((is_positive(integrator) && is_negative(rate_error_rads)) || (is_negative(integrator) && is_positive(rate_error_rads)))) {
871  integrator = get_rate_yaw_pid().get_i();
872  }
873 
874  // Compute output in range -1 ~ +1
875  float output = get_rate_yaw_pid().get_p() + integrator + get_rate_yaw_pid().get_d() + get_rate_yaw_pid().get_ff(rate_target_rads);
876 
877  // Constrain output
878  return constrain_float(output, -1.0f, 1.0f);
879 }
880 
881 // Enable or disable body-frame feed forward
882 void AC_AttitudeControl::accel_limiting(bool enable_limits)
883 {
884  if (enable_limits) {
885  // If enabling limits, reload from eeprom or set to defaults
886  if (is_zero(_accel_roll_max)) {
887  _accel_roll_max.load();
888  }
889  if (is_zero(_accel_pitch_max)) {
890  _accel_pitch_max.load();
891  }
892  if (is_zero(_accel_yaw_max)) {
893  _accel_yaw_max.load();
894  }
895  } else {
896  _accel_roll_max = 0.0f;
897  _accel_pitch_max = 0.0f;
898  _accel_yaw_max = 0.0f;
899  }
900 }
901 
902 // Return tilt angle limit for pilot input that prioritises altitude hold over lean angle
904 {
905  // convert to centi-degrees for public interface
906  return ToDeg(_althold_lean_angle_max) * 100.0f;
907 }
908 
909 // Proportional controller with piecewise sqrt sections to constrain second derivative
910 float AC_AttitudeControl::sqrt_controller(float error, float p, float second_ord_lim, float dt)
911 {
912  float correction_rate;
913  if (is_negative(second_ord_lim) || is_zero(second_ord_lim)) {
914  // second order limit is zero or negative.
915  correction_rate = error*p;
916  } else if (is_zero(p)) {
917  // P term is zero but we have a second order limit.
918  if (is_positive(error)) {
919  correction_rate = safe_sqrt(2.0f*second_ord_lim*(error));
920  } else if (is_negative(error)) {
921  correction_rate = -safe_sqrt(2.0f*second_ord_lim*(-error));
922  } else {
923  correction_rate = 0.0f;
924  }
925  } else {
926  // Both the P and second order limit have been defined.
927  float linear_dist = second_ord_lim/sq(p);
928  if (error > linear_dist) {
929  correction_rate = safe_sqrt(2.0f*second_ord_lim*(error-(linear_dist/2.0f)));
930  } else if (error < -linear_dist) {
931  correction_rate = -safe_sqrt(2.0f*second_ord_lim*(-error-(linear_dist/2.0f)));
932  } else {
933  correction_rate = error*p;
934  }
935  }
936  if (!is_zero(dt)) {
937  // this ensures we do not get small oscillations by over shooting the error correction in the last time step.
938  return constrain_float(correction_rate, -fabsf(error)/dt, fabsf(error)/dt);
939  } else {
940  return correction_rate;
941  }
942 }
943 
944 // Inverse proportional controller with piecewise sqrt sections to constrain second derivative
945 float AC_AttitudeControl::stopping_point(float first_ord_mag, float p, float second_ord_lim)
946 {
947  if (is_positive(second_ord_lim) && !is_zero(second_ord_lim) && is_zero(p)) {
948  return (first_ord_mag*first_ord_mag)/(2.0f*second_ord_lim);
949  } else if ((is_negative(second_ord_lim) || is_zero(second_ord_lim)) && !is_zero(p)) {
950  return first_ord_mag/p;
951  } else if ((is_negative(second_ord_lim) || is_zero(second_ord_lim)) && is_zero(p)) {
952  return 0.0f;
953  }
954 
955  // calculate the velocity at which we switch from calculating the stopping point using a linear function to a sqrt function
956  float linear_velocity = second_ord_lim/p;
957 
958  if (fabsf(first_ord_mag) < linear_velocity) {
959  // if our current velocity is below the cross-over point we use a linear function
960  return first_ord_mag/p;
961  } else {
962  float linear_dist = second_ord_lim/sq(p);
963  float overshoot = (linear_dist*0.5f) + sq(first_ord_mag)/(2.0f*second_ord_lim);
964  if (is_positive(first_ord_mag)){
965  return overshoot;
966  } else {
967  return -overshoot;
968  }
969  }
970 }
971 
972 // Return roll rate step size in centidegrees/s that results in maximum output after 4 time steps
974 {
975  float alpha = get_rate_roll_pid().get_filt_alpha();
976  float alpha_remaining = 1-alpha;
977  return 2.0f*_motors.get_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());
978 }
979 
980 // Return pitch rate step size in centidegrees/s that results in maximum output after 4 time steps
982 {
983  float alpha = get_rate_pitch_pid().get_filt_alpha();
984  float alpha_remaining = 1-alpha;
985  return 2.0f*_motors.get_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());
986 }
987 
988 // Return yaw rate step size in centidegrees/s that results in maximum output after 4 time steps
990 {
991  float alpha = get_rate_yaw_pid().get_filt_alpha();
992  float alpha_remaining = 1-alpha;
993  return 2.0f*_motors.get_throttle_hover()*AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX/((alpha_remaining*alpha_remaining*alpha_remaining*alpha*get_rate_yaw_pid().kD())/_dt + get_rate_yaw_pid().kP());
994 }
void input_quaternion(Quaternion attitude_desired_quat)
static float stopping_point(float first_ord_mag, float p, float second_ord_lim)
void to_euler(float &roll, float &pitch, float &yaw) const
Definition: quaternion.cpp:272
void input_rate_bf_roll_pitch_yaw_3(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
void set_throttle_out_unstabilized(float throttle_in, bool reset_attitude_control, float filt_cutoff)
void euler_rate_to_ang_vel(const Vector3f &euler_rad, const Vector3f &euler_rate_rads, Vector3f &ang_vel_rads)
void ang_vel_limit(Vector3f &euler_rad, float ang_vel_roll_max, float ang_vel_pitch_max, float ang_vel_yaw_max) const
Vector3< float > Vector3f
Definition: vector3.h:246
void set_throttle_filter_cutoff(float filt_hz)
#define AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS
void to_axis_angle(Vector3f &v)
Definition: quaternion.cpp:189
void input_shaping_rate_predictor(Vector2f error_angle, Vector2f &target_ang_vel, float dt) const
virtual void 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)
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
AP_Float & kP()
Definition: AC_PID.h:60
#define AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT_CDS
float get_althold_lean_angle_max() const
static float input_shaping_angle(float error_angle, float smoothing_gain, float accel_max, float target_ang_vel, float dt)
#define AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX
#define AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS
void accel_limiting(bool enable_or_disable)
Quaternion _attitude_target_quat
float get_accel_pitch_max_radss() const
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float rate_target_to_motor_roll(float rate_actual_rads, float rate_target_rads)
const Matrix3f & get_rotation_body_to_ned(void) const
Definition: AP_AHRS_View.h:47
bool ang_vel_to_euler_rate(const Vector3f &euler_rad, const Vector3f &ang_vel_rads, Vector3f &euler_rate_rads)
virtual void input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)
struct AP_Motors::AP_Motors_limit limit
float get_d()
Definition: AC_PID.cpp:155
void input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
Vector3f get_gyro_latest(void) const
#define AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS
void from_euler(float roll, float pitch, float yaw)
Definition: quaternion.cpp:130
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
void reset_I()
Definition: AC_PID.cpp:179
static float input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt)
#define AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS
void from_rotation_matrix(const Matrix3f &m)
Definition: quaternion.cpp:76
#define AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT
float q3
Definition: quaternion.h:27
#define MIN(a, b)
Definition: usb_conf.h:215
#define ToDeg(x)
Definition: AP_Common.h:54
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
Vector3f update_ang_vel_target_from_att_error(Vector3f attitude_error_rot_vec_rad)
Object managing one P controller.
Definition: AC_P.h:13
const Vector3f & get_gyro(void) const
Definition: AP_AHRS_View.h:38
T y
Definition: vector2.h:37
float get_filt_alpha() const
Definition: AC_PID.cpp:217
Vector3f euler_accel_limit(Vector3f euler_rad, Vector3f euler_accel)
#define AC_ATTITUDE_THRUST_ERROR_ANGLE
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
ArduCopter attitude control library.
void input_euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds)
void set_input_filter_d(float input)
Definition: AC_PID.cpp:112
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
virtual float get_roll_trim_rad()
T y
Definition: vector3.h:67
T z
Definition: vector3.h:67
void rotation_matrix(Matrix3f &m) const
Definition: quaternion.cpp:24
static const struct AP_Param::GroupInfo var_info[]
float get_ff(float requested_rate)
Definition: AC_PID.cpp:162
static float sqrt_controller(float error, float p, float second_ord_lim, float dt)
virtual float get_throttle_hover() const =0
Vector3f _attitude_target_euler_rate
void set_throttle(float throttle_in)
void from_axis_angle(Vector3f v)
Definition: quaternion.cpp:154
void normalize()
Definition: vector3.h:176
#define AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS
#define AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS
virtual void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
float length(void) const
Definition: vector3.cpp:288
void shift_ef_yaw_target(float yaw_shift_cd)
void set_desired_rate(float desired)
Definition: AC_PID.h:80
#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_TC_DEFAULT
Vector3f _attitude_target_euler_angle
void thrust_heading_rotation_angles(Quaternion &att_to_quat, const Quaternion &att_from_quat, Vector3f &att_diff_angle, float &thrust_vec_dot)
virtual void input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)
float length(void) const
Definition: vector2.cpp:24
virtual AC_PID & get_rate_pitch_pid()=0
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
void normalize()
Definition: quaternion.cpp:297
float rate_target_to_motor_pitch(float rate_actual_rads, float rate_target_rads)
float wrap_2PI(const T radian)
Definition: AP_Math.cpp:167
static constexpr float radians(float deg)
Definition: AP_Math.h:158
virtual AC_PID & get_rate_roll_pid()=0
float q4
Definition: quaternion.h:27
void set_input_filter_all(float input)
Definition: AC_PID.cpp:87
AP_Float & kD()
Definition: AC_PID.h:62
bool is_negative(const T fVal1)
Definition: AP_Math.h:61
#define error(fmt, args ...)
float sq(const T val)
Definition: AP_Math.h:170
Quaternion inverse(void) const
Definition: quaternion.cpp:292
Quaternion _attitude_ang_error
virtual float rate_target_to_motor_yaw(float rate_actual_rads, float rate_target_rads)
float get_accel_roll_max_radss() const
float get_p(float error) const
Definition: AC_P.cpp:15
float get_integrator() const
Definition: AC_PID.h:76
float get_i()
Definition: AC_PID.cpp:140
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
Definition: AP_Param.h:109
float get_accel_yaw_max_radss() const
#define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT
AP_Float & kP()
Definition: AC_P.h:58
float get_p()
Definition: AC_PID.cpp:134
virtual AC_PID & get_rate_yaw_pid()=0
const AP_AHRS_View & _ahrs
#define AP_GROUPEND
Definition: AP_Param.h:121
float q2
Definition: quaternion.h:27
T x
Definition: vector3.h:67