AC_AttitudeControl_Sub.h 3.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384
  1. #pragma once
  2. /// @file AC_AttitudeControl_Sub.h
  3. /// @brief ArduSub attitude control library
  4. #include "AC_AttitudeControl.h"
  5. #include <AP_Motors/AP_MotorsMulticopter.h>
  6. // default angle controller PID gains
  7. // (Sub-specific defaults for parent class)
  8. #define AC_ATC_SUB_ANGLE_P 6.0f
  9. #define AC_ATC_SUB_ACCEL_Y_MAX 110000.0f
  10. // default rate controller PID gains
  11. #define AC_ATC_SUB_RATE_RP_P 0.135f
  12. #define AC_ATC_SUB_RATE_RP_I 0.090f
  13. #define AC_ATC_SUB_RATE_RP_D 0.0036f
  14. #define AC_ATC_SUB_RATE_RP_IMAX 0.444f
  15. #define AC_ATC_SUB_RATE_RP_FILT_HZ 30.0f
  16. #define AC_ATC_SUB_RATE_YAW_P 0.180f
  17. #define AC_ATC_SUB_RATE_YAW_I 0.018f
  18. #define AC_ATC_SUB_RATE_YAW_D 0.0f
  19. #define AC_ATC_SUB_RATE_YAW_IMAX 0.222f
  20. #define AC_ATC_SUB_RATE_YAW_FILT_HZ 5.0f
  21. class AC_AttitudeControl_Sub : public AC_AttitudeControl {
  22. public:
  23. AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt);
  24. // empty destructor to suppress compiler warning
  25. virtual ~AC_AttitudeControl_Sub() {}
  26. // pid accessors
  27. AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; }
  28. AC_PID& get_rate_pitch_pid() override { return _pid_rate_pitch; }
  29. AC_PID& get_rate_yaw_pid() override { return _pid_rate_yaw; }
  30. // Update Alt_Hold angle maximum
  31. void update_althold_lean_angle_max(float throttle_in) override;
  32. // Set output throttle
  33. void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override;
  34. // calculate total body frame throttle required to produce the given earth frame throttle
  35. float get_throttle_boosted(float throttle_in);
  36. // set desired throttle vs attitude mixing (actual mix is slewed towards this value over 1~2 seconds)
  37. // low values favour pilot/autopilot throttle over attitude control, high values favour attitude control over throttle
  38. // has no effect when throttle is above hover throttle
  39. void set_throttle_mix_min() override { _throttle_rpy_mix_desired = _thr_mix_min; }
  40. void set_throttle_mix_man() override { _throttle_rpy_mix_desired = _thr_mix_man; }
  41. void set_throttle_mix_max() override { _throttle_rpy_mix_desired = _thr_mix_max; }
  42. // are we producing min throttle?
  43. bool is_throttle_mix_min() const override { return (_throttle_rpy_mix < 1.25f*_thr_mix_min); }
  44. // run lowest level body-frame rate controller and send outputs to the motors
  45. void rate_controller_run() override;
  46. // sanity check parameters. should be called once before take-off
  47. void parameter_sanity_check() override;
  48. AP_Float _thr_mix_man; // throttle vs attitude control prioritisation used when using manual throttle (higher values mean we prioritise attitude control over throttle)
  49. AP_Float _thr_mix_min; // throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
  50. AP_Float _thr_mix_max; // throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)
  51. // user settable parameters
  52. static const struct AP_Param::GroupInfo var_info[];
  53. protected:
  54. // update_throttle_rpy_mix - updates thr_low_comp value towards the target
  55. void update_throttle_rpy_mix();
  56. // get maximum value throttle can be raised to based on throttle vs attitude prioritisation
  57. float get_throttle_avg_max(float throttle_in);
  58. AP_MotorsMulticopter& _motors_multi;
  59. AC_PID _pid_rate_roll;
  60. AC_PID _pid_rate_pitch;
  61. AC_PID _pid_rate_yaw;
  62. };