RCOutput_ZYNQ.h 1.2 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. namespace Linux {
  4. #define MAX_ZYNQ_PWMS 8 /* number of pwm channels */
  5. class RCOutput_ZYNQ : public AP_HAL::RCOutput {
  6. public:
  7. void init() override;
  8. void set_freq(uint32_t chmask, uint16_t freq_hz) override;
  9. uint16_t get_freq(uint8_t ch) override;
  10. void enable_ch(uint8_t ch) override;
  11. void disable_ch(uint8_t ch) override;
  12. void write(uint8_t ch, uint16_t period_us) override;
  13. uint16_t read(uint8_t ch) override;
  14. void read(uint16_t* period_us, uint8_t len) override;
  15. void cork(void) override;
  16. void push(void) override;
  17. private:
  18. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OCPOC_ZYNQ
  19. static const int TICK_PER_US=50;
  20. static const int TICK_PER_S=50000000;
  21. #else
  22. static const int TICK_PER_US=100;
  23. static const int TICK_PER_S=100000000;
  24. #endif
  25. // Period|Hi 32 bits each
  26. struct s_period_hi {
  27. uint32_t period;
  28. uint32_t hi;
  29. };
  30. struct pwm_cmd {
  31. struct s_period_hi periodhi[MAX_ZYNQ_PWMS];
  32. };
  33. volatile struct pwm_cmd *sharedMem_cmd;
  34. uint16_t pending[MAX_ZYNQ_PWMS];
  35. bool corked;
  36. uint32_t pending_mask;
  37. };
  38. }