#include #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI #include #include #include #include #include #include #include #include #include #include #include #include #include "GPIO.h" #include "RCInput.h" extern const AP_HAL::HAL& hal; using namespace Linux; void LinuxRCInput_PRU::init(void*) { int mem_fd = open("/dev/mem", O_RDWR|O_SYNC); if (mem_fd == -1) { hal.scheduler->panic("Unable to open /dev/mem"); } ring_buffer = (volatile struct ring_buffer*) mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCIN_PRUSS_SHAREDRAM_BASE); close(mem_fd); ring_buffer->ring_head = 0; _s0_time = 0; // enable the spektrum RC input power hal.gpio->pinMode(BBB_P8_17, HAL_GPIO_OUTPUT); hal.gpio->write(BBB_P8_17, 1); } /* called at 1kHz to check for new pulse capture data from the PRU */ void LinuxRCInput_PRU::_timer_tick() { while (ring_buffer->ring_head != ring_buffer->ring_tail) { if (ring_buffer->ring_tail >= NUM_RING_ENTRIES) { // invalid ring_tail from PRU - ignore RC input return; } if (ring_buffer->buffer[ring_buffer->ring_head].pin_value == 1) { // remember the time we spent in the low state _s0_time = ring_buffer->buffer[ring_buffer->ring_head].delta_t; } else { // the pulse value is the sum of the time spent in the low // and high states _process_rc_pulse(_s0_time, ring_buffer->buffer[ring_buffer->ring_head].delta_t); } // move to the next ring buffer entry ring_buffer->ring_head = (ring_buffer->ring_head + 1) % NUM_RING_ENTRIES; } } #endif // CONFIG_HAL_BOARD_SUBTYPE