5 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) 7 # define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.2f // Soft 10 # define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.15f // Medium 154 if (reset_attitude_control) {
247 float euler_roll_angle =
radians(euler_roll_angle_cd*0.01
f);
248 float euler_pitch_angle =
radians(euler_pitch_angle_cd*0.01f);
249 float euler_yaw_rate =
radians(euler_yaw_rate_cds*0.01f);
298 float euler_roll_angle =
radians(euler_roll_angle_cd*0.01
f);
299 float euler_pitch_angle =
radians(euler_pitch_angle_cd*0.01f);
300 float euler_yaw_angle =
radians(euler_yaw_angle_cd*0.01f);
356 float euler_roll_rate =
radians(euler_roll_rate_cds*0.01
f);
357 float euler_pitch_rate =
radians(euler_pitch_rate_cds*0.01f);
358 float euler_yaw_rate =
radians(euler_yaw_rate_cds*0.01f);
398 float roll_rate_rads =
radians(roll_rate_bf_cds*0.01
f);
399 float pitch_rate_rads =
radians(pitch_rate_bf_cds*0.01f);
400 float yaw_rate_rads =
radians(yaw_rate_bf_cds*0.01f);
435 float roll_rate_rads =
radians(roll_rate_bf_cds*0.01
f);
436 float pitch_rate_rads =
radians(pitch_rate_bf_cds*0.01f);
437 float yaw_rate_rads =
radians(yaw_rate_bf_cds*0.01f);
458 float roll_rate_rads =
radians(roll_rate_bf_cds*0.01
f);
459 float pitch_rate_rads =
radians(pitch_rate_bf_cds*0.01f);
460 float yaw_rate_rads =
radians(yaw_rate_bf_cds*0.01f);
491 _attitude_ang_error.to_axis_angle(attitude_error_vector);
504 float roll_step_rads =
radians(roll_angle_step_bf_cd*0.01
f);
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);
550 Quaternion desired_ang_vel_quat = to_to_from_quat.
inverse()*attitude_target_ang_vel_quat*to_to_from_quat;
592 Vector3f att_from_thrust_vec = att_from_rot_matrix*
Vector3f(0.0
f,0.0
f,1.0
f);
595 Vector3f thrust_vec_cross = att_from_thrust_vec % att_to_thrust_vec;
598 thrust_vec_dot = acosf(
constrain_float(att_from_thrust_vec * att_to_thrust_vec,-1.0
f,1.0
f));
601 float thrust_vector_length = thrust_vec_cross.
length();
604 thrust_vec_dot = 0.0f;
606 thrust_vec_cross /= thrust_vector_length;
609 thrust_vec_correction_quat.
from_axis_angle(thrust_vec_cross, thrust_vec_dot);
612 thrust_vec_correction_quat = att_from_quat.
inverse()*thrust_vec_correction_quat*att_from_quat;
620 att_diff_angle.
x = rotation.
x;
621 att_diff_angle.
y = rotation.
y;
625 att_diff_angle.
z = rotation.
z;
635 att_to_quat = att_from_quat*thrust_vec_correction_quat*yaw_vec_correction_quat;
644 float desired_ang_vel =
sqrt_controller(error_angle, 1.0
f /
MAX(input_tc, 0.01
f), accel_max, dt);
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);
658 return desired_ang_vel;
675 Vector3f ang_vel(target_ang_vel.
x, target_ang_vel.
y, 0.0f);
678 target_ang_vel.
x = ang_vel.
x;
679 target_ang_vel.
y = ang_vel.
y;
686 if (!
is_zero(ang_vel_roll_max)) {
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);
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.0
f) {
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;
700 if (!
is_zero(ang_vel_yaw_max)) {
714 rot_accel.
x = euler_accel.
x;
715 rot_accel.
y = euler_accel.
y;
716 rot_accel.
z = euler_accel.
z;
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);
728 float yaw_shift =
radians(yaw_shift_cd*0.01
f);
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);
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;
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);
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;
809 return rate_target_ang_vel;
815 float rate_error_rads = rate_target_rads - rate_actual_rads;
838 float rate_error_rads = rate_target_rads - rate_actual_rads;
861 float rate_error_rads = rate_target_rads - rate_actual_rads;
912 float correction_rate;
915 correction_rate = error*p;
919 correction_rate =
safe_sqrt(2.0
f*second_ord_lim*(error));
921 correction_rate = -
safe_sqrt(2.0
f*second_ord_lim*(-error));
923 correction_rate = 0.0f;
927 float linear_dist = second_ord_lim/
sq(p);
928 if (error > linear_dist) {
929 correction_rate =
safe_sqrt(2.0
f*second_ord_lim*(error-(linear_dist/2.0
f)));
930 }
else if (error < -linear_dist) {
931 correction_rate = -
safe_sqrt(2.0
f*second_ord_lim*(-error-(linear_dist/2.0
f)));
933 correction_rate = error*p;
938 return constrain_float(correction_rate, -fabsf(error)/dt, fabsf(error)/dt);
940 return correction_rate;
948 return (first_ord_mag*first_ord_mag)/(2.0f*second_ord_lim);
950 return first_ord_mag/p;
956 float linear_velocity = second_ord_lim/p;
958 if (fabsf(first_ord_mag) < linear_velocity) {
960 return first_ord_mag/p;
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);
976 float alpha_remaining = 1-alpha;
984 float alpha_remaining = 1-alpha;
992 float alpha_remaining = 1-alpha;
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
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_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)
AP_Float _ang_vel_pitch_max
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
void set_throttle_filter_cutoff(float filt_hz)
#define AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS
void to_axis_angle(Vector3f &v)
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)
#define AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT_CDS
float max_rate_step_bf_roll()
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)
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)
struct AP_Motors::AP_Motors_limit limit
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)
Vector3f get_gyro_latest(void) const
#define AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS
void from_euler(float roll, float pitch, float yaw)
AP_Int8 _rate_bf_ff_enabled
bool is_positive(const T fVal1)
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
float _thrust_error_angle
void from_rotation_matrix(const Matrix3f &m)
bool _use_sqrt_controller
#define AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Vector3f update_ang_vel_target_from_att_error(Vector3f attitude_error_rot_vec_rad)
Object managing one P controller.
const Vector3f & get_gyro(void) const
float get_filt_alpha() const
void reset_rate_controller_I_terms()
AP_Float _accel_pitch_max
Vector3f euler_accel_limit(Vector3f euler_rad, Vector3f euler_accel)
#define AC_ATTITUDE_THRUST_ERROR_ANGLE
float wrap_PI(const T radian)
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)
bool is_zero(const T fVal1)
AP_Float _ang_vel_yaw_max
virtual float get_roll_trim_rad()
void inertial_frame_reset()
Vector3f _attitude_target_ang_vel
void rotation_matrix(Matrix3f &m) const
static const struct AP_Param::GroupInfo var_info[]
float get_ff(float requested_rate)
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)
#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)
void shift_ef_yaw_target(float yaw_shift_cd)
void set_desired_rate(float desired)
#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_TC_DEFAULT
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)
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)
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)
float wrap_2PI(const T radian)
static constexpr float radians(float deg)
virtual AC_PID & get_rate_roll_pid()=0
void set_input_filter_all(float input)
AP_Float _ang_vel_roll_max
bool is_negative(const T fVal1)
#define error(fmt, args ...)
Quaternion inverse(void) const
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
float get_integrator() const
float max_rate_step_bf_pitch()
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
float get_accel_yaw_max_radss() const
#define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT
virtual AC_PID & get_rate_yaw_pid()=0
const AP_AHRS_View & _ahrs
float max_rate_step_bf_yaw()