27 , _channel_base(channel_base)
28 , _channel_count(channel_count)
30 , _pending(new uint16_t[_channel_count])
46 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO 48 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RST_ZYNQ 54 AP_HAL::panic(
"RCOutput_Sysfs_PWM: Unable to setup PWM pin.");
69 if (chmask & 1 << i) {
127 period_us[i] =
read(i);
const uint8_t _channel_base
void enable_ch(uint8_t ch)
RCOutput_Sysfs(uint8_t chip, uint8_t channel_base, uint8_t channel_count)
bool set_duty_cycle(uint32_t nsec_duty_cycle)
void set_freq(uint32_t chmask, uint16_t freq_hz)
uint16_t read(uint8_t ch)
uint32_t nsec_to_usec(uint32_t nsec)
const uint8_t _channel_count
PWM_Sysfs_Base ** _pwm_channels
uint16_t get_freq(uint8_t ch)
uint32_t usec_to_nsec(uint32_t usec)
virtual void set_polarity(PWM_Sysfs_Base::Polarity polarity)
Common definitions and utility routines for the ArduPilot libraries.
void disable_ch(uint8_t ch)
void write(uint8_t ch, uint16_t period_us)
void panic(const char *errormsg,...) FMT_PRINTF(1
void set_freq(uint32_t freq)