APM:Libraries
RCInput_PRU.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_PXF || \
4  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD
5 #include "RCInput_PRU.h"
6 
7 #include <errno.h>
8 #include <fcntl.h>
9 #include <poll.h>
10 #include <stdint.h>
11 #include <stdio.h>
12 #include <stdlib.h>
13 #include <string.h>
14 #include <sys/mman.h>
15 #include <sys/stat.h>
16 #include <sys/time.h>
17 #include <unistd.h>
18 
19 #include "GPIO.h"
20 
21 #define RCIN_PRUSS_SHAREDRAM_BASE 0x4a312000
22 
23 extern const AP_HAL::HAL& hal;
24 
25 using namespace Linux;
26 
28 {
29  int mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
30  if (mem_fd == -1) {
31  AP_HAL::panic("Unable to open /dev/mem");
32  }
33  ring_buffer = (volatile struct ring_buffer*) mmap(0, 0x1000, PROT_READ|PROT_WRITE,
34  MAP_SHARED, mem_fd, RCIN_PRUSS_SHAREDRAM_BASE);
35  close(mem_fd);
37  _s0_time = 0;
38 
39  // enable the spektrum RC input power
41  hal.gpio->write(BBB_P8_17, 1);
42 }
43 
44 /*
45  called at 1kHz to check for new pulse capture data from the PRU
46  */
48 {
51  // invalid ring_tail from PRU - ignore RC input
52  return;
53  }
55  // remember the time we spent in the low state
57  } else {
58  // the pulse value is the sum of the time spent in the low
59  // and high states
61  }
62  // move to the next ring buffer entry
64  }
65 }
66 
67 #endif // CONFIG_HAL_BOARD_SUBTYPE
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
static const unsigned int NUM_RING_ENTRIES
Definition: RCInput_PRU.h:21
void _timer_tick(void)
Definition: RCInput_PRU.cpp:47
volatile uint16_t ring_head
Definition: RCInput_PRU.h:24
void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1)
Definition: RCInput.cpp:308
virtual void write(uint8_t pin, uint8_t value)=0
#define RCIN_PRUSS_SHAREDRAM_BASE
Definition: RCInput_PRU.cpp:21
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
virtual void pinMode(uint8_t pin, uint8_t output)=0
#define HAL_GPIO_OUTPUT
Definition: GPIO.h:8
volatile uint16_t ring_tail
Definition: RCInput_PRU.h:25
AP_HAL::GPIO * gpio
Definition: HAL.h:111
struct Linux::RCInput_PRU::ring_buffer::@99 buffer[NUM_RING_ENTRIES]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define BBB_P8_17
Definition: GPIO_BBB.h:56