#include #include "RCOutput_ZYNQ.h" #include #include #include #include #include #include #include #include #include #include #include #include using namespace Linux; #define PWM_CHAN_COUNT 8 // FIXME static void catch_sigbus(int sig) { AP_HAL::panic("RCOutput.cpp:SIGBUS error gernerated\n"); } void RCOutput_ZYNQ::init() { uint32_t mem_fd; signal(SIGBUS,catch_sigbus); mem_fd = open("/dev/mem", O_RDWR|O_SYNC); sharedMem_cmd = (struct pwm_cmd *) mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_ZYNQ_PWM_BASE); close(mem_fd); // all outputs default to 50Hz, the top level vehicle code // overrides this when necessary set_freq(0xFFFFFFFF, 50); } void RCOutput_ZYNQ::set_freq(uint32_t chmask, uint16_t freq_hz) //LSB corresponds to CHAN_1 { uint8_t i; unsigned long tick=TICK_PER_S/(unsigned long)freq_hz; for (i=0;iperiodhi[i].period=tick; } } } uint16_t RCOutput_ZYNQ::get_freq(uint8_t ch) { return TICK_PER_S/sharedMem_cmd->periodhi[ch].period;; } void RCOutput_ZYNQ::enable_ch(uint8_t ch) { // sharedMem_cmd->enmask |= 1U<enmask &= !(1U<periodhi[ch].hi = TICK_PER_US*period_us; } uint16_t RCOutput_ZYNQ::read(uint8_t ch) { return (sharedMem_cmd->periodhi[ch].hi/TICK_PER_US); } void RCOutput_ZYNQ::read(uint16_t* period_us, uint8_t len) { uint8_t i; if(len>PWM_CHAN_COUNT){ len = PWM_CHAN_COUNT; } for(i=0;iperiodhi[i].hi/TICK_PER_US; } }