APM:Libraries
RCOutput_Sysfs.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_Linux.h"
4 #include "PWM_Sysfs.h"
5 
6 namespace Linux {
7 
9 public:
10  RCOutput_Sysfs(uint8_t chip, uint8_t channel_base, uint8_t channel_count);
12 
14  {
15  return static_cast<RCOutput_Sysfs *>(rcoutput);
16  }
17 
18  void init();
19  void set_freq(uint32_t chmask, uint16_t freq_hz);
20  uint16_t get_freq(uint8_t ch);
21  void enable_ch(uint8_t ch);
22  void disable_ch(uint8_t ch);
23  void write(uint8_t ch, uint16_t period_us);
24  uint16_t read(uint8_t ch);
25  void read(uint16_t *period_us, uint8_t len);
26  void cork(void) override;
27  void push(void) override;
28 
29 private:
30  const uint8_t _chip;
31  const uint8_t _channel_base;
32  const uint8_t _channel_count;
34 
35  // for handling cork()/push()
36  bool _corked;
37  uint16_t *_pending;
38  uint32_t _pending_mask;
39 };
40 
41 }
const uint8_t _channel_base
void cork(void) override
void enable_ch(uint8_t ch)
RCOutput_Sysfs(uint8_t chip, uint8_t channel_base, uint8_t channel_count)
void set_freq(uint32_t chmask, uint16_t freq_hz)
uint16_t read(uint8_t ch)
const uint8_t _channel_count
PWM_Sysfs_Base ** _pwm_channels
uint16_t get_freq(uint8_t ch)
static RCOutput_Sysfs * from(AP_HAL::RCOutput *rcoutput)
void push(void) override
void disable_ch(uint8_t ch)
void write(uint8_t ch, uint16_t period_us)