RCInput_RPI.cpp 22 KB

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