APM:Libraries
RCOutput_ZYNQ.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 
5 namespace Linux {
6 
7 #define MAX_ZYNQ_PWMS 8 /* number of pwm channels */
8 
10 public:
11  void init();
12  void set_freq(uint32_t chmask, uint16_t freq_hz);
13  uint16_t get_freq(uint8_t ch);
14  void enable_ch(uint8_t ch);
15  void disable_ch(uint8_t ch);
16  void write(uint8_t ch, uint16_t period_us);
17  uint16_t read(uint8_t ch);
18  void read(uint16_t* period_us, uint8_t len);
19  void cork(void) override;
20  void push(void) override;
21 
22 private:
23 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OCPOC_ZYNQ
24  static const int TICK_PER_US=50;
25  static const int TICK_PER_S=50000000;
26 #else
27  static const int TICK_PER_US=100;
28  static const int TICK_PER_S=100000000;
29 #endif
30 
31  // Period|Hi 32 bits each
32  struct s_period_hi {
33  uint32_t period;
34  uint32_t hi;
35  };
36  struct pwm_cmd {
37  struct s_period_hi periodhi[MAX_ZYNQ_PWMS];
38  };
39  volatile struct pwm_cmd *sharedMem_cmd;
40 
42  bool corked;
43  uint32_t pending_mask;
44 };
45 
46 }
void set_freq(uint32_t chmask, uint16_t freq_hz)
void cork(void) override
void enable_ch(uint8_t ch)
void write(uint8_t ch, uint16_t period_us)
static const int TICK_PER_S
Definition: RCOutput_ZYNQ.h:25
uint16_t get_freq(uint8_t ch)
static const int TICK_PER_US
Definition: RCOutput_ZYNQ.h:24
#define MAX_ZYNQ_PWMS
Definition: RCOutput_ZYNQ.h:7
void disable_ch(uint8_t ch)
volatile struct pwm_cmd * sharedMem_cmd
Definition: RCOutput_ZYNQ.h:39
uint16_t read(uint8_t ch)
uint16_t pending[MAX_ZYNQ_PWMS]
Definition: RCOutput_ZYNQ.h:41
void push(void) override