APM:Libraries
RCOutput_PRU.cpp
Go to the documentation of this file.
1 #include "RCOutput_PRU.h"
2 
3 #include <dirent.h>
4 #include <fcntl.h>
5 #include <linux/spi/spidev.h>
6 #include <signal.h>
7 #include <stdint.h>
8 #include <stdio.h>
9 #include <stdlib.h>
10 #include <sys/ioctl.h>
11 #include <sys/mman.h>
12 #include <sys/stat.h>
13 #include <sys/types.h>
14 #include <unistd.h>
15 
16 #include <AP_HAL/AP_HAL.h>
17 
18 using namespace Linux;
19 
20 #define PWM_CHAN_COUNT 12
21 
22 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;
23 
24 static void catch_sigbus(int sig)
25 {
26  AP_HAL::panic("RCOutput.cpp:SIGBUS error gernerated\n");
27 }
29 {
30  uint32_t mem_fd;
31  signal(SIGBUS,catch_sigbus);
32  mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
33  sharedMem_cmd = (struct pwm_cmd *) mmap(0, 0x1000, PROT_READ|PROT_WRITE,
34  MAP_SHARED, mem_fd, RCOUT_PRUSS_SHAREDRAM_BASE);
35  close(mem_fd);
36 
37  // all outputs default to 50Hz, the top level vehicle code
38  // overrides this when necessary
39  set_freq(0xFFFFFFFF, 50);
40 }
41 
42 void RCOutput_PRU::set_freq(uint32_t chmask, uint16_t freq_hz) //LSB corresponds to CHAN_1
43 {
44  uint8_t i;
45  unsigned long tick=TICK_PER_S/(unsigned long)freq_hz;
46 
47  for (i=0;i<PWM_CHAN_COUNT;i++) {
48  if (chmask & (1U<<i)) {
49  sharedMem_cmd->periodhi[chan_pru_map[i]][0]=tick;
50  }
51  }
52 }
53 
54 uint16_t RCOutput_PRU::get_freq(uint8_t ch)
55 {
57 }
58 
59 void RCOutput_PRU::enable_ch(uint8_t ch)
60 {
61  sharedMem_cmd->enmask |= 1U<<chan_pru_map[ch];
62 }
63 
64 void RCOutput_PRU::disable_ch(uint8_t ch)
65 {
66  sharedMem_cmd->enmask &= !(1U<<chan_pru_map[ch]);
67 }
68 
69 void RCOutput_PRU::write(uint8_t ch, uint16_t period_us)
70 {
71  if (corked) {
72  pending[ch] = period_us;
73  pending_mask |= (1U << ch);
74  } else {
75  sharedMem_cmd->periodhi[chan_pru_map[ch]][1] = TICK_PER_US*period_us;
76  }
77 }
78 
79 uint16_t RCOutput_PRU::read(uint8_t ch)
80 {
82 }
83 
84 void RCOutput_PRU::read(uint16_t* period_us, uint8_t len)
85 {
86  uint8_t i;
87  if(len>PWM_CHAN_COUNT){
88  len = PWM_CHAN_COUNT;
89  }
90  for(i=0;i<len;i++){
91  period_us[i] = sharedMem_cmd->hilo_read[chan_pru_map[i]][1]/TICK_PER_US;
92  }
93 }
94 
96 {
97  corked = true;
98 }
99 
101 {
102  if (!corked) {
103  return;
104  }
105  corked = false;
106  for (uint8_t i=0; i<ARRAY_SIZE(pending); i++) {
107  if (pending_mask & (1U << i)) {
108  write(i, pending[i]);
109  }
110  }
111  pending_mask = 0;
112 }
uint16_t read(uint8_t ch)
void push(void) override
uint32_t periodhi[MAX_PWMS][2]
Definition: RCOutput_PRU.h:37
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
void enable_ch(uint8_t ch)
void set_freq(uint32_t chmask, uint16_t freq_hz)
static const int TICK_PER_S
Definition: RCOutput_PRU.h:32
#define RCOUT_PRUSS_SHAREDRAM_BASE
Definition: RCOutput_PRU.h:4
uint32_t hilo_read[MAX_PWMS][2]
Definition: RCOutput_PRU.h:38
uint16_t pending[MAX_PWMS]
Definition: RCOutput_PRU.h:43
void disable_ch(uint8_t ch)
static void catch_sigbus(int sig)
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
void cork(void) override
static const int TICK_PER_US
Definition: RCOutput_PRU.h:31
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
#define PWM_CHAN_COUNT
uint16_t get_freq(uint8_t ch)
void write(uint8_t ch, uint16_t period_us)
volatile struct pwm_cmd * sharedMem_cmd
Definition: RCOutput_PRU.h:41
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
static const uint8_t chan_pru_map[]