7 #define MAX_ZYNQ_PWMS 8 12 void set_freq(uint32_t chmask, uint16_t freq_hz);
16 void write(uint8_t ch, uint16_t period_us);
17 uint16_t
read(uint8_t ch);
18 void read(uint16_t* period_us, uint8_t len);
19 void cork(
void)
override;
20 void push(
void)
override;
23 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OCPOC_ZYNQ 27 static const int TICK_PER_US=100;
28 static const int TICK_PER_S=100000000;
void set_freq(uint32_t chmask, uint16_t freq_hz)
void enable_ch(uint8_t ch)
void write(uint8_t ch, uint16_t period_us)
static const int TICK_PER_S
uint16_t get_freq(uint8_t ch)
static const int TICK_PER_US
void disable_ch(uint8_t ch)
volatile struct pwm_cmd * sharedMem_cmd
uint16_t read(uint8_t ch)
uint16_t pending[MAX_ZYNQ_PWMS]