10 #ifndef AC_ATC_MULTI_RATE_RP_P 11 # define AC_ATC_MULTI_RATE_RP_P 0.135f 13 #ifndef AC_ATC_MULTI_RATE_RP_I 14 # define AC_ATC_MULTI_RATE_RP_I 0.090f 16 #ifndef AC_ATC_MULTI_RATE_RP_D 17 # define AC_ATC_MULTI_RATE_RP_D 0.0036f 19 #ifndef AC_ATC_MULTI_RATE_RP_IMAX 20 # define AC_ATC_MULTI_RATE_RP_IMAX 0.5f 22 #ifndef AC_ATC_MULTI_RATE_RP_FILT_HZ 23 # define AC_ATC_MULTI_RATE_RP_FILT_HZ 20.0f 25 #ifndef AC_ATC_MULTI_RATE_YAW_P 26 # define AC_ATC_MULTI_RATE_YAW_P 0.180f 28 #ifndef AC_ATC_MULTI_RATE_YAW_I 29 # define AC_ATC_MULTI_RATE_YAW_I 0.018f 31 #ifndef AC_ATC_MULTI_RATE_YAW_D 32 # define AC_ATC_MULTI_RATE_YAW_D 0.0f 34 #ifndef AC_ATC_MULTI_RATE_YAW_IMAX 35 # define AC_ATC_MULTI_RATE_YAW_IMAX 0.5f 37 #ifndef AC_ATC_MULTI_RATE_YAW_FILT_HZ 38 # define AC_ATC_MULTI_RATE_YAW_FILT_HZ 2.5f 58 void set_throttle_out(
float throttle_in,
bool apply_angle_boost,
float filt_cutoff)
override;
AC_PID & get_rate_roll_pid()
float get_throttle_mix(void) const override
AP_MotorsMulticopter & _motors_multi
AP_MotorsMatrix motors(400)
float _throttle_rpy_mix_desired
void set_throttle_mix_man() override
ArduCopter attitude control library.
void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override
void set_throttle_mix_max() override
void set_throttle_mix_value(float value) override
void rate_controller_run()
bool is_throttle_mix_min() const override
AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter &motors, float dt)
void update_throttle_rpy_mix()
static const struct AP_Param::GroupInfo var_info[]
void parameter_sanity_check()
Motor control class for Multicopters.
virtual ~AC_AttitudeControl_Multi()
float get_throttle_avg_max(float throttle_in)
Copter PID control class.
void update_althold_lean_angle_max(float throttle_in) override
float get_throttle_boosted(float throttle_in)
void set_throttle_mix_min() override
AC_PID & get_rate_pitch_pid()
AC_PID & get_rate_yaw_pid()