AP_MotorsHeli_Single.h 7.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149
  1. /// @file AP_MotorsHeli_Single.h
  2. /// @brief Motor control class 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 <SRV_Channel/SRV_Channel.h>
  7. #include "AP_MotorsHeli.h"
  8. #include "AP_MotorsHeli_RSC.h"
  9. #include "AP_MotorsHeli_Swash.h"
  10. // rsc and extgyro function output channels.
  11. #define AP_MOTORS_HELI_SINGLE_EXTGYRO CH_7
  12. #define AP_MOTORS_HELI_SINGLE_TAILRSC CH_7
  13. // tail types
  14. #define AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO 0
  15. #define AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO 1
  16. #define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH 2
  17. #define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH 3
  18. // direct-drive variable pitch defaults
  19. #define AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT 50
  20. // default external gyro gain
  21. #define AP_MOTORS_HELI_SINGLE_EXT_GYRO_GAIN 350
  22. // COLYAW parameter min and max values
  23. #define AP_MOTORS_HELI_SINGLE_COLYAW_RANGE 10.0f
  24. // maximum number of swashplate servos
  25. #define AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS 3
  26. /// @class AP_MotorsHeli_Single
  27. class AP_MotorsHeli_Single : public AP_MotorsHeli {
  28. public:
  29. // constructor
  30. AP_MotorsHeli_Single(uint16_t loop_rate,
  31. uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) :
  32. AP_MotorsHeli(loop_rate, speed_hz),
  33. _tail_rotor(SRV_Channel::k_heli_tail_rsc, AP_MOTORS_HELI_SINGLE_TAILRSC),
  34. _swashplate()
  35. {
  36. AP_Param::setup_object_defaults(this, var_info);
  37. };
  38. // set update rate to motors - a value in hertz
  39. void set_update_rate(uint16_t speed_hz) override;
  40. // output_test_seq - spin a motor at the pwm value specified
  41. // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
  42. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  43. virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override;
  44. // output_to_motors - sends values out to the motors
  45. void output_to_motors() override;
  46. // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1
  47. void set_desired_rotor_speed(float desired_speed) override;
  48. // set_rpm - for rotor speed governor
  49. void set_rpm(float rotor_rpm) override;
  50. // get_main_rotor_speed - estimated rotor speed when no speed sensor or governor is used
  51. float get_main_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
  52. // get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1
  53. float get_desired_rotor_speed() const override { return _main_rotor.get_desired_speed(); }
  54. // rotor_speed_above_critical - return true if rotor speed is above that critical for flight
  55. bool rotor_speed_above_critical() const override { return _main_rotor.get_rotor_speed() > _main_rotor.get_critical_speed(); }
  56. // get_governor_output
  57. float get_governor_output() const override { return _main_rotor.get_governor_output(); }
  58. // get_control_output
  59. float get_control_output() const override{ return _main_rotor.get_control_output(); }
  60. // calculate_scalars - recalculates various scalars used
  61. void calculate_scalars() override;
  62. // calculate_armed_scalars - recalculates scalars that can change while armed
  63. void calculate_armed_scalars() override;
  64. // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
  65. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  66. uint16_t get_motor_mask() override;
  67. // ext_gyro_gain - set external gyro gain in range 0 ~ 1000
  68. void ext_gyro_gain(float gain) override { if (gain >= 0 && gain <= 1000) { _ext_gyro_gain_std = gain; }}
  69. // has_flybar - returns true if we have a mechical flybar
  70. bool has_flybar() const override { return _flybar_mode; }
  71. // supports_yaw_passthrought - returns true if we support yaw passthrough
  72. bool supports_yaw_passthrough() const override { return _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO; }
  73. void set_acro_tail(bool set) override { _acro_tail = set; }
  74. // parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
  75. bool parameter_check(bool display_msg) const override;
  76. // var_info
  77. static const struct AP_Param::GroupInfo var_info[];
  78. protected:
  79. // init_outputs - initialise Servo/PWM ranges and endpoints
  80. bool init_outputs() override;
  81. // update_motor_controls - sends commands to motor controllers
  82. void update_motor_control(RotorControlState state) override;
  83. // heli_move_actuators - moves swash plate and tail rotor
  84. void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override;
  85. // move_yaw - moves the yaw servo
  86. void move_yaw(float yaw_out);
  87. // servo_test - move servos through full range of movement
  88. void servo_test() override;
  89. // external objects we depend upon
  90. AP_MotorsHeli_RSC _tail_rotor; // tail rotor
  91. AP_MotorsHeli_Swash _swashplate; // swashplate
  92. // internal variables
  93. float _oscillate_angle = 0.0f; // cyclic oscillation angle, used by servo_test function
  94. float _servo_test_cycle_time = 0.0f; // cycle time tracker, used by servo_test function
  95. float _collective_test = 0.0f; // over-ride for collective output, used by servo_test function
  96. float _roll_test = 0.0f; // over-ride for roll output, used by servo_test function
  97. float _pitch_test = 0.0f; // over-ride for pitch output, used by servo_test function
  98. float _yaw_test = 0.0f; // over-ride for yaw output, used by servo_test function
  99. float _servo1_out = 0.0f; // output value sent to motor
  100. float _servo2_out = 0.0f; // output value sent to motor
  101. float _servo3_out = 0.0f; // output value sent to motor
  102. float _servo4_out = 0.0f; // output value sent to motor
  103. float _servo5_out = 0.0f; // output value sent to motor
  104. // parameters
  105. AP_Int16 _tail_type; // Tail type used: Servo, Servo with external gyro, direct drive variable pitch or direct drive fixed pitch
  106. AP_Int16 _ext_gyro_gain_std; // PWM sent to external gyro on ch7 when tail type is Servo w/ ExtGyro
  107. AP_Int16 _ext_gyro_gain_acro; // PWM sent to external gyro on ch7 when tail type is Servo w/ ExtGyro in ACRO
  108. AP_Float _collective_yaw_effect; // Feed-forward compensation to automatically add rudder input when collective pitch is increased. Can be positive or negative depending on mechanics.
  109. AP_Int8 _flybar_mode; // Flybar present or not. Affects attitude controller used during ACRO flight mode
  110. AP_Int16 _direct_drive_tailspeed; // Direct Drive VarPitch Tail ESC speed (0 ~ 1000)
  111. bool _acro_tail = false;
  112. };