AC_AttitudeControl_Heli.h 8.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160
  1. #pragma once
  2. /// @file AC_AttitudeControl_Heli.h
  3. /// @brief ArduCopter attitude control library for traditional helicopters
  4. #include "AC_AttitudeControl.h"
  5. #include <AP_Motors/AP_MotorsHeli.h>
  6. #include <AC_PID/AC_HELI_PID.h>
  7. #include <Filter/Filter.h>
  8. // default rate controller PID gains
  9. #define AC_ATC_HELI_RATE_RP_P 0.024f
  10. #define AC_ATC_HELI_RATE_RP_I 0.6f
  11. #define AC_ATC_HELI_RATE_RP_D 0.001f
  12. #define AC_ATC_HELI_RATE_RP_IMAX 1.0f
  13. #define AC_ATC_HELI_RATE_RP_FF 0.060f
  14. #define AC_ATC_HELI_RATE_RP_FILT_HZ 20.0f
  15. #define AC_ATC_HELI_RATE_YAW_P 0.18f
  16. #define AC_ATC_HELI_RATE_YAW_I 0.12f
  17. #define AC_ATC_HELI_RATE_YAW_D 0.003f
  18. #define AC_ATC_HELI_RATE_YAW_IMAX 1.0f
  19. #define AC_ATC_HELI_RATE_YAW_FF 0.024f
  20. #define AC_ATC_HELI_RATE_YAW_FILT_HZ 20.0f
  21. #define AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX 0.95f // Heli's use 95% of max collective before limiting frame angle
  22. #define AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE 0.02f
  23. #define AC_ATTITUDE_HELI_RATE_RP_FF_FILTER 10.0f
  24. #define AC_ATTITUDE_HELI_RATE_Y_VFF_FILTER 10.0f
  25. #define AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT 300
  26. #define AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD ToRad(30.0f)
  27. class AC_AttitudeControl_Heli : public AC_AttitudeControl {
  28. public:
  29. AC_AttitudeControl_Heli( AP_AHRS_View &ahrs,
  30. const AP_Vehicle::MultiCopter &aparm,
  31. AP_MotorsHeli& motors,
  32. float dt) :
  33. AC_AttitudeControl(ahrs, aparm, motors, dt),
  34. _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),
  35. _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),
  36. _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)
  37. {
  38. AP_Param::setup_object_defaults(this, var_info);
  39. // initialise flags
  40. _flags_heli.limit_roll = false;
  41. _flags_heli.limit_pitch = false;
  42. _flags_heli.limit_yaw = false;
  43. _flags_heli.leaky_i = true;
  44. _flags_heli.flybar_passthrough = false;
  45. _flags_heli.tail_passthrough = false;
  46. _flags_heli.do_piro_comp = false;
  47. }
  48. // pid accessors
  49. AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; }
  50. AC_PID& get_rate_pitch_pid() override { return _pid_rate_pitch; }
  51. AC_PID& get_rate_yaw_pid() override { return _pid_rate_yaw; }
  52. // passthrough_bf_roll_pitch_rate_yaw - roll and pitch are passed through directly, body-frame rate target for yaw
  53. void passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds) override;
  54. // Integrate vehicle rate into _att_error_rot_vec_rad
  55. void integrate_bf_rate_error_to_angle_errors();
  56. // subclass non-passthrough too, for external gyro, no flybar
  57. void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) override;
  58. // rate_controller_run - run lowest level body-frame rate controller and send outputs to the motors
  59. // should be called at 100hz or more
  60. virtual void rate_controller_run() override;
  61. // Update Alt_Hold angle maximum
  62. void update_althold_lean_angle_max(float throttle_in) override;
  63. // use_leaky_i - controls whether we use leaky i term for body-frame to motor output stage
  64. void use_leaky_i(bool leaky_i) override { _flags_heli.leaky_i = leaky_i; }
  65. // use_flybar_passthrough - controls whether we pass-through
  66. // control inputs to swash-plate and tail
  67. void use_flybar_passthrough(bool passthrough, bool tail_passthrough) override {
  68. _flags_heli.flybar_passthrough = passthrough;
  69. _flags_heli.tail_passthrough = tail_passthrough;
  70. }
  71. // do_piro_comp - controls whether piro-comp is active or not
  72. void do_piro_comp(bool piro_comp) { _flags_heli.do_piro_comp = piro_comp; }
  73. // set_hover_roll_scalar - scales Hover Roll Trim parameter. To be used by vehicle code according to vehicle condition.
  74. void set_hover_roll_trim_scalar(float scalar) override {_hover_roll_trim_scalar = constrain_float(scalar, 0.0f, 1.0f);}
  75. // Set output throttle
  76. void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override;
  77. // Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
  78. 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;
  79. // Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
  80. 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;
  81. // enable/disable inverted flight
  82. void set_inverted_flight(bool inverted) override {
  83. _inverted_flight = inverted;
  84. }
  85. // user settable parameters
  86. static const struct AP_Param::GroupInfo var_info[];
  87. private:
  88. // To-Do: move these limits flags into the heli motors class
  89. struct AttControlHeliFlags {
  90. uint8_t limit_roll : 1; // 1 if we have requested larger roll angle than swash can physically move
  91. uint8_t limit_pitch : 1; // 1 if we have requested larger pitch angle than swash can physically move
  92. uint8_t limit_yaw : 1; // 1 if we have requested larger yaw angle than tail servo can physically move
  93. uint8_t leaky_i : 1; // 1 if we should use leaky i term for body-frame rate to motor stage
  94. uint8_t flybar_passthrough : 1; // 1 if we should pass through pilots roll & pitch input directly to swash-plate
  95. uint8_t tail_passthrough : 1; // 1 if we should pass through pilots yaw input to tail
  96. uint8_t do_piro_comp : 1; // 1 if we should do pirouette compensation on roll/pitch
  97. } _flags_heli;
  98. //
  99. // body-frame rate controller
  100. //
  101. // rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target body-frame rate (in radians/sec) for roll, pitch and yaw
  102. // outputs are sent directly to motor class
  103. void rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads);
  104. float rate_target_to_motor_yaw(float rate_yaw_actual_rads, float rate_yaw_rads);
  105. //
  106. // throttle methods
  107. //
  108. // pass through for roll and pitch
  109. float _passthrough_roll;
  110. float _passthrough_pitch;
  111. // pass through for yaw if tail_passthrough is set
  112. float _passthrough_yaw;
  113. // get_roll_trim - angle in centi-degrees to be added to roll angle. Used by helicopter to counter tail rotor thrust in hover
  114. 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));}
  115. // internal variables
  116. float _hover_roll_trim_scalar = 0; // scalar used to suppress Hover Roll Trim
  117. // This represents an euler axis-angle rotation vector from the vehicles
  118. // estimated attitude to the reference (setpoint) attitude used in the attitude
  119. // controller, in radians in the vehicle body frame of reference.
  120. Vector3f _att_error_rot_vec_rad;
  121. // parameters
  122. AP_Int8 _piro_comp_enabled; // Flybar present or not. Affects attitude controller used during ACRO flight mode
  123. AP_Int16 _hover_roll_trim; // Angle in centi-degrees used to counter tail rotor thrust in hover
  124. AC_HELI_PID _pid_rate_roll;
  125. AC_HELI_PID _pid_rate_pitch;
  126. AC_HELI_PID _pid_rate_yaw;
  127. };