ardupilot/libraries/AP_HAL_Linux/RCInput_ZYNQ.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

58 lines
1.3 KiB
C++
Raw Normal View History

#include "RCInput_ZYNQ.h"
2014-11-13 23:10:35 -04:00
#include <errno.h>
#include <fcntl.h>
#include <poll.h>
#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>
#include <sys/time.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
2014-11-13 23:10:35 -04:00
#include "GPIO.h"
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OCPOC_ZYNQ
#define RCIN_ZYNQ_PULSE_INPUT_BASE 0x43ca0000
#else
#define RCIN_ZYNQ_PULSE_INPUT_BASE 0x43c10000
#endif
2014-11-13 23:10:35 -04:00
extern const AP_HAL::HAL& hal;
using namespace Linux;
void RCInput_ZYNQ::init()
2014-11-13 23:10:35 -04: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) {
AP_HAL::panic("Unable to open /dev/mem");
2014-11-13 23:10:35 -04: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
*/
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)
2014-11-13 23:10:35 -04:00
_s0_time = (v & 0x7fffffff)/TICK_PER_US;
else
_process_rc_pulse(_s0_time, (v & 0x7fffffff)/TICK_PER_US);
}
}