AP_MotorsHeli_Quad.h 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102
  1. /// @file AP_MotorsHeli_Quad.h
  2. /// @brief Motor control class collective pitch quad helicopter (such as stingray)
  3. #pragma once
  4. #include <AP_Common/AP_Common.h>
  5. #include <AP_Math/AP_Math.h>
  6. #include <RC_Channel/RC_Channel.h>
  7. #include "AP_MotorsHeli.h"
  8. #include "AP_MotorsHeli_RSC.h"
  9. // default collective min, max and midpoints for the rear swashplate
  10. #define AP_MOTORS_HELI_QUAD_COLLECTIVE_MIN 1100
  11. #define AP_MOTORS_HELI_QUAD_COLLECTIVE_MAX 1900
  12. #define AP_MOTORS_HELI_QUAD_NUM_MOTORS 4
  13. class AP_MotorsHeli_Quad : public AP_MotorsHeli {
  14. public:
  15. // constructor
  16. AP_MotorsHeli_Quad(uint16_t loop_rate,
  17. uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) :
  18. AP_MotorsHeli(loop_rate, speed_hz)
  19. {
  20. AP_Param::setup_object_defaults(this, var_info);
  21. };
  22. // set_update_rate - set update rate to motors
  23. void set_update_rate( uint16_t speed_hz ) override;
  24. // output_test_seq - spin a motor at the pwm value specified
  25. virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override;
  26. // output_to_motors - sends values out to the motors
  27. void output_to_motors() override;
  28. // set_rpm - for rotor speed governor
  29. void set_rpm(float rotor_rpm) override;
  30. // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000
  31. void set_desired_rotor_speed(float desired_speed) override;
  32. // get_estimated_rotor_speed - gets estimated rotor speed as a number from 0 ~ 1000
  33. float get_main_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
  34. // get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1000
  35. float get_desired_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
  36. // rotor_speed_above_critical - return true if rotor speed is above that critical for flight
  37. bool rotor_speed_above_critical() const override { return _main_rotor.get_rotor_speed() > _main_rotor.get_critical_speed(); }
  38. // get_governor_output
  39. float get_governor_output() const override { return _main_rotor.get_governor_output(); }
  40. // get_control_output
  41. float get_control_output() const override { return _main_rotor.get_control_output(); }
  42. // calculate_scalars - recalculates various scalars used
  43. void calculate_scalars() override;
  44. // calculate_armed_scalars - recalculates scalars that can change while armed
  45. void calculate_armed_scalars() override;
  46. // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
  47. uint16_t get_motor_mask() override;
  48. // has_flybar - returns true if we have a mechanical flybar
  49. bool has_flybar() const override { return AP_MOTORS_HELI_NOFLYBAR; }
  50. // supports_yaw_passthrought - returns true if we support yaw passthrough
  51. bool supports_yaw_passthrough() const override { return false; }
  52. // servo_test - move servos through full range of movement
  53. void servo_test() override;
  54. // var_info for holding Parameter information
  55. static const struct AP_Param::GroupInfo var_info[];
  56. protected:
  57. // init_outputs
  58. bool init_outputs () override;
  59. // update_motor_controls - sends commands to motor controllers
  60. void update_motor_control(RotorControlState state) override;
  61. // calculate_roll_pitch_collective_factors - setup rate factors
  62. void calculate_roll_pitch_collective_factors ();
  63. // move_actuators - moves swash plate to attitude of parameters passed in
  64. void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override;
  65. // rate factors
  66. float _rollFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS];
  67. float _pitchFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS];
  68. float _collectiveFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS];
  69. float _yawFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS];
  70. float _out[AP_MOTORS_HELI_QUAD_NUM_MOTORS];
  71. };