APM:Libraries
RCInput_RPI.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_Linux.h"
4 #include "RCInput.h"
5 #include <signal.h>
6 #include <pthread.h>
7 #include <stdio.h>
8 #include <stdlib.h>
9 #include <unistd.h>
10 #include <string.h>
11 #include <errno.h>
12 #include <stdarg.h>
13 #include <stdint.h>
14 #include <signal.h>
15 #include <time.h>
16 #include <sys/time.h>
17 #include <sys/types.h>
18 #include <sys/stat.h>
19 #include <fcntl.h>
20 #include <sys/mman.h>
21 #include <assert.h>
22 #include <queue>
23 
24 
25 namespace Linux {
26 
27 enum state_t{
31 };
32 
33 //Memory table structure
34 typedef struct {
35  void **virt_pages;
36  void **phys_pages;
37  uint32_t page_count;
39 
40 
41 //DMA control block structure
42 typedef struct {
43  uint32_t info, src, dst, length,
44  stride, next, pad[2];
45 } dma_cb_t;
46 
47 class Memory_table {
48 // Allow RCInput_RPI access to private members of Memory_table
49 friend class RCInput_RPI;
50 
51 private:
52  void** _virt_pages;
53  void** _phys_pages;
54  uint32_t _page_count;
55 
56 public:
57  Memory_table();
58  Memory_table(uint32_t, int);
59  ~Memory_table();
60 
61  //Get virtual address from the corresponding physical address from memory_table.
62  void* get_virt_addr(const uint32_t phys_addr) const;
63 
64  // This function returns physical address with help of pointer, which is offset from the beginning of the buffer.
65  void* get_page(void **pages, const uint32_t addr) const;
66 
67  // This function returns offset from the beginning of the buffer using (virtual) address in 'pages' and memory_table.
68  uint32_t get_offset(void **pages, const uint32_t addr) const;
69 
70  //How many bytes are available for reading in circle buffer?
71  uint32_t bytes_available(const uint32_t read_addr, const uint32_t write_addr) const;
72 
73  uint32_t get_page_count() const;
74 };
75 
76 
77 class RCInput_RPI : public RCInput
78 {
79 public:
80  void init();
81  void _timer_tick(void);
82  RCInput_RPI();
83  ~RCInput_RPI();
84 
85 private:
86 
87  //Physical adresses of peripherals. Are different on different Raspberries.
88  uint32_t dma_base;
89  uint32_t clk_base;
90  uint32_t pcm_base;
91 
92  //registers
93  static volatile uint32_t *pcm_reg;
94  static volatile uint32_t *clk_reg;
95  static volatile uint32_t *dma_reg;
96 
99 
100  uint64_t curr_tick;
101  uint64_t prev_tick;
102  uint64_t delta_time;
103 
104  uint32_t curr_tick_inc;
105  uint32_t curr_pointer;
106  uint32_t curr_channel;
107 
108  uint16_t width_s0;
109  uint16_t width_s1;
110 
111  uint8_t curr_signal;
112  uint8_t last_signal;
113 
114  bool _initialized = false;
115 
117 
119 
120  void init_dma_cb(dma_cb_t** cbp, uint32_t mode, uint32_t source, uint32_t dest, uint32_t length, uint32_t stride, uint32_t next_cb);
121  void* map_peripheral(uint32_t base, uint32_t len);
122  void init_registers();
123  void init_ctrl_data();
124  void init_PCM();
125  void init_DMA();
126  void init_buffer();
127  static void stop_dma();
128  static void termination_handler(int signum);
129  void set_sigaction();
130  void set_physical_addresses(int version);
131  void teardown() override;
132 };
133 
134 }
AP_HAL::DigitalSource * enable_pin
Definition: RCInput_RPI.h:118
Memory_table * circle_buffer
Definition: RCInput_RPI.h:97
uint32_t curr_tick_inc
Definition: RCInput_RPI.h:104
uint32_t get_page_count() const
void * get_virt_addr(const uint32_t phys_addr) const
void * get_page(void **pages, const uint32_t addr) const
static volatile uint32_t * clk_reg
Definition: RCInput_RPI.h:94
uint32_t get_offset(void **pages, const uint32_t addr) const
uint32_t bytes_available(const uint32_t read_addr, const uint32_t write_addr) const
uint32_t _page_count
Definition: RCInput_RPI.h:54
uint32_t curr_pointer
Definition: RCInput_RPI.h:105
uint32_t stride
Definition: RCInput_RPI.h:43
void init()
Generic board initialization function.
Definition: system.cpp:136
static volatile uint32_t * dma_reg
Definition: RCInput_RPI.h:95
Memory_table * con_blocks
Definition: RCInput_RPI.h:98
static volatile uint32_t * pcm_reg
Definition: RCInput_RPI.h:93
friend class RCInput_RPI
Definition: RCInput_RPI.h:49
uint32_t curr_channel
Definition: RCInput_RPI.h:106