2015-10-09 16:40:42 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "AP_HAL_Linux.h"
|
|
|
|
#include "PWM_Sysfs.h"
|
|
|
|
|
2016-07-29 16:14:02 -03:00
|
|
|
namespace Linux {
|
|
|
|
|
|
|
|
class RCOutput_Sysfs : public AP_HAL::RCOutput {
|
2015-10-09 16:40:42 -03:00
|
|
|
public:
|
2016-06-07 02:06:35 -03:00
|
|
|
RCOutput_Sysfs(uint8_t chip, uint8_t channel_base, uint8_t channel_count);
|
2015-10-09 16:40:42 -03:00
|
|
|
~RCOutput_Sysfs();
|
|
|
|
|
|
|
|
static RCOutput_Sysfs *from(AP_HAL::RCOutput *rcoutput)
|
|
|
|
{
|
|
|
|
return static_cast<RCOutput_Sysfs *>(rcoutput);
|
|
|
|
}
|
|
|
|
|
2019-02-21 19:08:12 -04:00
|
|
|
void init() override;
|
|
|
|
void set_freq(uint32_t chmask, uint16_t freq_hz) override;
|
|
|
|
uint16_t get_freq(uint8_t ch) override;
|
|
|
|
void enable_ch(uint8_t ch) override;
|
|
|
|
void disable_ch(uint8_t ch) override;
|
|
|
|
void write(uint8_t ch, uint16_t period_us) override;
|
|
|
|
uint16_t read(uint8_t ch) override;
|
|
|
|
void read(uint16_t *period_us, uint8_t len) override;
|
2016-10-11 17:58:40 -03:00
|
|
|
void cork(void) override;
|
|
|
|
void push(void) override;
|
2015-10-09 16:40:42 -03:00
|
|
|
|
|
|
|
private:
|
|
|
|
const uint8_t _chip;
|
2016-06-07 02:06:35 -03:00
|
|
|
const uint8_t _channel_base;
|
2015-10-09 16:40:42 -03:00
|
|
|
const uint8_t _channel_count;
|
2016-06-07 02:06:35 -03:00
|
|
|
PWM_Sysfs_Base **_pwm_channels;
|
2016-10-11 17:58:40 -03:00
|
|
|
|
|
|
|
// for handling cork()/push()
|
|
|
|
bool _corked;
|
|
|
|
uint16_t *_pending;
|
|
|
|
uint32_t _pending_mask;
|
2015-10-09 16:40:42 -03:00
|
|
|
};
|
2016-07-29 16:14:02 -03:00
|
|
|
|
|
|
|
}
|