2016-07-29 16:14:02 -03:00
|
|
|
#include "RCInput_ZYNQ.h"
|
|
|
|
|
2014-11-13 23:10:35 -04:00
|
|
|
#include <errno.h>
|
|
|
|
#include <fcntl.h>
|
|
|
|
#include <poll.h>
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <stdint.h>
|
|
|
|
#include <stdio.h>
|
|
|
|
#include <stdlib.h>
|
|
|
|
#include <string.h>
|
2014-11-13 23:10:35 -04:00
|
|
|
#include <sys/mman.h>
|
|
|
|
#include <sys/stat.h>
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <sys/time.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2014-11-13 23:10:35 -04:00
|
|
|
|
|
|
|
#include "GPIO.h"
|
|
|
|
|
2016-07-29 20:26:07 -03:00
|
|
|
#define RCIN_ZYNQ_PULSE_INPUT_BASE 0x43c10000
|
|
|
|
|
2014-11-13 23:10:35 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
using namespace Linux;
|
|
|
|
|
2015-12-02 11:14:20 -04:00
|
|
|
void RCInput_ZYNQ::init()
|
2014-11-13 23:10:35 -04:00
|
|
|
{
|
2016-10-30 10:22:29 -03:00
|
|
|
int mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
|
2014-11-13 23:10:35 -04:00
|
|
|
if (mem_fd == -1) {
|
2015-11-19 23:10:58 -04:00
|
|
|
AP_HAL::panic("Unable to open /dev/mem");
|
2014-11-13 23:10:35 -04:00
|
|
|
}
|
2016-05-17 23:26:57 -03:00
|
|
|
pulse_input = (volatile uint32_t*) mmap(0, 0x1000, PROT_READ|PROT_WRITE,
|
2014-11-13 23:10:35 -04:00
|
|
|
MAP_SHARED, mem_fd, RCIN_ZYNQ_PULSE_INPUT_BASE);
|
|
|
|
close(mem_fd);
|
|
|
|
|
|
|
|
_s0_time = 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
called at 1kHz to check for new pulse capture data from the PL pulse timer
|
|
|
|
*/
|
2015-10-20 18:13:25 -03:00
|
|
|
void RCInput_ZYNQ::_timer_tick()
|
2014-11-13 23:10:35 -04:00
|
|
|
{
|
|
|
|
uint32_t v;
|
|
|
|
|
|
|
|
// all F's means no samples available
|
|
|
|
while((v = *pulse_input) != 0xffffffff) {
|
|
|
|
// Hi bit indicates pin state, low bits denote pulse length
|
|
|
|
if(!(v & 0x80000000))
|
|
|
|
_s0_time = (v & 0x7fffffff)/TICK_PER_US;
|
|
|
|
else
|
|
|
|
_process_rc_pulse(_s0_time, (v & 0x7fffffff)/TICK_PER_US);
|
|
|
|
}
|
|
|
|
}
|