AP_Motors_Class.h 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256
  1. #pragma once
  2. #include <AP_Common/AP_Common.h>
  3. #include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
  4. #include <AP_Notify/AP_Notify.h> // Notify library
  5. #include <SRV_Channel/SRV_Channel.h>
  6. #include <Filter/Filter.h> // filter library
  7. // offsets for motors in motor_out and _motor_filtered arrays
  8. #define AP_MOTORS_MOT_1 0U
  9. #define AP_MOTORS_MOT_2 1U
  10. #define AP_MOTORS_MOT_3 2U
  11. #define AP_MOTORS_MOT_4 3U
  12. #define AP_MOTORS_MOT_5 4U
  13. #define AP_MOTORS_MOT_6 5U
  14. #define AP_MOTORS_MOT_7 6U
  15. #define AP_MOTORS_MOT_8 7U
  16. #define AP_MOTORS_MOT_9 8U
  17. #define AP_MOTORS_MOT_10 9U
  18. #define AP_MOTORS_MOT_11 10U
  19. #define AP_MOTORS_MOT_12 11U
  20. #define AP_MOTORS_MAX_NUM_MOTORS 12
  21. // motor update rate
  22. #define AP_MOTORS_SPEED_DEFAULT 490 // default output rate to the motors
  23. /// @class AP_Motors
  24. class AP_Motors {
  25. public:
  26. enum motor_frame_class {
  27. MOTOR_FRAME_UNDEFINED = 0,
  28. MOTOR_FRAME_QUAD = 1,
  29. MOTOR_FRAME_HEXA = 2,
  30. MOTOR_FRAME_OCTA = 3,
  31. MOTOR_FRAME_OCTAQUAD = 4,
  32. MOTOR_FRAME_Y6 = 5,
  33. MOTOR_FRAME_HELI = 6,
  34. MOTOR_FRAME_TRI = 7,
  35. MOTOR_FRAME_SINGLE = 8,
  36. MOTOR_FRAME_COAX = 9,
  37. MOTOR_FRAME_TAILSITTER = 10,
  38. MOTOR_FRAME_HELI_DUAL = 11,
  39. MOTOR_FRAME_DODECAHEXA = 12,
  40. MOTOR_FRAME_HELI_QUAD = 13,
  41. };
  42. enum motor_frame_type {
  43. MOTOR_FRAME_TYPE_PLUS = 0,
  44. MOTOR_FRAME_TYPE_X = 1,
  45. MOTOR_FRAME_TYPE_V = 2,
  46. MOTOR_FRAME_TYPE_H = 3,
  47. MOTOR_FRAME_TYPE_VTAIL = 4,
  48. MOTOR_FRAME_TYPE_ATAIL = 5,
  49. MOTOR_FRAME_TYPE_PLUSREV = 6, // plus with reversed motor direction
  50. MOTOR_FRAME_TYPE_Y6B = 10,
  51. MOTOR_FRAME_TYPE_Y6F = 11, // for FireFlyY6
  52. MOTOR_FRAME_TYPE_BF_X = 12, // X frame, betaflight ordering
  53. MOTOR_FRAME_TYPE_DJI_X = 13, // X frame, DJI ordering
  54. MOTOR_FRAME_TYPE_CW_X = 14, // X frame, clockwise ordering
  55. MOTOR_FRAME_TYPE_I = 15, // (sideways H) octo only
  56. };
  57. // Constructor
  58. AP_Motors(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
  59. // singleton support
  60. static AP_Motors *get_singleton(void) { return _singleton; }
  61. // check initialisation succeeded
  62. bool initialised_ok() const { return _flags.initialised_ok; }
  63. // arm, disarm or check status status of motors
  64. bool armed() const { return _flags.armed; }
  65. void armed(bool arm);
  66. // set motor interlock status
  67. void set_interlock(bool set) { _flags.interlock = set;}
  68. // get motor interlock status. true means motors run, false motors don't run
  69. bool get_interlock() const { return _flags.interlock; }
  70. // set_roll, set_pitch, set_yaw, set_throttle
  71. void set_roll(float roll_in) { _roll_in = roll_in; }; // range -1 ~ +1
  72. void set_roll_ff(float roll_in) { _roll_in_ff = roll_in; }; // range -1 ~ +1
  73. void set_pitch(float pitch_in) { _pitch_in = pitch_in; }; // range -1 ~ +1
  74. void set_pitch_ff(float pitch_in) { _pitch_in_ff = pitch_in; }; // range -1 ~ +1
  75. void set_yaw(float yaw_in) { _yaw_in = yaw_in; }; // range -1 ~ +1
  76. void set_yaw_ff(float yaw_in) { _yaw_in_ff = yaw_in; }; // range -1 ~ +1
  77. void set_throttle(float throttle_in) { _throttle_in = throttle_in; }; // range 0 ~ 1
  78. void set_throttle_avg_max(float throttle_avg_max) { _throttle_avg_max = constrain_float(throttle_avg_max, 0.0f, 1.0f); }; // range 0 ~ 1
  79. void set_throttle_filter_cutoff(float filt_hz) { _throttle_filter.set_cutoff_frequency(filt_hz); }
  80. void set_forward(float forward_in) { _forward_in = forward_in; }; // range -1 ~ +1
  81. void set_lateral(float lateral_in) { _lateral_in = lateral_in; }; // range -1 ~ +1
  82. // accessors for roll, pitch, yaw and throttle inputs to motors
  83. float get_roll() const { return _roll_in; }
  84. float get_pitch() const { return _pitch_in; }
  85. float get_yaw() const { return _yaw_in; }
  86. float get_throttle() const { return constrain_float(_throttle_filter.get(), 0.0f, 1.0f); }
  87. float get_throttle_bidirectional() const { return constrain_float(2 * (_throttle_filter.get() - 0.5f), -1.0f, 1.0f); }
  88. float get_forward() const { return _forward_in; }
  89. float get_lateral() const { return _lateral_in; }
  90. virtual float get_throttle_hover() const = 0;
  91. // motor failure handling
  92. void set_thrust_boost(bool enable) { _thrust_boost = enable; }
  93. bool get_thrust_boost() const { return _thrust_boost; }
  94. virtual uint8_t get_lost_motor() const { return 0; }
  95. // desired spool states
  96. enum class DesiredSpoolState : uint8_t {
  97. SHUT_DOWN = 0, // all motors should move to stop
  98. GROUND_IDLE = 1, // all motors should move to ground idle
  99. THROTTLE_UNLIMITED = 2, // motors should move to being a state where throttle is unconstrained (e.g. by start up procedure)
  100. };
  101. void set_desired_spool_state(enum DesiredSpoolState spool);
  102. enum DesiredSpoolState get_desired_spool_state(void) const { return _spool_desired; }
  103. // spool states
  104. enum class SpoolState : uint8_t {
  105. SHUT_DOWN = 0, // all motors stop
  106. GROUND_IDLE = 1, // all motors at ground idle
  107. SPOOLING_UP = 2, // increasing maximum throttle while stabilizing
  108. THROTTLE_UNLIMITED = 3, // throttle is no longer constrained by start up procedure
  109. SPOOLING_DOWN = 4, // decreasing maximum throttle while stabilizing
  110. };
  111. // get_spool_state - get current spool state
  112. enum SpoolState get_spool_state(void) const { return _spool_state; }
  113. // set_density_ratio - sets air density as a proportion of sea level density
  114. void set_air_density_ratio(float ratio) { _air_density_ratio = ratio; }
  115. // structure for holding motor limit flags
  116. struct AP_Motors_limit {
  117. uint8_t roll : 1; // we have reached roll or pitch limit
  118. uint8_t pitch : 1; // we have reached roll or pitch limit
  119. uint8_t yaw : 1; // we have reached yaw limit
  120. uint8_t throttle_lower : 1; // we have reached throttle's lower limit
  121. uint8_t throttle_upper : 1; // we have reached throttle's upper limit
  122. } limit;
  123. //
  124. // virtual functions that should be implemented by child classes
  125. //
  126. // set update rate to motors - a value in hertz
  127. virtual void set_update_rate( uint16_t speed_hz ) { _speed_hz = speed_hz; }
  128. // init
  129. virtual void init(motor_frame_class frame_class, motor_frame_type frame_type) = 0;
  130. // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
  131. virtual void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) = 0;
  132. // output - sends commands to the motors
  133. virtual void output() = 0;
  134. // output_min - sends minimum values out to the motors
  135. virtual void output_min() = 0;
  136. // output_test_seq - spin a motor at the pwm value specified
  137. // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
  138. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  139. virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) = 0;
  140. // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
  141. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  142. virtual uint16_t get_motor_mask() = 0;
  143. // pilot input in the -1 ~ +1 range for roll, pitch and yaw. 0~1 range for throttle
  144. void set_radio_passthrough(float roll_input, float pitch_input, float throttle_input, float yaw_input);
  145. // set loop rate. Used to support loop rate as a parameter
  146. void set_loop_rate(uint16_t loop_rate) { _loop_rate = loop_rate; }
  147. // return the roll factor of any motor, this is used for tilt rotors and tail sitters
  148. // using copter motors for forward flight
  149. virtual float get_roll_factor(uint8_t i) { return 0.0f; }
  150. enum pwm_type { PWM_TYPE_NORMAL = 0,
  151. PWM_TYPE_ONESHOT = 1,
  152. PWM_TYPE_ONESHOT125 = 2,
  153. PWM_TYPE_BRUSHED = 3,
  154. PWM_TYPE_DSHOT150 = 4,
  155. PWM_TYPE_DSHOT300 = 5,
  156. PWM_TYPE_DSHOT600 = 6,
  157. PWM_TYPE_DSHOT1200 = 7};
  158. pwm_type get_pwm_type(void) const { return (pwm_type)_pwm_type.get(); }
  159. protected:
  160. // output functions that should be overloaded by child classes
  161. virtual void output_armed_stabilizing() = 0;
  162. virtual void rc_write(uint8_t chan, uint16_t pwm);
  163. virtual void rc_write_angle(uint8_t chan, int16_t angle_cd);
  164. virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz);
  165. virtual uint32_t rc_map_mask(uint32_t mask) const;
  166. // add a motor to the motor map
  167. void add_motor_num(int8_t motor_num);
  168. // update the throttle input filter
  169. virtual void update_throttle_filter() = 0;
  170. // save parameters as part of disarming
  171. virtual void save_params_on_disarm() {}
  172. // flag bitmask
  173. struct AP_Motors_flags {
  174. uint8_t armed : 1; // 0 if disarmed, 1 if armed
  175. uint8_t interlock : 1; // 1 if the motor interlock is enabled (i.e. motors run), 0 if disabled (motors don't run)
  176. uint8_t initialised_ok : 1; // 1 if initialisation was successful
  177. } _flags;
  178. // internal variables
  179. uint16_t _loop_rate; // rate in Hz at which output() function is called (normally 400hz)
  180. uint16_t _speed_hz; // speed in hz to send updates to motors
  181. float _roll_in; // desired roll control from attitude controllers, -1 ~ +1
  182. float _roll_in_ff; // desired roll feed forward control from attitude controllers, -1 ~ +1
  183. float _pitch_in; // desired pitch control from attitude controller, -1 ~ +1
  184. float _pitch_in_ff; // desired pitch feed forward control from attitude controller, -1 ~ +1
  185. float _yaw_in; // desired yaw control from attitude controller, -1 ~ +1
  186. float _yaw_in_ff; // desired yaw feed forward control from attitude controller, -1 ~ +1
  187. float _throttle_in; // last throttle input from set_throttle caller
  188. float _forward_in; // last forward input from set_forward caller
  189. float _lateral_in; // last lateral input from set_lateral caller
  190. float _throttle_avg_max; // last throttle input from set_throttle_avg_max
  191. LowPassFilterFloat _throttle_filter; // throttle input filter
  192. DesiredSpoolState _spool_desired; // desired spool state
  193. SpoolState _spool_state; // current spool mode
  194. // air pressure compensation variables
  195. float _air_density_ratio; // air density / sea level density - decreases in altitude
  196. // mask of what channels need fast output
  197. uint16_t _motor_fast_mask;
  198. // pass through variables
  199. float _roll_radio_passthrough; // roll input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
  200. float _pitch_radio_passthrough; // pitch input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
  201. float _throttle_radio_passthrough; // throttle/collective input from pilot in 0 ~ 1 range. used for setup and providing servo feedback while landed
  202. float _yaw_radio_passthrough; // yaw input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
  203. AP_Int8 _pwm_type; // PWM output type
  204. // motor failure handling
  205. bool _thrust_boost; // true if thrust boost is enabled to handle motor failure
  206. bool _thrust_balanced; // true when output thrust is well balanced
  207. float _thrust_boost_ratio; // choice between highest and second highest motor output for output mixing (0 ~ 1). Zero is normal operation
  208. private:
  209. static AP_Motors *_singleton;
  210. };