123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160 |
- #pragma once
- #include "AC_AttitudeControl.h"
- #include <AP_Motors/AP_MotorsHeli.h>
- #include <AC_PID/AC_HELI_PID.h>
- #include <Filter/Filter.h>
- #define AC_ATC_HELI_RATE_RP_P 0.024f
- #define AC_ATC_HELI_RATE_RP_I 0.6f
- #define AC_ATC_HELI_RATE_RP_D 0.001f
- #define AC_ATC_HELI_RATE_RP_IMAX 1.0f
- #define AC_ATC_HELI_RATE_RP_FF 0.060f
- #define AC_ATC_HELI_RATE_RP_FILT_HZ 20.0f
- #define AC_ATC_HELI_RATE_YAW_P 0.18f
- #define AC_ATC_HELI_RATE_YAW_I 0.12f
- #define AC_ATC_HELI_RATE_YAW_D 0.003f
- #define AC_ATC_HELI_RATE_YAW_IMAX 1.0f
- #define AC_ATC_HELI_RATE_YAW_FF 0.024f
- #define AC_ATC_HELI_RATE_YAW_FILT_HZ 20.0f
- #define AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX 0.95f
- #define AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE 0.02f
- #define AC_ATTITUDE_HELI_RATE_RP_FF_FILTER 10.0f
- #define AC_ATTITUDE_HELI_RATE_Y_VFF_FILTER 10.0f
- #define AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT 300
- #define AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD ToRad(30.0f)
- class AC_AttitudeControl_Heli : public AC_AttitudeControl {
- public:
- AC_AttitudeControl_Heli( AP_AHRS_View &ahrs,
- const AP_Vehicle::MultiCopter &aparm,
- AP_MotorsHeli& motors,
- float dt) :
- AC_AttitudeControl(ahrs, aparm, motors, dt),
- _pid_rate_roll(AC_ATC_HELI_RATE_RP_P, AC_ATC_HELI_RATE_RP_I, AC_ATC_HELI_RATE_RP_D, AC_ATC_HELI_RATE_RP_FF, AC_ATC_HELI_RATE_RP_IMAX, AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, AC_ATC_HELI_RATE_RP_FILT_HZ, 0.0f, dt),
- _pid_rate_pitch(AC_ATC_HELI_RATE_RP_P, AC_ATC_HELI_RATE_RP_I, AC_ATC_HELI_RATE_RP_D, AC_ATC_HELI_RATE_RP_FF, AC_ATC_HELI_RATE_RP_IMAX, AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, AC_ATC_HELI_RATE_RP_FILT_HZ, 0.0f, dt),
- _pid_rate_yaw(AC_ATC_HELI_RATE_YAW_P, AC_ATC_HELI_RATE_YAW_I, AC_ATC_HELI_RATE_YAW_D, AC_ATC_HELI_RATE_YAW_FF, AC_ATC_HELI_RATE_YAW_IMAX, AC_ATTITUDE_HELI_RATE_Y_VFF_FILTER, AC_ATC_HELI_RATE_YAW_FILT_HZ, 0.0f, dt)
- {
- AP_Param::setup_object_defaults(this, var_info);
-
- _flags_heli.limit_roll = false;
- _flags_heli.limit_pitch = false;
- _flags_heli.limit_yaw = false;
- _flags_heli.leaky_i = true;
- _flags_heli.flybar_passthrough = false;
- _flags_heli.tail_passthrough = false;
- _flags_heli.do_piro_comp = false;
- }
-
- AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; }
- AC_PID& get_rate_pitch_pid() override { return _pid_rate_pitch; }
- AC_PID& get_rate_yaw_pid() override { return _pid_rate_yaw; }
-
- void passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds) override;
-
- void integrate_bf_rate_error_to_angle_errors();
-
- void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) override;
-
-
- virtual void rate_controller_run() override;
-
- void update_althold_lean_angle_max(float throttle_in) override;
-
- void use_leaky_i(bool leaky_i) override { _flags_heli.leaky_i = leaky_i; }
-
-
-
- void use_flybar_passthrough(bool passthrough, bool tail_passthrough) override {
- _flags_heli.flybar_passthrough = passthrough;
- _flags_heli.tail_passthrough = tail_passthrough;
- }
-
- void do_piro_comp(bool piro_comp) { _flags_heli.do_piro_comp = piro_comp; }
-
- void set_hover_roll_trim_scalar(float scalar) override {_hover_roll_trim_scalar = constrain_float(scalar, 0.0f, 1.0f);}
-
- void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override;
-
- 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;
-
- 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;
-
-
- void set_inverted_flight(bool inverted) override {
- _inverted_flight = inverted;
- }
-
-
- static const struct AP_Param::GroupInfo var_info[];
- private:
-
- struct AttControlHeliFlags {
- uint8_t limit_roll : 1;
- uint8_t limit_pitch : 1;
- uint8_t limit_yaw : 1;
- uint8_t leaky_i : 1;
- uint8_t flybar_passthrough : 1;
- uint8_t tail_passthrough : 1;
- uint8_t do_piro_comp : 1;
- } _flags_heli;
-
-
-
-
-
- void rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads);
- float rate_target_to_motor_yaw(float rate_yaw_actual_rads, float rate_yaw_rads);
-
-
-
-
-
- float _passthrough_roll;
- float _passthrough_pitch;
-
- float _passthrough_yaw;
-
- float get_roll_trim_rad() override { return constrain_float(radians(_hover_roll_trim_scalar * _hover_roll_trim * 0.01f), -radians(10.0f),radians(10.0f));}
-
- float _hover_roll_trim_scalar = 0;
-
-
-
- Vector3f _att_error_rot_vec_rad;
-
- AP_Int8 _piro_comp_enabled;
- AP_Int16 _hover_roll_trim;
- AC_HELI_PID _pid_rate_roll;
- AC_HELI_PID _pid_rate_pitch;
- AC_HELI_PID _pid_rate_yaw;
-
- };
|