RCOutput_Sysfs.h 1.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041
  1. #pragma once
  2. #include "AP_HAL_Linux.h"
  3. #include "PWM_Sysfs.h"
  4. namespace Linux {
  5. class RCOutput_Sysfs : public AP_HAL::RCOutput {
  6. public:
  7. RCOutput_Sysfs(uint8_t chip, uint8_t channel_base, uint8_t channel_count);
  8. ~RCOutput_Sysfs();
  9. static RCOutput_Sysfs *from(AP_HAL::RCOutput *rcoutput)
  10. {
  11. return static_cast<RCOutput_Sysfs *>(rcoutput);
  12. }
  13. void init() override;
  14. void set_freq(uint32_t chmask, uint16_t freq_hz) override;
  15. uint16_t get_freq(uint8_t ch) override;
  16. void enable_ch(uint8_t ch) override;
  17. void disable_ch(uint8_t ch) override;
  18. void write(uint8_t ch, uint16_t period_us) override;
  19. uint16_t read(uint8_t ch) override;
  20. void read(uint16_t *period_us, uint8_t len) override;
  21. void cork(void) override;
  22. void push(void) override;
  23. private:
  24. const uint8_t _chip;
  25. const uint8_t _channel_base;
  26. const uint8_t _channel_count;
  27. PWM_Sysfs_Base **_pwm_channels;
  28. // for handling cork()/push()
  29. bool _corked;
  30. uint16_t *_pending;
  31. uint32_t _pending_mask;
  32. };
  33. }