RCOutput_Bebop.h 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109
  1. #pragma once
  2. #include "AP_HAL_Linux.h"
  3. #include <AP_HAL/I2CDevice.h>
  4. struct bldc_info;
  5. namespace Linux {
  6. enum bebop_bldc_motor {
  7. BEBOP_BLDC_MOTOR_1 = 0,
  8. #if CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_DISCO
  9. BEBOP_BLDC_MOTOR_2,
  10. BEBOP_BLDC_MOTOR_3,
  11. BEBOP_BLDC_MOTOR_4,
  12. #endif
  13. BEBOP_BLDC_MOTORS_NUM,
  14. };
  15. enum bebop_bldc_sound {
  16. BEBOP_BLDC_SOUND_NONE = 0,
  17. BEBOP_BLDC_SOUND_SHORT_BEEP,
  18. BEBOP_BLDC_SOUND_BOOT_BEEP,
  19. BEBOP_BLDC_SOUND_BEBOP,
  20. };
  21. /* description of the bldc status */
  22. #define BEBOP_BLDC_STATUS_INIT 0
  23. #define BEBOP_BLDC_STATUS_IDLE 1
  24. #define BEBOP_BLDC_STATUS_RAMPING 2
  25. #define BEBOP_BLDC_STATUS_SPINNING_1 3
  26. #define BEBOP_BLDC_STATUS_SPINNING_2 4
  27. #define BEBOP_BLDC_STATUS_STOPPING 5
  28. #define BEBOP_BLDC_STATUS_CRITICAL 6
  29. /* description of the bldc errno */
  30. #define BEBOP_BLDC_ERRNO_EEPROM 1
  31. #define BEBOP_BLDC_ERRNO_MOTOR_STALLED 2
  32. #define BEBOP_BLDC_ERRNO_PROP_SECU 3
  33. #define BEBOP_BLDC_ERRNO_COM_LOST 4
  34. #define BEBOP_BLDC_ERRNO_BATT_LEVEL 9
  35. #define BEBOP_BLDC_ERRNO_LIPO 10
  36. #define BEBOP_BLDC_ERRNO_MOTOR_HW 11
  37. class BebopBLDC_ObsData {
  38. public:
  39. uint16_t rpm[BEBOP_BLDC_MOTORS_NUM];
  40. uint8_t rpm_saturated[BEBOP_BLDC_MOTORS_NUM];
  41. uint16_t batt_mv;
  42. uint8_t status;
  43. uint8_t error;
  44. uint8_t motors_err;
  45. uint8_t temperature;
  46. };
  47. class RCOutput_Bebop : public AP_HAL::RCOutput {
  48. public:
  49. RCOutput_Bebop(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
  50. static RCOutput_Bebop *from(AP_HAL::RCOutput *rcout) {
  51. return static_cast<RCOutput_Bebop*>(rcout);
  52. }
  53. void init() override;
  54. void set_freq(uint32_t chmask, uint16_t freq_hz) override;
  55. uint16_t get_freq(uint8_t ch) override;
  56. void enable_ch(uint8_t ch) override;
  57. void disable_ch(uint8_t ch) override;
  58. void write(uint8_t ch, uint16_t period_us) override;
  59. void cork() override;
  60. void push() override;
  61. uint16_t read(uint8_t ch) override;
  62. void read(uint16_t* period_us, uint8_t len) override;
  63. void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override;
  64. int read_obs_data(BebopBLDC_ObsData &data);
  65. void play_note(uint8_t pwm, uint16_t period_us, uint16_t duration_ms);
  66. private:
  67. AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
  68. uint16_t _request_period_us[BEBOP_BLDC_MOTORS_NUM];
  69. uint16_t _period_us[BEBOP_BLDC_MOTORS_NUM];
  70. uint16_t _rpm[BEBOP_BLDC_MOTORS_NUM];
  71. uint16_t _frequency;
  72. uint16_t _min_pwm;
  73. uint16_t _max_pwm;
  74. uint8_t _n_motors=4;
  75. uint8_t _state;
  76. bool _corking = false;
  77. uint16_t _max_rpm;
  78. uint8_t _checksum(uint8_t *data, unsigned int len);
  79. void _start_prop();
  80. void _toggle_gpio(uint8_t mask);
  81. void _set_ref_speed(uint16_t rpm[BEBOP_BLDC_MOTORS_NUM]);
  82. bool _get_info(struct bldc_info *info);
  83. void _stop_prop();
  84. void _clear_error();
  85. void _play_sound(uint8_t sound);
  86. uint16_t _period_us_to_rpm(uint16_t period_us);
  87. /* thread related members */
  88. pthread_t _thread;
  89. pthread_mutex_t _mutex;
  90. pthread_cond_t _cond;
  91. void _run_rcout();
  92. static void *_control_thread(void *arg);
  93. };
  94. }