2014-08-19 00:48:56 -03:00
|
|
|
#include "RCOutput_PRU.h"
|
2016-05-17 23:26:57 -03:00
|
|
|
|
2014-05-13 15:31:36 -03:00
|
|
|
#include <dirent.h>
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <fcntl.h>
|
|
|
|
#include <linux/spi/spidev.h>
|
|
|
|
#include <signal.h>
|
2014-05-13 15:31:36 -03:00
|
|
|
#include <stdint.h>
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <stdio.h>
|
|
|
|
#include <stdlib.h>
|
2014-05-13 15:31:36 -03:00
|
|
|
#include <sys/ioctl.h>
|
2014-06-09 09:25:15 -03:00
|
|
|
#include <sys/mman.h>
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <sys/stat.h>
|
|
|
|
#include <sys/types.h>
|
|
|
|
#include <unistd.h>
|
2014-05-13 07:22:17 -03:00
|
|
|
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
|
|
|
using namespace Linux;
|
2014-06-09 09:25:15 -03:00
|
|
|
|
2014-05-13 07:22:17 -03:00
|
|
|
#define PWM_CHAN_COUNT 12
|
|
|
|
|
2014-07-07 23:58:14 -03:00
|
|
|
static const uint8_t chan_pru_map[]= {10,8,11,9,7,6,5,4,3,2,1,0}; //chan_pru_map[CHANNEL_NUM] = PRU_REG_R30/31_NUM;
|
2014-05-13 07:22:17 -03:00
|
|
|
|
2014-07-08 00:21:26 -03:00
|
|
|
static void catch_sigbus(int sig)
|
|
|
|
{
|
2018-08-01 05:58:23 -03:00
|
|
|
AP_HAL::panic("RCOutput.cpp:SIGBUS error generated\n");
|
2014-07-08 00:21:26 -03:00
|
|
|
}
|
2015-12-02 11:14:20 -04:00
|
|
|
void RCOutput_PRU::init()
|
2014-05-13 07:22:17 -03:00
|
|
|
{
|
2014-07-07 23:58:14 -03:00
|
|
|
uint32_t mem_fd;
|
2014-07-08 00:21:26 -03:00
|
|
|
signal(SIGBUS,catch_sigbus);
|
2016-10-30 10:22:29 -03:00
|
|
|
mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
|
2016-05-17 23:26:57 -03:00
|
|
|
sharedMem_cmd = (struct pwm_cmd *) mmap(0, 0x1000, PROT_READ|PROT_WRITE,
|
2014-08-17 23:35:22 -03:00
|
|
|
MAP_SHARED, mem_fd, RCOUT_PRUSS_SHAREDRAM_BASE);
|
2014-06-09 09:25:15 -03:00
|
|
|
close(mem_fd);
|
2014-08-18 00:02:50 -03:00
|
|
|
|
|
|
|
// all outputs default to 50Hz, the top level vehicle code
|
|
|
|
// overrides this when necessary
|
|
|
|
set_freq(0xFFFFFFFF, 50);
|
2014-05-13 07:22:17 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void RCOutput_PRU::set_freq(uint32_t chmask, uint16_t freq_hz) //LSB corresponds to CHAN_1
|
2014-05-13 07:22:17 -03:00
|
|
|
{
|
2014-07-08 00:21:26 -03:00
|
|
|
uint8_t i;
|
2014-06-27 03:01:59 -03:00
|
|
|
unsigned long tick=TICK_PER_S/(unsigned long)freq_hz;
|
2014-08-18 00:02:50 -03:00
|
|
|
|
|
|
|
for (i=0;i<PWM_CHAN_COUNT;i++) {
|
|
|
|
if (chmask & (1U<<i)) {
|
2014-06-27 03:01:59 -03:00
|
|
|
sharedMem_cmd->periodhi[chan_pru_map[i]][0]=tick;
|
2014-05-13 08:21:07 -03:00
|
|
|
}
|
|
|
|
}
|
2014-05-13 07:22:17 -03:00
|
|
|
}
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
uint16_t RCOutput_PRU::get_freq(uint8_t ch)
|
2014-05-13 07:22:17 -03:00
|
|
|
{
|
2014-06-27 03:01:59 -03:00
|
|
|
return TICK_PER_S/sharedMem_cmd->periodhi[chan_pru_map[ch]][0];
|
2013-09-22 03:01:24 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void RCOutput_PRU::enable_ch(uint8_t ch)
|
2014-05-13 07:22:17 -03:00
|
|
|
{
|
2014-07-08 00:21:26 -03:00
|
|
|
sharedMem_cmd->enmask |= 1U<<chan_pru_map[ch];
|
2014-05-13 07:22:17 -03:00
|
|
|
}
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void RCOutput_PRU::disable_ch(uint8_t ch)
|
2014-05-13 07:22:17 -03:00
|
|
|
{
|
2014-07-08 00:21:26 -03:00
|
|
|
sharedMem_cmd->enmask &= !(1U<<chan_pru_map[ch]);
|
2014-05-13 07:22:17 -03:00
|
|
|
}
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void RCOutput_PRU::write(uint8_t ch, uint16_t period_us)
|
2014-05-13 07:22:17 -03:00
|
|
|
{
|
2016-10-11 21:19:16 -03:00
|
|
|
if (corked) {
|
|
|
|
pending[ch] = period_us;
|
|
|
|
pending_mask |= (1U << ch);
|
|
|
|
} else {
|
|
|
|
sharedMem_cmd->periodhi[chan_pru_map[ch]][1] = TICK_PER_US*period_us;
|
|
|
|
}
|
2014-05-13 07:22:17 -03:00
|
|
|
}
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
uint16_t RCOutput_PRU::read(uint8_t ch)
|
2014-06-09 09:25:15 -03:00
|
|
|
{
|
2014-07-07 23:58:14 -03:00
|
|
|
return (sharedMem_cmd->hilo_read[chan_pru_map[ch]][1]/TICK_PER_US);
|
2013-09-22 03:01:24 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void RCOutput_PRU::read(uint16_t* period_us, uint8_t len)
|
2014-05-13 07:22:17 -03:00
|
|
|
{
|
2014-07-07 23:58:14 -03:00
|
|
|
uint8_t i;
|
2014-07-08 00:21:26 -03:00
|
|
|
if(len>PWM_CHAN_COUNT){
|
|
|
|
len = PWM_CHAN_COUNT;
|
|
|
|
}
|
2014-05-13 08:21:07 -03:00
|
|
|
for(i=0;i<len;i++){
|
2014-07-07 23:58:14 -03:00
|
|
|
period_us[i] = sharedMem_cmd->hilo_read[chan_pru_map[i]][1]/TICK_PER_US;
|
2014-05-13 08:21:07 -03:00
|
|
|
}
|
2014-05-13 07:22:17 -03:00
|
|
|
}
|
2016-10-11 21:19:16 -03:00
|
|
|
|
|
|
|
void RCOutput_PRU::cork(void)
|
|
|
|
{
|
|
|
|
corked = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
void RCOutput_PRU::push(void)
|
|
|
|
{
|
2017-04-17 21:01:54 -03:00
|
|
|
if (!corked) {
|
|
|
|
return;
|
|
|
|
}
|
2016-10-11 21:19:16 -03:00
|
|
|
corked = false;
|
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(pending); i++) {
|
|
|
|
if (pending_mask & (1U << i)) {
|
|
|
|
write(i, pending[i]);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
pending_mask = 0;
|
|
|
|
}
|