RCOutput_PCA9685.h 1.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152
  1. #pragma once
  2. #include <AP_HAL/I2CDevice.h>
  3. #include "AP_HAL_Linux.h"
  4. #define PCA9685_PRIMARY_ADDRESS 0x40 // All address pins low, PCA9685 default
  5. #define PCA9685_SECONDARY_ADDRESS 0x41
  6. #define PCA9685_TERTIARY_ADDRESS 0x42
  7. #define PCA9685_QUATENARY_ADDRESS 0x55
  8. #define PCA9685_QUINARY_ADDRESS 0x61
  9. namespace Linux {
  10. class RCOutput_PCA9685 : public AP_HAL::RCOutput {
  11. public:
  12. RCOutput_PCA9685(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  13. bool external_clock,
  14. uint8_t channel_offset,
  15. int16_t oe_pin_number);
  16. ~RCOutput_PCA9685();
  17. void init() override;
  18. void reset_all_channels();
  19. void set_freq(uint32_t chmask, uint16_t freq_hz) override;
  20. uint16_t get_freq(uint8_t ch) override;
  21. void enable_ch(uint8_t ch) override;
  22. void disable_ch(uint8_t ch) override;
  23. void write(uint8_t ch, uint16_t period_us) override;
  24. void cork() override;
  25. void push() override;
  26. uint16_t read(uint8_t ch) override;
  27. void read(uint16_t* period_us, uint8_t len) override;
  28. private:
  29. void reset();
  30. AP_HAL::DigitalSource *_enable_pin;
  31. AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
  32. uint16_t _frequency;
  33. float _osc_clock;
  34. uint16_t *_pulses_buffer;
  35. bool _external_clock;
  36. bool _corking = false;
  37. uint8_t _channel_offset;
  38. int16_t _oe_pin_number;
  39. uint16_t _pending_write_mask;
  40. };
  41. }