AP_MotorsHeli_Dual.h 6.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141
  1. /// @file AP_MotorsHeli_Dual.h
  2. /// @brief Motor control class for dual heli (tandem or transverse)
  3. /// @author Fredrik Hedberg
  4. #ifndef __AP_MOTORS_HELI_DUAL_H__
  5. #define __AP_MOTORS_HELI_DUAL_H__
  6. #include <AP_Common/AP_Common.h>
  7. #include <AP_Math/AP_Math.h>
  8. #include <RC_Channel/RC_Channel.h>
  9. #include "AP_MotorsHeli.h"
  10. #include "AP_MotorsHeli_RSC.h"
  11. #include "AP_MotorsHeli_Swash.h"
  12. // tandem modes
  13. #define AP_MOTORS_HELI_DUAL_MODE_TANDEM 0 // tandem mode (rotors front and aft)
  14. #define AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE 1 // transverse mode (rotors side by side)
  15. // tandem modes
  16. #define AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH 0 // swashplate pitch tilt axis
  17. #define AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL 1 // swashplate roll tilt axis
  18. #define AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL 2 // swashplate collective axis
  19. // default differential-collective-pitch scaler
  20. #define AP_MOTORS_HELI_DUAL_DCP_SCALER 0.25f
  21. // maximum number of swashplate servos
  22. #define AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS 6
  23. // default collective min, max and midpoints for the rear swashplate
  24. #define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN 1250
  25. #define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX 1750
  26. #define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MID 1500
  27. /// @class AP_MotorsHeli_Dual
  28. class AP_MotorsHeli_Dual : public AP_MotorsHeli {
  29. public:
  30. // constructor
  31. AP_MotorsHeli_Dual(uint16_t loop_rate,
  32. uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) :
  33. AP_MotorsHeli(loop_rate, speed_hz)
  34. {
  35. AP_Param::setup_object_defaults(this, var_info);
  36. };
  37. // set_update_rate - set update rate to motors
  38. void set_update_rate( uint16_t speed_hz ) override;
  39. // output_test_seq - spin a motor at the pwm value specified
  40. virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override;
  41. // output_to_motors - sends values out to the motors
  42. void output_to_motors() override;
  43. // set_rpm - for rotor speed governor
  44. void set_rpm(float rotor_rpm) override;
  45. // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000
  46. void set_desired_rotor_speed(float desired_speed) override;
  47. // get_estimated_rotor_speed - gets estimated rotor speed as a number from 0 ~ 1000
  48. float get_main_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
  49. // get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1000
  50. float get_desired_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
  51. // rotor_speed_above_critical - return true if rotor speed is above that critical for flight
  52. bool rotor_speed_above_critical() const override { return _main_rotor.get_rotor_speed() > _main_rotor.get_critical_speed(); }
  53. // get_governor_output
  54. float get_governor_output() const override { return _main_rotor.get_governor_output(); }
  55. // get_control_output
  56. float get_control_output() const override { return _main_rotor.get_control_output(); }
  57. // calculate_scalars - recalculates various scalars used
  58. void calculate_scalars() override;
  59. // calculate_armed_scalars - recalculates scalars that can change while armed
  60. void calculate_armed_scalars() override;
  61. // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
  62. uint16_t get_motor_mask() override;
  63. // has_flybar - returns true if we have a mechical flybar
  64. bool has_flybar() const override { return AP_MOTORS_HELI_NOFLYBAR; }
  65. // supports_yaw_passthrought - returns true if we support yaw passthrough
  66. bool supports_yaw_passthrough() const override { return false; }
  67. // servo_test - move servos through full range of movement
  68. void servo_test() override;
  69. // parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
  70. bool parameter_check(bool display_msg) const override;
  71. // var_info for holding Parameter information
  72. static const struct AP_Param::GroupInfo var_info[];
  73. protected:
  74. // init_outputs
  75. bool init_outputs () override;
  76. // update_motor_controls - sends commands to motor controllers
  77. void update_motor_control(RotorControlState state) override;
  78. // get_swashplate - calculate movement of each swashplate based on configuration
  79. float get_swashplate(int8_t swash_num, int8_t swash_axis, float pitch_input, float roll_input, float yaw_input, float coll_input);
  80. // move_actuators - moves swash plate to attitude of parameters passed in
  81. void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override;
  82. // objects we depend upon
  83. AP_MotorsHeli_Swash _swashplate1; // swashplate1
  84. AP_MotorsHeli_Swash _swashplate2; // swashplate2
  85. // internal variables
  86. float _oscillate_angle = 0.0f; // cyclic oscillation angle, used by servo_test function
  87. float _servo_test_cycle_time = 0.0f; // cycle time tracker, used by servo_test function
  88. float _collective_test = 0.0f; // over-ride for collective output, used by servo_test function
  89. float _roll_test = 0.0f; // over-ride for roll output, used by servo_test function
  90. float _pitch_test = 0.0f; // over-ride for pitch output, used by servo_test function
  91. float _servo_out[8]; // output value sent to motor
  92. // parameters
  93. AP_Int16 _collective2_min; // Lowest possible servo position for the rear swashplate
  94. AP_Int16 _collective2_max; // Highest possible servo position for the rear swashplate
  95. AP_Int16 _collective2_mid; // Swash servo position corresponding to zero collective pitch for the rear swashplate (or zero lift for Asymmetrical blades)
  96. AP_Int8 _dual_mode; // which dual mode the heli is
  97. AP_Float _dcp_scaler; // scaling factor applied to the differential-collective-pitch
  98. AP_Float _dcp_yaw_effect; // feed-forward compensation to automatically add yaw input when differential collective pitch is applied.
  99. AP_Float _yaw_scaler; // scaling factor applied to the yaw mixing
  100. // internal variables
  101. float _collective2_mid_pct = 0.0f; // collective mid parameter value for rear swashplate converted to 0 ~ 1 range
  102. };
  103. #endif // AP_MotorsHeli_Dual