11 #define AC_ATC_SUB_ANGLE_P 6.0f 12 #define AC_ATC_SUB_ACCEL_Y_MAX 110000.0f 15 #define AC_ATC_SUB_RATE_RP_P 0.135f 16 #define AC_ATC_SUB_RATE_RP_I 0.090f 17 #define AC_ATC_SUB_RATE_RP_D 0.0036f 18 #define AC_ATC_SUB_RATE_RP_IMAX 0.444f 19 #define AC_ATC_SUB_RATE_RP_FILT_HZ 30.0f 20 #define AC_ATC_SUB_RATE_YAW_P 0.180f 21 #define AC_ATC_SUB_RATE_YAW_I 0.018f 22 #define AC_ATC_SUB_RATE_YAW_D 0.0f 23 #define AC_ATC_SUB_RATE_YAW_IMAX 0.222f 24 #define AC_ATC_SUB_RATE_YAW_FILT_HZ 5.0f 42 void set_throttle_out(
float throttle_in,
bool apply_angle_boost,
float filt_cutoff)
override;
AC_PID & get_rate_roll_pid()
void parameter_sanity_check()
void rate_controller_run()
void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override
AP_MotorsMatrix motors(400)
float _throttle_rpy_mix_desired
float get_throttle_avg_max(float throttle_in)
ArduCopter attitude control library.
static const struct AP_Param::GroupInfo var_info[]
void set_throttle_mix_man() override
void set_throttle_mix_min() override
float get_throttle_boosted(float throttle_in)
AP_MotorsMulticopter & _motors_multi
void set_throttle_mix_max() override
bool is_throttle_mix_min() const override
Motor control class for Multicopters.
void update_throttle_rpy_mix()
Copter PID control class.
AC_PID & get_rate_pitch_pid()
void update_althold_lean_angle_max(float throttle_in) override
virtual ~AC_AttitudeControl_Sub()
AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter &motors, float dt)
AC_PID & get_rate_yaw_pid()