15 #define AC_ATTITUDE_CONTROL_ANGLE_P 4.5f // default angle P gain for roll, pitch and yaw 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 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) 29 #define AC_ATTITUDE_THRUST_ERROR_ANGLE radians(30.0f) // Thrust angle error above which yaw corrections are limited 31 #define AC_ATTITUDE_400HZ_DT 0.0025f // delta time in seconds for 400hz update rate 33 #define AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT 1 // body-frame rate feedforward enabled by default 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 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 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 221 virtual void set_throttle_out(
float throttle_in,
bool apply_angle_boost,
float filt_cutoff) = 0;
242 static float stopping_point(
float first_ord_mag,
float p,
float second_ord_lim);
246 static float input_shaping_angle(
float error_angle,
float smoothing_gain,
float accel_max,
float target_ang_vel,
float dt);
249 static float input_shaping_ang_vel(
float target_ang_vel,
float desired_ang_vel,
float accel_max,
float dt);
256 void ang_vel_limit(
Vector3f& euler_rad,
float ang_vel_roll_max,
float ang_vel_pitch_max,
float ang_vel_yaw_max)
const;
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)
float get_slew_yaw_rads()
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 relax_attitude_controllers()
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)
AP_Float _ang_vel_pitch_max
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 ~AC_AttitudeControl()
virtual void use_flybar_passthrough(bool passthrough, bool tail_passthrough)
float max_angle_step_bf_roll()
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)
float max_angle_step_bf_yaw()
void set_input_tc(float input_tc)
void bf_feedforward(bool enable_or_disable)
float max_rate_step_bf_roll()
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
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 attitude_controller_run_quat()
void input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
AP_Int8 _angle_boost_enabled
float get_accel_roll_max() const
AP_Int8 _rate_bf_ff_enabled
float max_angle_step_bf_pitch()
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)
float _thrust_error_angle
#define AC_ATTITUDE_CONTROL_THR_MIX_DEFAULT
void from_rotation_matrix(const Matrix3f &m)
bool _use_sqrt_controller
#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()
AC_P & get_angle_roll_p()
Object managing one P controller.
A system for managing and storing variables that are of general interest to the system.
void reset_rate_controller_I_terms()
AP_Float _accel_pitch_max
Vector3f euler_accel_limit(Vector3f euler_rad, Vector3f euler_accel)
float _throttle_rpy_mix_desired
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)
AP_Float _ang_vel_yaw_max
virtual float get_roll_trim_rad()
void control_monitor_filter_pid(float value, float &rms_P)
Vector3f rate_bf_targets() const
void inertial_frame_reset()
void rate_bf_yaw_target(float rate_cds)
Vector3f _attitude_target_ang_vel
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()
AC_P & get_angle_pitch_p()
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
float _althold_lean_angle_max
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
Vector3f _rate_target_ang_vel
float constrain_float(const float amt, const float low, const float high)
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)
virtual AC_PID & get_rate_roll_pid()=0
Vector3f get_att_target_euler_cd() const
AP_Float _ang_vel_roll_max
#define error(fmt, args ...)
float angle_boost() const
virtual void use_leaky_i(bool leaky_i)
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
void save_accel_roll_max(float accel_roll_max)
Copter PID control class.
virtual void set_throttle_mix_man()
float max_rate_step_bf_pitch()
float control_monitor_rms_output_pitch(void) const
float get_accel_yaw_max_radss() const
float control_monitor_rms_output_roll(void) const
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
bool get_bf_feedforward()
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)
float max_rate_step_bf_yaw()
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
float get_throttle_in() const