AC_AttitudeControl_Multi.h 4.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100
  1. #pragma once
  2. /// @file AC_AttitudeControl_Multi.h
  3. /// @brief ArduCopter attitude control library
  4. #include "AC_AttitudeControl.h"
  5. #include <AP_Motors/AP_MotorsMulticopter.h>
  6. // default rate controller PID gains
  7. #ifndef AC_ATC_MULTI_RATE_RP_P
  8. # define AC_ATC_MULTI_RATE_RP_P 0.135f
  9. #endif
  10. #ifndef AC_ATC_MULTI_RATE_RP_I
  11. # define AC_ATC_MULTI_RATE_RP_I 0.135f
  12. #endif
  13. #ifndef AC_ATC_MULTI_RATE_RP_D
  14. # define AC_ATC_MULTI_RATE_RP_D 0.0036f
  15. #endif
  16. #ifndef AC_ATC_MULTI_RATE_RP_IMAX
  17. # define AC_ATC_MULTI_RATE_RP_IMAX 0.5f
  18. #endif
  19. #ifndef AC_ATC_MULTI_RATE_RP_FILT_HZ
  20. # define AC_ATC_MULTI_RATE_RP_FILT_HZ 20.0f
  21. #endif
  22. #ifndef AC_ATC_MULTI_RATE_YAW_P
  23. # define AC_ATC_MULTI_RATE_YAW_P 0.180f
  24. #endif
  25. #ifndef AC_ATC_MULTI_RATE_YAW_I
  26. # define AC_ATC_MULTI_RATE_YAW_I 0.018f
  27. #endif
  28. #ifndef AC_ATC_MULTI_RATE_YAW_D
  29. # define AC_ATC_MULTI_RATE_YAW_D 0.0f
  30. #endif
  31. #ifndef AC_ATC_MULTI_RATE_YAW_IMAX
  32. # define AC_ATC_MULTI_RATE_YAW_IMAX 0.5f
  33. #endif
  34. #ifndef AC_ATC_MULTI_RATE_YAW_FILT_HZ
  35. # define AC_ATC_MULTI_RATE_YAW_FILT_HZ 2.5f
  36. #endif
  37. class AC_AttitudeControl_Multi : public AC_AttitudeControl {
  38. public:
  39. AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt);
  40. // empty destructor to suppress compiler warning
  41. virtual ~AC_AttitudeControl_Multi() {}
  42. // pid accessors
  43. AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; }
  44. AC_PID& get_rate_pitch_pid() override { return _pid_rate_pitch; }
  45. AC_PID& get_rate_yaw_pid() override { return _pid_rate_yaw; }
  46. // Update Alt_Hold angle maximum
  47. void update_althold_lean_angle_max(float throttle_in) override;
  48. // Set output throttle
  49. void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override;
  50. // calculate total body frame throttle required to produce the given earth frame throttle
  51. float get_throttle_boosted(float throttle_in);
  52. // set desired throttle vs attitude mixing (actual mix is slewed towards this value over 1~2 seconds)
  53. // low values favour pilot/autopilot throttle over attitude control, high values favour attitude control over throttle
  54. // has no effect when throttle is above hover throttle
  55. void set_throttle_mix_min() override { _throttle_rpy_mix_desired = _thr_mix_min; }
  56. void set_throttle_mix_man() override { _throttle_rpy_mix_desired = _thr_mix_man; }
  57. void set_throttle_mix_max() override { _throttle_rpy_mix_desired = _thr_mix_max; }
  58. void set_throttle_mix_value(float value) override { _throttle_rpy_mix_desired = _throttle_rpy_mix = value; }
  59. float get_throttle_mix(void) const override { return _throttle_rpy_mix; }
  60. // are we producing min throttle?
  61. bool is_throttle_mix_min() const override { return (_throttle_rpy_mix < 1.25f * _thr_mix_min); }
  62. // run lowest level body-frame rate controller and send outputs to the motors
  63. void rate_controller_run() override;
  64. // sanity check parameters. should be called once before take-off
  65. void parameter_sanity_check() override;
  66. // user settable parameters
  67. static const struct AP_Param::GroupInfo var_info[];
  68. protected:
  69. // update_throttle_rpy_mix - updates thr_low_comp value towards the target
  70. void update_throttle_rpy_mix();
  71. // get maximum value throttle can be raised to based on throttle vs attitude prioritisation
  72. float get_throttle_avg_max(float throttle_in);
  73. AP_MotorsMulticopter& _motors_multi;
  74. AC_PID _pid_rate_roll;
  75. AC_PID _pid_rate_pitch;
  76. AC_PID _pid_rate_yaw;
  77. AP_Float _thr_mix_man; // throttle vs attitude control prioritisation used when using manual throttle (higher values mean we prioritise attitude control over throttle)
  78. AP_Float _thr_mix_min; // throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
  79. AP_Float _thr_mix_max; // throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)
  80. };