2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2014-08-19 00:37:10 -03:00
|
|
|
|
2014-10-26 16:18:04 -03:00
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \
|
2015-09-06 18:35:13 -03:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD || \
|
2015-01-10 19:20:38 -04:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
|
|
|
|
|
2014-08-19 00:37:10 -03:00
|
|
|
#include <stdio.h>
|
|
|
|
#include <sys/time.h>
|
|
|
|
#include <stdio.h>
|
|
|
|
#include <stdlib.h>
|
|
|
|
#include <string.h>
|
|
|
|
#include <errno.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
#include <fcntl.h>
|
|
|
|
#include <poll.h>
|
|
|
|
#include <sys/mman.h>
|
|
|
|
#include <sys/stat.h>
|
|
|
|
#include <stdint.h>
|
|
|
|
|
2014-10-07 22:48:46 -03:00
|
|
|
#include "GPIO.h"
|
2014-08-19 00:37:10 -03:00
|
|
|
#include "RCInput.h"
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
using namespace Linux;
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void RCInput_PRU::init(void*)
|
2014-08-19 00:37:10 -03:00
|
|
|
{
|
|
|
|
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;
|
2014-10-07 22:48:46 -03:00
|
|
|
|
|
|
|
// enable the spektrum RC input power
|
|
|
|
hal.gpio->pinMode(BBB_P8_17, HAL_GPIO_OUTPUT);
|
|
|
|
hal.gpio->write(BBB_P8_17, 1);
|
2014-08-19 00:37:10 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
called at 1kHz to check for new pulse capture data from the PRU
|
|
|
|
*/
|
2015-10-20 18:13:25 -03:00
|
|
|
void RCInput_PRU::_timer_tick()
|
2014-08-19 00:37:10 -03:00
|
|
|
{
|
|
|
|
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
|
2014-10-06 23:24:23 -03:00
|
|
|
_process_rc_pulse(_s0_time, ring_buffer->buffer[ring_buffer->ring_head].delta_t);
|
2014-08-19 00:37:10 -03:00
|
|
|
}
|
|
|
|
// move to the next ring buffer entry
|
|
|
|
ring_buffer->ring_head = (ring_buffer->ring_head + 1) % NUM_RING_ENTRIES;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-10-26 16:18:04 -03:00
|
|
|
#endif // CONFIG_HAL_BOARD_SUBTYPE
|