APM:Libraries
RCInput_RPI.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
4  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
5  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
6  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \
7  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
8 #include <assert.h>
9 #include <errno.h>
10 #include <fcntl.h>
11 #include <pthread.h>
12 #include <stdint.h>
13 #include <stdio.h>
14 #include <stdlib.h>
15 #include <string.h>
16 #include <sys/ioctl.h>
17 #include <sys/mman.h>
18 #include <sys/stat.h>
19 #include <sys/time.h>
20 #include <sys/types.h>
21 #include <time.h>
22 #include <unistd.h>
23 
24 #include "GPIO.h"
25 #include "RCInput_RPI.h"
26 #include "Util_RPI.h"
27 
28 #ifdef DEBUG
29 #define debug(fmt, args ...) do { fprintf(stderr,"[RCInput_RPI]: %s:%d: " fmt, __FUNCTION__, __LINE__, ## args); } while (0)
30 #else
31 #define debug(fmt, args ...)
32 #endif
33 
34 //Parametres
35 #define RCIN_RPI_BUFFER_LENGTH 8
36 #define RCIN_RPI_SAMPLE_FREQ 500
37 #define RCIN_RPI_DMA_CHANNEL 0
38 #define RCIN_RPI_MAX_COUNTER 1300
39 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
40 #define PPM_INPUT_RPI RPI_GPIO_5
41 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
42 #define PPM_INPUT_RPI NAVIO_GPIO_PPM_IN
43 #define PAGE_SIZE (4*1024)
44 #else
45 #define PPM_INPUT_RPI RPI_GPIO_4
46 #endif
47 #define RCIN_RPI_MAX_SIZE_LINE 50
48 
49 //Memory Addresses
50 #define RCIN_RPI_RPI1_DMA_BASE 0x20007000
51 #define RCIN_RPI_RPI1_CLK_BASE 0x20101000
52 #define RCIN_RPI_RPI1_PCM_BASE 0x20203000
53 
54 #define RCIN_RPI_RPI2_DMA_BASE 0x3F007000
55 #define RCIN_RPI_RPI2_CLK_BASE 0x3F101000
56 #define RCIN_RPI_RPI2_PCM_BASE 0x3F203000
57 
58 #define RCIN_RPI_GPIO_LEV0_ADDR 0x7e200034
59 #define RCIN_RPI_DMA_LEN 0x1000
60 #define RCIN_RPI_CLK_LEN 0xA8
61 #define RCIN_RPI_PCM_LEN 0x24
62 #define RCIN_RPI_TIMER_BASE 0x7e003004
63 
64 #define RCIN_RPI_DMA_SRC_INC (1<<8)
65 #define RCIN_RPI_DMA_DEST_INC (1<<4)
66 #define RCIN_RPI_DMA_NO_WIDE_BURSTS (1<<26)
67 #define RCIN_RPI_DMA_WAIT_RESP (1<<3)
68 #define RCIN_RPI_DMA_D_DREQ (1<<6)
69 #define RCIN_RPI_DMA_PER_MAP(x) ((x)<<16)
70 #define RCIN_RPI_DMA_END (1<<1)
71 #define RCIN_RPI_DMA_RESET (1<<31)
72 #define RCIN_RPI_DMA_INT (1<<2)
73 
74 #define RCIN_RPI_DMA_CS (0x00/4)
75 #define RCIN_RPI_DMA_CONBLK_AD (0x04/4)
76 #define RCIN_RPI_DMA_DEBUG (0x20/4)
77 
78 #define RCIN_RPI_PCM_CS_A (0x00/4)
79 #define RCIN_RPI_PCM_FIFO_A (0x04/4)
80 #define RCIN_RPI_PCM_MODE_A (0x08/4)
81 #define RCIN_RPI_PCM_RXC_A (0x0c/4)
82 #define RCIN_RPI_PCM_TXC_A (0x10/4)
83 #define RCIN_RPI_PCM_DREQ_A (0x14/4)
84 #define RCIN_RPI_PCM_INTEN_A (0x18/4)
85 #define RCIN_RPI_PCM_INT_STC_A (0x1c/4)
86 #define RCIN_RPI_PCM_GRAY (0x20/4)
87 
88 #define RCIN_RPI_PCMCLK_CNTL 38
89 #define RCIN_RPI_PCMCLK_DIV 39
90 
91 
92 extern const AP_HAL::HAL& hal;
93 
94 using namespace Linux;
95 
96 
97 volatile uint32_t *RCInput_RPI::pcm_reg;
98 volatile uint32_t *RCInput_RPI::clk_reg;
99 volatile uint32_t *RCInput_RPI::dma_reg;
100 
102 {
103  _page_count = 0;
104 }
105 
106 // Init Memory table
107 Memory_table::Memory_table(uint32_t page_count, int version)
108 {
109  uint32_t i;
110  int fdMem, file;
111  // Cache coherent adresses depends on RPI's version
112  uint32_t bus = version == 1 ? 0x40000000 : 0xC0000000;
113  uint64_t pageInfo;
114  void *offset;
115 
116  _virt_pages = (void **)calloc(page_count, sizeof(void *));
117  _phys_pages = (void **)calloc(page_count, sizeof(void *));
118  _page_count = page_count;
119 
120  if ((fdMem = open("/dev/mem", O_RDWR | O_SYNC | O_CLOEXEC)) < 0) {
121  fprintf(stderr, "Failed to open /dev/mem\n");
122  exit(-1);
123  }
124 
125  if ((file = open("/proc/self/pagemap", O_RDWR | O_SYNC | O_CLOEXEC)) < 0) {
126  fprintf(stderr, "Failed to open /proc/self/pagemap\n");
127  exit(-1);
128  }
129 
130  // Magic to determine the physical address for this page:
131  offset = mmap(0, _page_count * PAGE_SIZE, PROT_READ | PROT_WRITE, MAP_SHARED | MAP_ANONYMOUS | MAP_NORESERVE | MAP_LOCKED, -1, 0);
132  lseek(file, ((uintptr_t)offset) / PAGE_SIZE * 8, SEEK_SET);
133 
134  // Get list of available cache coherent physical addresses
135  for (i = 0; i < _page_count; i++) {
136  _virt_pages[i] = mmap(0, PAGE_SIZE, PROT_READ | PROT_WRITE, MAP_SHARED | MAP_ANONYMOUS | MAP_NORESERVE | MAP_LOCKED, -1, 0);
137  if (::read(file, &pageInfo, 8) < 8) {
138  fprintf(stderr, "Failed to read pagemap\n");
139  exit(-1);
140  }
141  _phys_pages[i] = (void *)((uintptr_t)(pageInfo * PAGE_SIZE) | bus);
142  }
143 
144  // Map physical addresses to virtual memory
145  for (i = 0; i < _page_count; i++) {
146  munmap(_virt_pages[i], PAGE_SIZE);
147  _virt_pages[i] = mmap(_virt_pages[i], PAGE_SIZE, PROT_READ | PROT_WRITE, MAP_SHARED | MAP_FIXED | MAP_NORESERVE | MAP_LOCKED, fdMem, ((uintptr_t)_phys_pages[i] & (version == 1 ? 0xFFFFFFFF : ~bus)));
148  memset(_virt_pages[i], 0xee, PAGE_SIZE);
149  }
150  close(file);
151  close(fdMem);
152 }
153 
155 {
156  free(_virt_pages);
157  free(_phys_pages);
158 }
159 
160 // This function returns physical address with help of pointer, which is offset
161 // from the beginning of the buffer.
162 void *Memory_table::get_page(void **const pages, uint32_t addr) const
163 {
164  if (addr >= PAGE_SIZE * _page_count) {
165  return nullptr;
166  }
167  return (uint8_t *)pages[(uint32_t)addr / 4096] + addr % 4096;
168 }
169 
170 //Get virtual address from the corresponding physical address from memory_table.
171 void *Memory_table::get_virt_addr(const uint32_t phys_addr) const
172 {
173  // FIXME: Can't the address be calculated directly?
174  // FIXME: if the address room in _phys_pages is not fragmented one may avoid
175  // a complete loop ..
176  uint32_t i = 0;
177  for (; i < _page_count; i++) {
178  if ((uintptr_t)_phys_pages[i] == (((uintptr_t)phys_addr) & 0xFFFFF000)) {
179  return (void *)((uintptr_t)_virt_pages[i] + (phys_addr & 0xFFF));
180  }
181  }
182  return nullptr;
183 }
184 
185 // This function returns offset from the beginning of the buffer using virtual
186 // address and memory_table.
187 uint32_t Memory_table::get_offset(void ** const pages, const uint32_t addr) const
188 {
189  uint32_t i = 0;
190  for (; i < _page_count; i++) {
191  if ((uintptr_t) pages[i] == (addr & 0xFFFFF000) ) {
192  return (i*PAGE_SIZE + (addr & 0xFFF));
193  }
194  }
195  return -1;
196 }
197 
198 // How many bytes are available for reading in circle buffer?
199 uint32_t Memory_table::bytes_available(const uint32_t read_addr, const uint32_t write_addr) const
200 {
201  if (write_addr > read_addr) {
202  return (write_addr - read_addr);
203  } else {
204  return _page_count * PAGE_SIZE - (read_addr - write_addr);
205  }
206 }
207 
209 {
210  return _page_count;
211 }
212 
213 // Physical addresses of peripheral depends on Raspberry Pi's version
215 {
216  if (version == 1) {
217  dma_base = RCIN_RPI_RPI1_DMA_BASE;
218  clk_base = RCIN_RPI_RPI1_CLK_BASE;
219  pcm_base = RCIN_RPI_RPI1_PCM_BASE;
220  } else if (version == 2) {
221  dma_base = RCIN_RPI_RPI2_DMA_BASE;
222  clk_base = RCIN_RPI_RPI2_CLK_BASE;
223  pcm_base = RCIN_RPI_RPI2_PCM_BASE;
224  }
225 }
226 
227 // Map peripheral to virtual memory
228 void *RCInput_RPI::map_peripheral(uint32_t base, uint32_t len)
229 {
230  int fd = open("/dev/mem", O_RDWR | O_CLOEXEC);
231  void *vaddr;
232 
233  if (fd < 0) {
234  printf("Failed to open /dev/mem: %m\n");
235  return nullptr;
236  }
237  vaddr = mmap(nullptr, len, PROT_READ | PROT_WRITE, MAP_SHARED, fd, base);
238  if (vaddr == MAP_FAILED) {
239  printf("rpio-pwm: Failed to map peripheral at 0x%08x: %m\n", base);
240  }
241 
242  close(fd);
243  return vaddr;
244 }
245 
246 // Method to init DMA control block
247 void RCInput_RPI::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)
248 {
249  (*cbp)->info = mode;
250  (*cbp)->src = source;
251  (*cbp)->dst = dest;
252  (*cbp)->length = length;
253  (*cbp)->next = next_cb;
254  (*cbp)->stride = stride;
255 }
256 
258 {
259  dma_reg[RCIN_RPI_DMA_CS | RCIN_RPI_DMA_CHANNEL << 8] = 0;
260 }
261 
262 /* We need to be sure that the DMA is stopped upon termination */
264 {
265  stop_dma();
266  AP_HAL::panic("Interrupted: %s", strsignal(signum));
267 }
268 
269 // This function is used to init DMA control blocks (setting sampling GPIO
270 // register, destination adresses, synchronization)
272 {
273  uint32_t phys_fifo_addr;
274  uint32_t dest = 0;
275  uint32_t cbp = 0;
276  dma_cb_t *cbp_curr;
277  // Set fifo addr (for delay)
278  phys_fifo_addr = ((pcm_base + 0x04) & 0x00FFFFFF) | 0x7e000000;
279 
280  // Init dma control blocks.
281  /*We are transferring 1 byte of GPIO register. Every 56th iteration we are
282  sampling TIMER register, which length is 8 bytes. So, for every 56 samples of GPIO we need
283  56 * 1 + 8 = 64 bytes of buffer. Value 56 was selected specially to have a 64-byte "block"
284  TIMER - GPIO. So, we have integer count of such "blocks" at one virtual page. (4096 / 64 = 64
285  "blocks" per page. As minimum, we must have 2 virtual pages of buffer (to have integer count of
286  vitual pages for control blocks): for every 56 iterations (64 bytes of buffer) we need 56 control blocks for GPIO
287  sampling, 56 control blocks for setting frequency and 1 control block for sampling timer, so,
288  we need 56 + 56 + 1 = 113 control blocks. For integer value, we need 113 pages of control blocks.
289  Each control block length is 32 bytes. In 113 pages we will have (113 * 4096 / 32) = 113 * 128 control
290  blocks. 113 * 128 control blocks = 64 * 128 bytes of buffer = 2 pages of buffer.
291  So, for 56 * 64 * 2 iteration we init DMA for sampling GPIO
292  and timer to (64 * 64 * 2) = 8192 bytes = 2 pages of buffer.
293  */
294 
295  for (uint32_t i = 0; i < 56 * 128 * RCIN_RPI_BUFFER_LENGTH; i++) {
296  //Transfer timer every 56th sample
297  if (i % 56 == 0) {
298  cbp_curr = (dma_cb_t *)con_blocks->get_page(con_blocks->_virt_pages, cbp);
299 
301  (uintptr_t)circle_buffer->get_page(circle_buffer->_phys_pages, dest),
302  8,
303  0,
304  (uintptr_t)con_blocks->get_page(con_blocks->_phys_pages,
305  cbp + sizeof(dma_cb_t)));
306 
307  dest += 8;
308  cbp += sizeof(dma_cb_t);
309  }
310 
311  // Transfer GPIO (1 byte)
312  cbp_curr = (dma_cb_t *)con_blocks->get_page(con_blocks->_virt_pages, cbp);
314  (uintptr_t)circle_buffer->get_page(circle_buffer->_phys_pages, dest),
315  1,
316  0,
317  (uintptr_t)con_blocks->get_page(con_blocks->_phys_pages,
318  cbp + sizeof(dma_cb_t)));
319 
320  dest += 1;
321  cbp += sizeof(dma_cb_t);
322 
323  // Delay (for setting sampling frequency)
324  /* DMA is waiting data request signal (DREQ) from PCM. PCM is set for 1 MhZ freqency, so,
325  each sample of GPIO is limited by writing to PCA queue.
326  */
327  cbp_curr = (dma_cb_t *)con_blocks->get_page(con_blocks->_virt_pages, cbp);
329  RCIN_RPI_TIMER_BASE, phys_fifo_addr,
330  4,
331  0,
332  (uintptr_t)con_blocks->get_page(con_blocks->_phys_pages,
333  cbp + sizeof(dma_cb_t)));
334 
335  cbp += sizeof(dma_cb_t);
336  }
337  //Make last control block point to the first (to make circle)
338  cbp -= sizeof(dma_cb_t);
339  ((dma_cb_t *)con_blocks->get_page(con_blocks->_virt_pages, cbp))->next = (uintptr_t)con_blocks->get_page(con_blocks->_phys_pages, 0);
340 }
341 
342 /*Initialise PCM
343  See BCM2835 documentation:
344  http://www.raspberrypi.org/wp-content/uploads/2012/02/BCM2835-ARM-Peripherals.pdf
345  */
347 {
348  pcm_reg[RCIN_RPI_PCM_CS_A] = 1; // Disable Rx+Tx, Enable PCM block
349  hal.scheduler->delay_microseconds(100);
350  clk_reg[RCIN_RPI_PCMCLK_CNTL] = 0x5A000006; // Source=PLLD (500MHz)
351  hal.scheduler->delay_microseconds(100);
352  clk_reg[RCIN_RPI_PCMCLK_DIV] = 0x5A000000 | ((50000/RCIN_RPI_SAMPLE_FREQ)<<12); // Set pcm div. If we need to configure DMA frequency.
353  hal.scheduler->delay_microseconds(100);
354  clk_reg[RCIN_RPI_PCMCLK_CNTL] = 0x5A000016; // Source=PLLD and enable
355  hal.scheduler->delay_microseconds(100);
356  pcm_reg[RCIN_RPI_PCM_TXC_A] = 0<<31 | 1<<30 | 0<<20 | 0<<16; // 1 channel, 8 bits
357  hal.scheduler->delay_microseconds(100);
358  pcm_reg[RCIN_RPI_PCM_MODE_A] = (10 - 1) << 10; //PCM mode
359  hal.scheduler->delay_microseconds(100);
360  pcm_reg[RCIN_RPI_PCM_CS_A] |= 1<<4 | 1<<3; // Clear FIFOs
361  hal.scheduler->delay_microseconds(100);
362  pcm_reg[RCIN_RPI_PCM_DREQ_A] = 64<<24 | 64<<8; // DMA Req when one slot is free?
363  hal.scheduler->delay_microseconds(100);
364  pcm_reg[RCIN_RPI_PCM_CS_A] |= 1<<9; // Enable DMA
365  hal.scheduler->delay_microseconds(100);
366  pcm_reg[RCIN_RPI_PCM_CS_A] |= 1<<2; // Enable Tx
367  hal.scheduler->delay_microseconds(100);
368 }
369 
370 /*Initialise DMA
371  See BCM2835 documentation:
372  http://www.raspberrypi.org/wp-content/uploads/2012/02/BCM2835-ARM-Peripherals.pdf
373  */
375 {
376  dma_reg[RCIN_RPI_DMA_CS | RCIN_RPI_DMA_CHANNEL << 8] = RCIN_RPI_DMA_RESET; //Reset DMA
377  hal.scheduler->delay_microseconds(100);
379  dma_reg[RCIN_RPI_DMA_CONBLK_AD | RCIN_RPI_DMA_CHANNEL << 8] = reinterpret_cast<uintptr_t>(con_blocks->get_page(con_blocks->_phys_pages, 0));//Set first control block address
380  dma_reg[RCIN_RPI_DMA_DEBUG | RCIN_RPI_DMA_CHANNEL << 8] = 7; // clear debug error flags
381  dma_reg[RCIN_RPI_DMA_CS | RCIN_RPI_DMA_CHANNEL << 8] = 0x10880001; // go, mid priority, wait for outstanding writes
382 }
383 
384 
385 // We must stop DMA when the process is killed
387 {
388  struct sigaction sa, sa_old;
389 
390  memset(&sa_old, 0, sizeof(sa));
391  memset(&sa, 0, sizeof(sa));
392 
393  /* Ignore signals */
394  sa.sa_handler = SIG_IGN;
395  sigaction(SIGWINCH, &sa, nullptr);
396  sigaction(SIGTTOU, &sa, nullptr);
397  sigaction(SIGTTIN, &sa, nullptr);
398 
399  /*
400  * Catch all other signals to ensure DMA is disabled - some of them may
401  * already be handled elsewhere in cases we consider normal termination.
402  * In those cases the teardown() method must be called.
403  */
404  for (int i = 0; i < NSIG; i++) {
405  sigaction(i, nullptr, &sa_old);
406 
407  if (sa_old.sa_handler == nullptr) {
408  sa.sa_handler = RCInput_RPI::termination_handler;
409  sigaction(i, &sa, nullptr);
410  }
411  }
412 }
413 
414 // Initial setup of variables
416  circle_buffer{nullptr},
417  con_blocks{nullptr},
418  prev_tick(0),
419  delta_time(0),
421  curr_pointer(0),
422  curr_channel(0),
423  width_s0(0),
424  curr_signal(0),
425  last_signal(228),
427 {
428 }
429 
431 {
432  delete circle_buffer;
433  delete con_blocks;
434 }
435 
437 {
438  stop_dma();
439 }
440 
441 //Initializing necessary registers
443 {
447 }
448 
450 {
451 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2
452  int version = 2;
453 #else
454  int version = UtilRPI::from(hal.util)->get_rpi_version();
455 #endif
456  set_physical_addresses(version);
458  con_blocks = new Memory_table(RCIN_RPI_BUFFER_LENGTH * 113, version);
459 
460  init_registers();
461 
462  // Enable PPM input
465 
466  // Configuration
467  set_sigaction();
468  init_ctrl_data();
469  init_PCM();
470  init_DMA();
471 
472  // Wait a bit to let DMA fill queues and come to stable sampling
473  hal.scheduler->delay(300);
474 
475  // Reading first sample
478  curr_pointer += 8;
479  curr_signal = *((uint8_t *)circle_buffer->get_page(circle_buffer->_virt_pages, curr_pointer)) & 0x10 ? 1 : 0;
481  curr_pointer++;
482 
483  _initialized = true;
484 }
485 
486 // Processing signal
488 {
489  uint32_t counter = 0;
490 
491  if (!_initialized) {
492  return;
493  }
494 
495  // Now we are getting address in which DMAC is writing at current moment
497  if (!ad) {
498  debug("DMA sampling stopped, restarting...\n");
499  init_ctrl_data();
500  init_PCM();
501  init_DMA();
502  return;
503  }
504 
505  for (int j = 1; j >= -1; j--) {
506  void *x = circle_buffer->get_virt_addr((ad + j)->dst);
507  if (x != nullptr) {
510  break;
511  }
512  }
513 
514  if (counter == 0) {
515  return;
516  }
517 
518  // How many bytes have DMA transferred (and we can process)?
519  // We can't stay in method for a long time, because it may lead to delays
520  if (counter > RCIN_RPI_MAX_COUNTER) {
521  debug("%5d sample(s) dropped\n", (counter - RCIN_RPI_MAX_COUNTER) / 0x8);
522  counter = RCIN_RPI_MAX_COUNTER;
523  }
524 
525  // Processing ready bytes
526  for (; counter > 0x40; counter--) {
527  // Is it timer sample?
528  if (curr_pointer % (64) == 0) {
530  curr_pointer += 8;
531  counter -= 8;
532  }
533 
534  // Reading required bit
535  curr_signal = *((uint8_t *)circle_buffer->get_page(circle_buffer->_virt_pages, curr_pointer)) & 0x10 ? 1 : 0;
536 
537  // If the signal changed
538  if (curr_signal != last_signal) {
540  prev_tick = curr_tick;
541  switch (state) {
544  break;
545  case RCIN_RPI_ZERO_STATE:
546  if (curr_signal == 0) {
547  width_s0 = (uint16_t)delta_time;
549  }
550  break;
551  case RCIN_RPI_ONE_STATE:
552  if (curr_signal == 1) {
553  width_s1 = (uint16_t)delta_time;
556  }
557  break;
558  }
559  }
560 
562  curr_pointer++;
564  curr_pointer = 0;
565  }
567  }
568 }
569 
570 #endif
#define PPM_INPUT_RPI
Definition: RCInput_RPI.cpp:40
int printf(const char *fmt,...)
Definition: stdio.c:113
static uint8_t counter
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
#define debug(fmt, args ...)
Definition: RCInput_RPI.cpp:31
#define RCIN_RPI_DMA_CHANNEL
Definition: RCInput_RPI.cpp:37
#define RCIN_RPI_RPI2_DMA_BASE
Definition: RCInput_RPI.cpp:54
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
#define RCIN_RPI_BUFFER_LENGTH
Definition: RCInput_RPI.cpp:35
#define RCIN_RPI_DMA_RESET
Definition: RCInput_RPI.cpp:71
void teardown() override
#define RCIN_RPI_DMA_SRC_INC
Definition: RCInput_RPI.cpp:64
#define RCIN_RPI_TIMER_BASE
Definition: RCInput_RPI.cpp:62
uint32_t get_page_count() const
#define RCIN_RPI_DMA_D_DREQ
Definition: RCInput_RPI.cpp:68
#define RCIN_RPI_DMA_NO_WIDE_BURSTS
Definition: RCInput_RPI.cpp:66
#define RCIN_RPI_DMA_INT
Definition: RCInput_RPI.cpp:72
void * get_virt_addr(const uint32_t phys_addr) const
#define RCIN_RPI_PCMCLK_DIV
Definition: RCInput_RPI.cpp:89
AP_HAL::Util * util
Definition: HAL.h:115
void * get_page(void **pages, const uint32_t addr) const
#define RCIN_RPI_PCMCLK_CNTL
Definition: RCInput_RPI.cpp:88
void set_physical_addresses(int version)
void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1)
Definition: RCInput.cpp:308
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define RCIN_RPI_DMA_PER_MAP(x)
Definition: RCInput_RPI.cpp:69
#define RCIN_RPI_DMA_CS
Definition: RCInput_RPI.cpp:74
#define PAGE_SIZE
Definition: osd_eeprom.h:13
static volatile uint32_t * clk_reg
Definition: RCInput_RPI.h:94
void * calloc(size_t nmemb, size_t size)
Definition: malloc.c:76
virtual void mode(uint8_t output)=0
void * map_peripheral(uint32_t base, uint32_t len)
virtual void delay(uint16_t ms)=0
#define RCIN_RPI_RPI2_PCM_BASE
Definition: RCInput_RPI.cpp:56
#define x(i)
#define RCIN_RPI_DMA_WAIT_RESP
Definition: RCInput_RPI.cpp:67
#define RCIN_RPI_DMA_END
Definition: RCInput_RPI.cpp:70
static void termination_handler(int signum)
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
#define RCIN_RPI_PCM_DREQ_A
Definition: RCInput_RPI.cpp:83
#define RCIN_RPI_PCM_TXC_A
Definition: RCInput_RPI.cpp:82
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
virtual AP_HAL::DigitalSource * channel(uint16_t n)=0
uint32_t get_offset(void **pages, const uint32_t addr) const
#define RCIN_RPI_GPIO_LEV0_ADDR
Definition: RCInput_RPI.cpp:58
uint32_t bytes_available(const uint32_t read_addr, const uint32_t write_addr) const
#define RCIN_RPI_DMA_DEBUG
Definition: RCInput_RPI.cpp:76
off_t lseek(int fileno, off_t position, int whence)
POSIX seek to file position.
Definition: posix.c:612
#define RCIN_RPI_RPI2_CLK_BASE
Definition: RCInput_RPI.cpp:55
#define HAL_GPIO_INPUT
Definition: GPIO.h:7
uint32_t _page_count
Definition: RCInput_RPI.h:54
void free(void *ptr)
Definition: malloc.c:81
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)
uint32_t curr_pointer
Definition: RCInput_RPI.h:105
#define RCIN_RPI_RPI1_CLK_BASE
Definition: RCInput_RPI.cpp:51
int get_rpi_version() const
Definition: Util_RPI.cpp:74
static UtilRPI * from(AP_HAL::Util *util)
Definition: Util_RPI.h:11
#define RCIN_RPI_DMA_DEST_INC
Definition: RCInput_RPI.cpp:65
#define RCIN_RPI_DMA_LEN
Definition: RCInput_RPI.cpp:59
#define RCIN_RPI_RPI1_DMA_BASE
Definition: RCInput_RPI.cpp:50
AP_HAL::GPIO * gpio
Definition: HAL.h:111
#define RCIN_RPI_RPI1_PCM_BASE
Definition: RCInput_RPI.cpp:52
static volatile uint32_t * dma_reg
Definition: RCInput_RPI.h:95
virtual void delay_microseconds(uint16_t us)=0
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
static void stop_dma()
Memory_table * con_blocks
Definition: RCInput_RPI.h:98
static volatile uint32_t * pcm_reg
Definition: RCInput_RPI.h:93
#define RCIN_RPI_PCM_CS_A
Definition: RCInput_RPI.cpp:78
#define RCIN_RPI_PCM_LEN
Definition: RCInput_RPI.cpp:61
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define RCIN_RPI_PCM_MODE_A
Definition: RCInput_RPI.cpp:80
void _timer_tick(void)
#define RCIN_RPI_DMA_CONBLK_AD
Definition: RCInput_RPI.cpp:75
#define RCIN_RPI_SAMPLE_FREQ
Definition: RCInput_RPI.cpp:36
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
#define RCIN_RPI_MAX_COUNTER
Definition: RCInput_RPI.cpp:38
#define RCIN_RPI_CLK_LEN
Definition: RCInput_RPI.cpp:60
uint32_t curr_channel
Definition: RCInput_RPI.h:106