4 #define RCOUT_PRUSS_SHAREDRAM_BASE 0x4a310000 6 #define PWM_CMD_MAGIC 0xf00fbaaf 7 #define PWM_REPLY_MAGIC 0xbaaff00f 8 #define PWM_CMD_CONFIG 0 9 #define PWM_CMD_ENABLE 1 10 #define PWM_CMD_DISABLE 2 11 #define PWM_CMD_MODIFY 3 14 #define PWM_CMD_TEST 6 20 void set_freq(uint32_t chmask, uint16_t freq_hz);
24 void write(uint8_t ch, uint16_t period_us);
25 uint16_t
read(uint8_t ch);
26 void read(uint16_t* period_us, uint8_t len);
27 void cork(
void)
override;
28 void push(
void)
override;
uint16_t read(uint8_t ch)
uint32_t periodhi[MAX_PWMS][2]
void enable_ch(uint8_t ch)
void set_freq(uint32_t chmask, uint16_t freq_hz)
static const int TICK_PER_S
uint32_t hilo_read[MAX_PWMS][2]
uint16_t pending[MAX_PWMS]
void disable_ch(uint8_t ch)
static const int TICK_PER_US
uint16_t get_freq(uint8_t ch)
void write(uint8_t ch, uint16_t period_us)
volatile struct pwm_cmd * sharedMem_cmd