47 void set_freq(uint32_t chmask, uint16_t freq_hz)
override;
56 uint16_t
get_freq(uint8_t ch)
override;
64 void write(uint8_t ch, uint16_t period_us)
override;
73 uint16_t
read(uint8_t ch)
override;
82 void read(uint16_t *period_us, uint8_t len)
override;
94 static uint16_t
_usec_to_hw(uint16_t freq, uint16_t usec);
103 static uint16_t
_hw_to_usec(uint16_t freq, uint16_t hw_val);
113 bool _hw_write(uint16_t address, uint16_t data);
122 uint16_t
_hw_read(uint16_t address);
void enable_ch(uint8_t ch) override
AP_HAL::OwnPtr< AP_HAL::Device > _spi
uint16_t read(uint8_t ch) override
static uint16_t _hw_to_usec(uint16_t freq, uint16_t hw_val)
bool _hw_write(uint16_t address, uint16_t data)
uint32_t _pending_duty_write_mask
void write(uint8_t ch, uint16_t period_us) override
void set_freq(uint32_t chmask, uint16_t freq_hz) override
uint16_t _hw_read(uint16_t address)
uint16_t get_freq(uint8_t ch) override
void disable_ch(uint8_t ch) override
static uint16_t _usec_to_hw(uint16_t freq, uint16_t usec)
uint32_t _pending_freq_write_mask