160 float yaw_rate_bf_rads =
radians(yaw_rate_bf_cds*0.01
f);
179 rate_change_rads =
constrain_float(rate_change_rads, -rate_change_limit_rads, rate_change_limit_rads);
286 float roll_pd, roll_i, roll_ff;
287 float pitch_pd, pitch_i, pitch_ff;
288 float rate_roll_error_rads, rate_pitch_error_rads;
289 float roll_out, pitch_out;
292 rate_roll_error_rads = rate_roll_target_rads - rate_rads.
x;
293 rate_pitch_error_rads = rate_pitch_target_rads - rate_rads.
y;
309 if (!
_flags_heli.
limit_roll || ((roll_i>0&&rate_roll_error_rads<0)||(roll_i<0&&rate_roll_error_rads>0))){
321 if (!
_flags_heli.
limit_pitch || ((pitch_i>0&&rate_pitch_error_rads<0)||(pitch_i<0&&rate_pitch_error_rads>0))){
334 roll_out = roll_pd + roll_i + roll_ff;
335 pitch_out = pitch_pd + pitch_i + pitch_ff;
361 int32_t piro_roll_i, piro_pitch_i;
363 piro_roll_i = roll_i;
364 piro_pitch_i = pitch_i;
367 yawratevector.
x = cosf(-rate_rads.
z *
_dt);
368 yawratevector.
y = sinf(-rate_rads.
z *
_dt);
371 roll_i = piro_roll_i * yawratevector.
x - piro_pitch_i * yawratevector.
y;
372 pitch_i = piro_pitch_i * yawratevector.
x + piro_roll_i * yawratevector.
y;
384 float rate_error_rads;
388 rate_error_rads = rate_target_rads - rate_yaw_actual_rads;
413 yaw_out = pd + i + vff;
445 euler_roll_angle_cd =
wrap_180_cd(euler_roll_angle_cd + 18000);
454 euler_roll_angle_cd =
wrap_180_cd(euler_roll_angle_cd + 18000);
float norm(const T first, const U second, const Params... parameters)
virtual void rate_controller_run()
Vector3< float > Vector3f
void set_throttle_filter_cutoff(float filt_hz)
struct AC_AttitudeControl_Heli::AttControlHeliFlags _flags_heli
float rate_target_to_motor_yaw(float rate_yaw_actual_rads, float rate_yaw_rads) override
void set_yaw(float yaw_in)
#define AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX
void input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds) override
AC_HELI_PID _pid_rate_roll
#define AP_GROUPINFO(name, idx, clazz, element, def)
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)
uint8_t flybar_passthrough
void update_althold_lean_angle_max(float throttle_in) override
Vector3f get_gyro_latest(void) const
float get_leaky_i(float leak_rate)
get_leaky_i - replacement for get_i but output is leaded at leak_rate
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
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) override
static const struct AP_Param::GroupInfo var_info[]
float _thrust_error_angle
AC_HELI_PID _pid_rate_yaw
#define AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD
void set_integrator(float i)
Vector3f update_ang_vel_target_from_att_error(Vector3f attitude_error_rot_vec_rad)
const Vector3f & get_gyro(void) const
LowPassFilterFloat yaw_velocity_feedforward_filter
float wrap_PI(const T radian)
ArduCopter attitude control library for traditional helicopters.
#define AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT
int16_t _passthrough_roll
Vector3f _attitude_target_ang_vel
void rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads)
#define AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE
float get_ff(float requested_rate)
#define AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX
void set_throttle(float throttle_in)
void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override
virtual void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
void passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds) override
void set_desired_rate(float desired)
Vector3f _attitude_target_euler_angle
float _althold_lean_angle_max
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)
Vector3f _rate_target_ang_vel
float constrain_float(const float amt, const float low, const float high)
AP_Int8 _piro_comp_enabled
float wrap_2PI(const T radian)
#define AP_NESTEDGROUPINFO(clazz, idx)
static constexpr float radians(float deg)
void set_input_filter_all(float input)
int16_t _passthrough_pitch
void integrate_bf_rate_error_to_angle_errors()
void set_pitch(float pitch_in)
void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) override
LowPassFilterFloat pitch_feedforward_filter
#define AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX
void set_roll(float roll_in)
float get_integrator() const
LowPassFilterFloat roll_feedforward_filter
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
float get_accel_yaw_max_radss() const
const AP_AHRS_View & _ahrs
T apply(T sample, float dt)
AC_HELI_PID _pid_rate_pitch
Vector3f _att_error_rot_vec_rad