14 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET 15 #define RCOUT_PRUSS_RAM_BASE 0x4a300000 16 #define RCOUT_PRUSS_CTRL_BASE 0x4a322000 17 #define RCOUT_PRUSS_IRAM_BASE 0x4a334000 19 #define RCOUT_PRUSS_RAM_BASE 0x4a302000 20 #define RCOUT_PRUSS_CTRL_BASE 0x4a324000 21 #define RCOUT_PRUSS_IRAM_BASE 0x4a338000 23 #define PWM_CHAN_COUNT 12 29 void set_freq(uint32_t chmask, uint16_t freq_hz);
33 void write(uint8_t ch, uint16_t period_us);
34 uint16_t
read(uint8_t ch);
35 void read(uint16_t* period_us, uint8_t len);
36 void cork(
void)
override;
37 void push(
void)
override;
uint16_t get_freq(uint8_t ch)
void disable_ch(uint8_t ch)
static const uint32_t TICK_PER_S
static const uint32_t TICK_PER_US
void write(uint8_t ch, uint16_t period_us)
uint16_t pending[PWM_CHAN_COUNT]
void enable_ch(uint8_t ch)
volatile uint32_t time_high
uint16_t read(uint8_t ch)
volatile struct pwm * pwm
struct Linux::RCOutput_AioPRU::pwm::@100 channel[PWM_CHAN_COUNT]
volatile uint32_t channelenable
void set_freq(uint32_t chmask, uint16_t freq_hz)