APM:Libraries
AC_AttitudeControl.h
Go to the documentation of this file.
1 #pragma once
2 
5 
6 #include <AP_Common/AP_Common.h>
7 #include <AP_Param/AP_Param.h>
8 #include <AP_Math/AP_Math.h>
10 #include <AP_AHRS/AP_AHRS_View.h>
11 #include <AP_Motors/AP_Motors.h>
12 #include <AC_PID/AC_PID.h>
13 #include <AC_PID/AC_P.h>
14 
15 #define AC_ATTITUDE_CONTROL_ANGLE_P 4.5f // default angle P gain for roll, pitch and yaw
16 
17 #define AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS radians(40.0f) // minimum body-frame acceleration limit for the stability controller (for roll and pitch axis)
18 #define AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS radians(720.0f) // maximum body-frame acceleration limit for the stability controller (for roll and pitch axis)
19 #define AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS radians(10.0f) // minimum body-frame acceleration limit for the stability controller (for yaw axis)
20 #define AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS radians(120.0f) // maximum body-frame acceleration limit for the stability controller (for yaw axis)
21 #define AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT_CDS 6000 // constraint on yaw angle error in degrees. This should lead to maximum turn rate of 10deg/sec * Stab Rate P so by default will be 45deg/sec.
22 #define AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS 110000.0f // default maximum acceleration for roll/pitch axis in centidegrees/sec/sec
23 #define AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS 27000.0f // default maximum acceleration for yaw axis in centidegrees/sec/sec
24 
25 #define AC_ATTITUDE_RATE_CONTROLLER_TIMEOUT 1.0f // body-frame rate controller timeout in seconds
26 #define AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX 1.0f // body-frame rate controller maximum output (for roll-pitch axis)
27 #define AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX 1.0f // body-frame rate controller maximum output (for yaw axis)
28 
29 #define AC_ATTITUDE_THRUST_ERROR_ANGLE radians(30.0f) // Thrust angle error above which yaw corrections are limited
30 
31 #define AC_ATTITUDE_400HZ_DT 0.0025f // delta time in seconds for 400hz update rate
32 
33 #define AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT 1 // body-frame rate feedforward enabled by default
34 
35 #define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_TC_DEFAULT 1.0f // Time constant used to limit lean angle so that vehicle does not lose altitude
36 #define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX 0.8f // Max throttle used to limit lean angle so that vehicle does not lose altitude
37 
38 #define AC_ATTITUDE_CONTROL_MIN_DEFAULT 0.1f // minimum throttle mix default
39 #define AC_ATTITUDE_CONTROL_MAN_DEFAULT 0.5f // manual throttle mix default
40 #define AC_ATTITUDE_CONTROL_MAX_DEFAULT 0.5f // maximum throttle mix default
41 #define AC_ATTITUDE_CONTROL_MAX 5.0f // maximum throttle mix default
42 
43 #define AC_ATTITUDE_CONTROL_THR_MIX_DEFAULT 0.5f // ratio controlling the max throttle output during competing requests of low throttle from the pilot (or autopilot) and higher throttle for attitude control. Higher favours Attitude over pilot input
44 
46 public:
48  const AP_Vehicle::MultiCopter &aparm,
50  float dt) :
54  _dt(dt),
55  _angle_boost(0),
59  _ahrs(ahrs),
60  _aparm(aparm),
61  _motors(motors)
62  {
64  }
65 
66  // Empty destructor to suppress compiler warning
67  virtual ~AC_AttitudeControl() {}
68 
69  // pid accessors
73  virtual AC_PID& get_rate_roll_pid() = 0;
74  virtual AC_PID& get_rate_pitch_pid() = 0;
75  virtual AC_PID& get_rate_yaw_pid() = 0;
76 
77  // get the roll acceleration limit in centidegrees/s/s or radians/s/s
78  float get_accel_roll_max() const { return _accel_roll_max; }
79  float get_accel_roll_max_radss() const { return radians(_accel_roll_max*0.01f); }
80 
81  // Sets the roll acceleration limit in centidegrees/s/s
82  void set_accel_roll_max(float accel_roll_max) { _accel_roll_max = accel_roll_max; }
83 
84  // Sets and saves the roll acceleration limit in centidegrees/s/s
85  void save_accel_roll_max(float accel_roll_max) { _accel_roll_max.set_and_save(accel_roll_max); }
86 
87  // get the pitch acceleration limit in centidegrees/s/s or radians/s/s
88  float get_accel_pitch_max() const { return _accel_pitch_max; }
89  float get_accel_pitch_max_radss() const { return radians(_accel_pitch_max*0.01f); }
90 
91  // Sets the pitch acceleration limit in centidegrees/s/s
92  void set_accel_pitch_max(float accel_pitch_max) { _accel_pitch_max = accel_pitch_max; }
93 
94  // Sets and saves the pitch acceleration limit in centidegrees/s/s
95  void save_accel_pitch_max(float accel_pitch_max) { _accel_pitch_max.set_and_save(accel_pitch_max); }
96 
97  // get the yaw acceleration limit in centidegrees/s/s or radians/s/s
98  float get_accel_yaw_max() const { return _accel_yaw_max; }
99  float get_accel_yaw_max_radss() const { return radians(_accel_yaw_max*0.01f); }
100 
101  // Sets the yaw acceleration limit in centidegrees/s/s
102  void set_accel_yaw_max(float accel_yaw_max) { _accel_yaw_max = accel_yaw_max; }
103 
104  // Sets and saves the yaw acceleration limit in centidegrees/s/s
105  void save_accel_yaw_max(float accel_yaw_max) { _accel_yaw_max.set_and_save(accel_yaw_max); }
106 
107  // set the rate control input smoothing time constant
108  void set_input_tc(float input_tc) { _input_tc = constrain_float(input_tc, 0.0f, 1.0f); }
109 
110  // Ensure attitude controller have zero errors to relax rate controller output
112 
113  // reset rate controller I terms
115 
116  // Sets attitude target to vehicle attitude
118 
119  // Sets yaw target to vehicle heading
121 
122  // Shifts earth frame yaw target by yaw_shift_cd. yaw_shift_cd should be in centidegrees and is added to the current target heading
123  void shift_ef_yaw_target(float yaw_shift_cd);
124 
125  // handle reset of attitude from EKF since the last iteration
126  void inertial_frame_reset();
127 
128  // Command a Quaternion attitude with feedforward and smoothing
129  void input_quaternion(Quaternion attitude_desired_quat);
130 
131  // Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
132  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);
133 
134  // Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
135  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);
136 
137  // Command an euler roll, pitch, and yaw rate with angular velocity feedforward and smoothing
138  void input_euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds);
139 
140  // Command an angular velocity with angular velocity feedforward and smoothing
141  virtual void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds);
142 
143  // Command an angular velocity with angular velocity feedforward and smoothing
144  void input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds);
145 
146  // Command an angular velocity with angular velocity smoothing using rate loops only with integrated rate error stabilization
147  void input_rate_bf_roll_pitch_yaw_3(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds);
148 
149  // Command an angular step (i.e change) in body frame angle
150  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);
151 
152  // Run angular velocity controller and send outputs to the motors
153  virtual void rate_controller_run() = 0;
154 
155  // Convert a 321-intrinsic euler angle derivative to an angular velocity vector
156  void euler_rate_to_ang_vel(const Vector3f& euler_rad, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads);
157 
158  // Convert an angular velocity vector to a 321-intrinsic euler angle derivative
159  // Returns false if the vehicle is pitched 90 degrees up or down
160  bool ang_vel_to_euler_rate(const Vector3f& euler_rad, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads);
161 
162  // Specifies whether the attitude controller should use the square root controller in the attitude correction.
163  // This is used during Autotune to ensure the P term is tuned without being influenced by the acceleration limit of the square root controller.
164  void use_sqrt_controller(bool use_sqrt_cont) { _use_sqrt_controller = use_sqrt_cont; }
165 
166  // Return 321-intrinsic euler angles in centidegrees representing the rotation from NED earth frame to the
167  // attitude controller's target attitude.
168  // **NOTE** Using vector3f*deg(100) is more efficient than deg(vector3f)*100 or deg(vector3d*100) because it gives the
169  // same result with the fewest multiplications. Even though it may look like a bug, it is intentional. See issue 4895.
171 
172  // Return the angle between the target thrust vector and the current thrust vector.
174 
175  // Set x-axis angular velocity in centidegrees/s
176  void rate_bf_roll_target(float rate_cds) { _rate_target_ang_vel.x = radians(rate_cds*0.01f); }
177 
178  // Set y-axis angular velocity in centidegrees/s
179  void rate_bf_pitch_target(float rate_cds) { _rate_target_ang_vel.y = radians(rate_cds*0.01f); }
180 
181  // Set z-axis angular velocity in centidegrees/s
182  void rate_bf_yaw_target(float rate_cds) { _rate_target_ang_vel.z = radians(rate_cds*0.01f); }
183 
184  // Return roll rate step size in radians/s that results in maximum output after 4 time steps
185  float max_rate_step_bf_roll();
186 
187  // Return pitch rate step size in radians/s that results in maximum output after 4 time steps
188  float max_rate_step_bf_pitch();
189 
190  // Return yaw rate step size in radians/s that results in maximum output after 4 time steps
191  float max_rate_step_bf_yaw();
192 
193  // Return roll step size in radians that results in maximum output after 4 time steps
195 
196  // Return pitch step size in radians that results in maximum output after 4 time steps
198 
199  // Return yaw step size in radians that results in maximum output after 4 time steps
201 
202  // Return angular velocity in radians used in the angular velocity controller
204 
205  // Enable or disable body-frame feed forward
206  void bf_feedforward(bool enable_or_disable) { _rate_bf_ff_enabled = enable_or_disable; }
207 
208  // Enable or disable body-frame feed forward and save
209  void bf_feedforward_save(bool enable_or_disable) { _rate_bf_ff_enabled.set_and_save(enable_or_disable); }
210 
211  // Return body-frame feed forward setting
213 
214  // Enable or disable body-frame feed forward
215  void accel_limiting(bool enable_or_disable);
216 
217  // Update Alt_Hold angle maximum
218  virtual void update_althold_lean_angle_max(float throttle_in) = 0;
219 
220  // Set output throttle
221  virtual void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) = 0;
222 
223  // Set output throttle and disable stabilization
224  void set_throttle_out_unstabilized(float throttle_in, bool reset_attitude_control, float filt_cutoff);
225 
226  // get throttle passed into attitude controller (i.e. throttle_in provided to set_throttle_out)
227  float get_throttle_in() const { return _throttle_in; }
228 
229  // Return throttle increase applied for tilt compensation
230  float angle_boost() const { return _angle_boost; }
231 
232  // Return tilt angle limit for pilot input that prioritises altitude hold over lean angle
233  float get_althold_lean_angle_max() const;
234 
235  // Return configured tilt angle limit in centidegrees
236  float lean_angle_max() const { return _aparm.angle_max; }
237 
238  // Proportional controller with piecewise sqrt sections to constrain second derivative
239  static float sqrt_controller(float error, float p, float second_ord_lim, float dt);
240 
241  // Inverse proportional controller with piecewise sqrt sections to constrain second derivative
242  static float stopping_point(float first_ord_mag, float p, float second_ord_lim);
243 
244  // calculates the velocity correction from an angle error. The angular velocity has acceleration and
245  // deceleration limits including basic jerk limiting using smoothing_gain
246  static float input_shaping_angle(float error_angle, float smoothing_gain, float accel_max, float target_ang_vel, float dt);
247 
248  // limits the acceleration and deceleration of a velocity request
249  static float input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt);
250 
251  // calculates the expected angular velocity correction from an angle error based on the AC_AttitudeControl settings.
252  // This function can be used to predict the delay associated with angle requests.
253  void input_shaping_rate_predictor(Vector2f error_angle, Vector2f& target_ang_vel, float dt) const;
254 
255  // translates body frame acceleration limits to the euler axis
256  void ang_vel_limit(Vector3f& euler_rad, float ang_vel_roll_max, float ang_vel_pitch_max, float ang_vel_yaw_max) const;
257 
258  // translates body frame acceleration limits to the euler axis
259  Vector3f euler_accel_limit(Vector3f euler_rad, Vector3f euler_accel);
260 
261  // thrust_heading_rotation_angles - calculates two ordered rotations to move the att_from_quat quaternion to the att_to_quat quaternion.
262  // The first rotation corrects the thrust vector and the second rotation corrects the heading vector.
263  void thrust_heading_rotation_angles(Quaternion& att_to_quat, const Quaternion& att_from_quat, Vector3f& att_diff_angle, float& thrust_vec_dot);
264 
265  // Calculates the body frame angular velocities to follow the target attitude
267 
268  // sanity check parameters. should be called once before take-off
269  virtual void parameter_sanity_check() {}
270 
271  // return true if the rpy mix is at lowest value
272  virtual bool is_throttle_mix_min() const { return true; }
273 
274  // control rpy throttle mix
275  virtual void set_throttle_mix_min() {}
276  virtual void set_throttle_mix_man() {}
277  virtual void set_throttle_mix_max() {}
278  virtual void set_throttle_mix_value(float value) {}
279  virtual float get_throttle_mix(void) const { return 0; }
280 
281  // enable use of flybass passthrough on heli
282  virtual void use_flybar_passthrough(bool passthrough, bool tail_passthrough) {}
283 
284  // use_leaky_i - controls whether we use leaky i term for body-frame to motor output stage on heli
285  virtual void use_leaky_i(bool leaky_i) {}
286 
287  // set_hover_roll_scalar - scales Hover Roll Trim parameter. To be used by vehicle code according to vehicle condition.
288  virtual void set_hover_roll_trim_scalar(float scalar) {}
289 
290  // passthrough_bf_roll_pitch_rate_yaw - roll and pitch are passed through directly, body-frame rate target for yaw
291  virtual void passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds) {};
292 
293  // enable inverted flight on backends that support it
294  virtual void set_inverted_flight(bool inverted) {}
295 
296  // User settable parameters
297  static const struct AP_Param::GroupInfo var_info[];
298 
299 protected:
300 
301  // Update rate_target_ang_vel using attitude_error_rot_vec_rad
302  Vector3f update_ang_vel_target_from_att_error(Vector3f attitude_error_rot_vec_rad);
303 
304  // Run the roll angular velocity PID controller and return the output
305  float rate_target_to_motor_roll(float rate_actual_rads, float rate_target_rads);
306 
307  // Run the pitch angular velocity PID controller and return the output
308  float rate_target_to_motor_pitch(float rate_actual_rads, float rate_target_rads);
309 
310  // Run the yaw angular velocity PID controller and return the output
311  virtual float rate_target_to_motor_yaw(float rate_actual_rads, float rate_target_rads);
312 
313  // Return angle in radians to be added to roll angle. Used by heli to counteract
314  // tail rotor thrust in hover. Overloaded by AC_Attitude_Heli to return angle.
315  virtual float get_roll_trim_rad() { return 0;}
316 
317  // Return the yaw slew rate limit in radians/s
318  float get_slew_yaw_rads() { return radians(_slew_yaw*0.01f); }
319 
320  // Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes
321  AP_Float _slew_yaw;
322 
323  // Maximum angular velocity (in degrees/second) for earth-frame roll, pitch and yaw axis
327 
328  // Maximum rotation acceleration for earth-frame roll axis
329  AP_Float _accel_roll_max;
330 
331  // Maximum rotation acceleration for earth-frame pitch axis
333 
334  // Maximum rotation acceleration for earth-frame yaw axis
335  AP_Float _accel_yaw_max;
336 
337  // Enable/Disable body frame rate feed forward
339 
340  // Enable/Disable angle boost
342 
343  // angle controller P objects
347 
348  // Angle limit time constant (to maintain altitude)
349  AP_Float _angle_limit_tc;
350 
351  // rate controller input smoothing time constant
352  AP_Float _input_tc;
353 
354  // Intersampling period in seconds
355  float _dt;
356 
357  // This represents a 321-intrinsic rotation in NED frame to the target (setpoint)
358  // attitude used in the attitude controller, in radians.
360 
361  // This represents the angular velocity of the target (setpoint) attitude used in
362  // the attitude controller as 321-intrinsic euler angle derivatives, in radians per
363  // second.
365 
366  // This represents a quaternion rotation in NED frame to the target (setpoint)
367  // attitude used in the attitude controller.
369 
370  // This represents the angular velocity of the target (setpoint) attitude used in
371  // the attitude controller as an angular velocity vector, in radians per second in
372  // the target attitude frame.
374 
375  // This represents the angular velocity in radians per second in the body frame, used in the angular
376  // velocity controller.
378 
379  // This represents a quaternion attitude error in the body frame, used for inertial frame reset handling.
381 
382  // The angle between the target thrust vector and the current thrust vector.
384 
385  // throttle provided as input to attitude controller. This does not include angle boost.
386  float _throttle_in = 0.0f;
387 
388  // This represents the throttle increase applied for tilt compensation.
389  // Used only for logging.
391 
392  // Specifies whether the attitude controller should use the square root controller in the attitude correction.
393  // This is used during Autotune to ensure the P term is tuned without being influenced by the acceleration limit of the square root controller.
395 
396  // Filtered Alt_Hold lean angle max - used to limit lean angle when throttle is saturated using Alt_Hold
398 
399  // desired throttle_low_comp value, actual throttle_low_comp is slewed towards this value over 1~2 seconds
401 
402  // mix between throttle and hover throttle for 0 to 1 and ratio above hover throttle for >1
404 
405  // References to external libraries
409 
410 protected:
411  /*
412  state of control monitoring
413  */
414  struct {
415  float rms_roll_P;
416  float rms_roll_D;
417  float rms_pitch_P;
418  float rms_pitch_D;
419  float rms_yaw;
421 
422  // update state in ControlMonitor
423  void control_monitor_filter_pid(float value, float &rms_P);
424  void control_monitor_update(void);
425 
426  // true in inverted flight mode
428 
429 public:
430  // log a CTRL message
431  void control_monitor_log(void);
432 
433  // return current RMS controller filter for each axis
434  float control_monitor_rms_output_roll(void) const;
435  float control_monitor_rms_output_roll_P(void) const;
436  float control_monitor_rms_output_roll_D(void) const;
437  float control_monitor_rms_output_pitch_P(void) const;
438  float control_monitor_rms_output_pitch_D(void) const;
439  float control_monitor_rms_output_pitch(void) const;
440  float control_monitor_rms_output_yaw(void) const;
441 };
442 
443 #define AC_ATTITUDE_CONTROL_LOG_FORMAT(msg) { msg, sizeof(AC_AttitudeControl::log_Attitude), \
444  "ATT", "cccccCC", "RollIn,Roll,PitchIn,Pitch,YawIn,Yaw,NavYaw" }
void input_quaternion(Quaternion attitude_desired_quat)
void control_monitor_log(void)
static float stopping_point(float first_ord_mag, float p, float second_ord_lim)
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_accel_pitch_max(float accel_pitch_max)
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)
virtual bool is_throttle_mix_min() const
float control_monitor_rms_output_roll_P(void) const
void use_sqrt_controller(bool use_sqrt_cont)
float get_att_error_angle_deg() const
void ang_vel_limit(Vector3f &euler_rad, float ang_vel_roll_max, float ang_vel_pitch_max, float ang_vel_yaw_max) const
virtual void use_flybar_passthrough(bool passthrough, bool tail_passthrough)
void input_shaping_rate_predictor(Vector2f error_angle, Vector2f &target_ang_vel, float dt) const
Generic PID algorithm, with EEPROM-backed storage of constants.
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)
void set_input_tc(float input_tc)
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
void bf_feedforward(bool enable_or_disable)
void set_accel_yaw_max(float accel_yaw_max)
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)
void accel_limiting(bool enable_or_disable)
Quaternion _attitude_target_quat
virtual void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff)=0
float get_accel_pitch_max_radss() const
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)
void input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
float get_accel_roll_max() const
void save_accel_pitch_max(float accel_pitch_max)
void save_accel_yaw_max(float accel_yaw_max)
void rate_bf_pitch_target(float rate_cds)
void bf_feedforward_save(bool enable_or_disable)
static float input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt)
#define AC_ATTITUDE_CONTROL_THR_MIX_DEFAULT
void from_rotation_matrix(const Matrix3f &m)
Definition: quaternion.cpp:76
#define AC_ATTITUDE_CONTROL_ANGLE_P
Vector3f update_ang_vel_target_from_att_error(Vector3f attitude_error_rot_vec_rad)
AP_MotorsMatrix motors(400)
virtual void parameter_sanity_check()
Object managing one P controller.
Definition: AC_P.h:13
A system for managing and storing variables that are of general interest to the system.
Vector3f euler_accel_limit(Vector3f euler_rad, Vector3f euler_accel)
float lean_angle_max() const
float get_accel_pitch_max() const
float control_monitor_rms_output_roll_D(void) const
void set_accel_roll_max(float accel_roll_max)
void input_euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds)
#define f(i)
virtual float get_roll_trim_rad()
T y
Definition: vector3.h:67
void control_monitor_filter_pid(float value, float &rms_P)
Vector3f rate_bf_targets() const
T z
Definition: vector3.h:67
void rate_bf_yaw_target(float rate_cds)
static const struct AP_Param::GroupInfo var_info[]
static float sqrt_controller(float error, float p, float second_ord_lim, float dt)
AC_AttitudeControl(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_Motors &motors, float dt)
Vector3f _attitude_target_euler_rate
virtual void set_throttle_mix_max()
virtual void set_inverted_flight(bool inverted)
float control_monitor_rms_output_pitch_P(void) const
virtual float get_throttle_mix(void) const
void set_yaw_target_to_current_heading()
float control_monitor_rms_output_yaw(void) const
virtual void rate_controller_run()=0
virtual void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
void rate_bf_roll_target(float rate_cds)
void shift_ef_yaw_target(float yaw_shift_cd)
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)
Common definitions and utility routines for the ArduPilot libraries.
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)
struct AC_AttitudeControl::@0 _control_monitor
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
float rate_target_to_motor_pitch(float rate_actual_rads, float rate_target_rads)
virtual void set_throttle_mix_value(float value)
void set_attitude_target_to_current_attitude()
static constexpr float radians(float deg)
Definition: AP_Math.h:158
virtual AC_PID & get_rate_roll_pid()=0
Vector3f get_att_target_euler_cd() const
#define error(fmt, args ...)
float angle_boost() const
virtual void use_leaky_i(bool leaky_i)
float value
float get_accel_yaw_max() const
Quaternion _attitude_ang_error
virtual void update_althold_lean_angle_max(float throttle_in)=0
virtual float rate_target_to_motor_yaw(float rate_actual_rads, float rate_target_rads)
float get_accel_roll_max_radss() const
void control_monitor_update(void)
float control_monitor_rms_output_pitch_D(void) const
#define degrees(x)
Definition: moduletest.c:23
void save_accel_roll_max(float accel_roll_max)
Copter PID control class.
Definition: AC_PID.h:17
virtual void set_throttle_mix_man()
float control_monitor_rms_output_pitch(void) const
float get_accel_yaw_max_radss() const
float control_monitor_rms_output_roll(void) const
AP_Float & kP()
Definition: AC_P.h:58
virtual void set_hover_roll_trim_scalar(float scalar)
virtual AC_PID & get_rate_yaw_pid()=0
const AP_Vehicle::MultiCopter & _aparm
const AP_AHRS_View & _ahrs
virtual void set_throttle_mix_min()
virtual void passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds)
T x
Definition: vector3.h:67
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
float get_throttle_in() const