45 char *enable_path,
char *duty_path,
46 char *period_path, uint8_t channel);
63 char *_generate_export_path(uint8_t chip);
64 char *_generate_polarity_path(uint8_t chip, uint8_t channel);
65 char *_generate_enable_path(uint8_t chip, uint8_t channel);
66 char *_generate_duty_path(uint8_t chip, uint8_t channel);
67 char *_generate_period_path(uint8_t chip, uint8_t channel);
75 char *_generate_export_path();
76 char *_generate_polarity_path(uint8_t channel);
77 char *_generate_enable_path(uint8_t channel);
78 char *_generate_duty_path(uint8_t channel);
79 char *_generate_period_path(uint8_t channel);
uint32_t _nsec_duty_cycle_value
void set_polarity(PWM_Sysfs_Base::Polarity polarity) override
PWM_Sysfs_Base(char *export_path, char *polarity_path, char *enable_path, char *duty_path, char *period_path, uint8_t channel)
uint32_t get_duty_cycle()
bool set_duty_cycle(uint32_t nsec_duty_cycle)
virtual ~PWM_Sysfs_Base()
PWM_Sysfs_Base::Polarity get_polarity() override
void set_period(uint32_t nsec_period)
virtual PWM_Sysfs_Base::Polarity get_polarity()
virtual void set_polarity(PWM_Sysfs_Base::Polarity polarity)
void set_freq(uint32_t freq)