AP_MotorsHeli_Swash.h 3.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475
  1. /// @file AP_MotorsHeli_Swash.h
  2. /// @brief Swashplate Library for traditional heli
  3. #pragma once
  4. #include <AP_Common/AP_Common.h>
  5. #include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
  6. #include <AP_Param/AP_Param.h>
  7. // swashplate types
  8. enum SwashPlateType {
  9. SWASHPLATE_TYPE_H3 = 0,
  10. SWASHPLATE_TYPE_H1,
  11. SWASHPLATE_TYPE_H3_140,
  12. SWASHPLATE_TYPE_H3_120,
  13. SWASHPLATE_TYPE_H4_90,
  14. SWASHPLATE_TYPE_H4_45
  15. };
  16. // collective direction
  17. enum CollectiveDirection {
  18. COLLECTIVE_DIRECTION_NORMAL = 0,
  19. COLLECTIVE_DIRECTION_REVERSED
  20. };
  21. class AP_MotorsHeli_Swash {
  22. public:
  23. AP_MotorsHeli_Swash()
  24. {
  25. AP_Param::setup_object_defaults(this, var_info);
  26. };
  27. // configure - configure the swashplate settings for any updated parameters
  28. void configure();
  29. // CCPM Mixers - calculate mixing scale factors by swashplate type
  30. void calculate_roll_pitch_collective_factors();
  31. // get_swash_type - gets swashplate type
  32. SwashPlateType get_swash_type() const { return _swash_type; }
  33. // get_servo_out - calculates servo output
  34. float get_servo_out(int8_t servo_num, float pitch, float roll, float collective) const;
  35. // linearize mechanical output of swashplate servo
  36. float get_linear_servo_output(float input) const;
  37. // get_phase_angle - returns the rotor phase angle
  38. int16_t get_phase_angle() const { return _phase_angle; }
  39. // var_info
  40. static const struct AP_Param::GroupInfo var_info[];
  41. private:
  42. // internal variables
  43. SwashPlateType _swash_type; // Swashplate type
  44. CollectiveDirection _collective_direction; // Collective control direction, normal or reversed
  45. float _rollFactor[4]; // Roll axis scaling of servo output based on servo position
  46. float _pitchFactor[4]; // Pitch axis scaling of servo output based on servo position
  47. float _collectiveFactor[4]; // Collective axis scaling of servo output based on servo position
  48. int8_t _make_servo_linear; // Sets servo output to be linearized
  49. // parameters
  50. AP_Int8 _swashplate_type; // Swash Type Setting
  51. AP_Int8 _swash_coll_dir; // Collective control direction, normal or reversed
  52. AP_Int8 _linear_swash_servo; // linearize swashplate output
  53. AP_Int8 enable;
  54. AP_Int16 _servo1_pos; // servo1 azimuth position on swashplate with front of heli being 0 deg
  55. AP_Int16 _servo2_pos; // servo2 azimuth position on swashplate with front of heli being 0 deg
  56. AP_Int16 _servo3_pos; // servo3 azimuth position on swashplate with front of heli being 0 deg
  57. AP_Int16 _phase_angle; // Phase angle correction for rotor head. If pitching the swash forward induces
  58. // a roll, this can be negative depending on mechanics.
  59. };