APM:Libraries
RCOutput_AioPRU.cpp
Go to the documentation of this file.
1 // This program is free software: you can redistribute it and/or modify
2 // it under the terms of the GNU General Public License as published by
3 // the Free Software Foundation, either version 3 of the License, or
4 // (at your option) any later version.
5 // This program is distributed in the hope that it will be useful,
6 // but WITHOUT ANY WARRANTY; without even the implied warranty of
7 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
8 // GNU General Public License for more details.
9 // You should have received a copy of the GNU General Public License
10 // along with this program. If not, see <http://www.gnu.org/licenses/>.
11 #include "RCOutput_AioPRU.h"
12 
13 #include <fcntl.h>
14 #include <signal.h>
15 #include <stdint.h>
16 #include <stdio.h>
17 #include <stdlib.h>
18 #include <sys/mman.h>
19 #include <unistd.h>
20 
21 #include <AP_HAL/AP_HAL.h>
22 
23 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE
24 #include "../../Tools/Linux_HAL_Essentials/pru/aiopru/RcAioPRU_BBBLUE_bin.h"
25 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
26 #include "../../Tools/Linux_HAL_Essentials/pru/aiopru/RcAioPRU_POCKET_bin.h"
27 #else
28 #include "../../Tools/Linux_HAL_Essentials/pru/aiopru/RcAioPRU_BBBMINI_bin.h"
29 #endif
30 
31 using namespace Linux;
32 
33 static void catch_sigbus(int sig)
34 {
35  AP_HAL::panic("RCOutputAioPRU.cpp:SIGBUS error gernerated\n");
36 }
38 {
39  uint32_t mem_fd;
40  uint32_t *iram;
41  uint32_t *ctrl;
42 
43  signal(SIGBUS,catch_sigbus);
44 
45  mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
46 
47  pwm = (struct pwm*) mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_PRUSS_RAM_BASE);
48  iram = (uint32_t*)mmap(0, 0x2000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_PRUSS_IRAM_BASE);
49  ctrl = (uint32_t*)mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_PRUSS_CTRL_BASE);
50 
51  close(mem_fd);
52 
53  // Reset PRU
54  *ctrl = 0;
55 
56  // Load firmware
57  memcpy(iram, PRUcode, sizeof(PRUcode));
58 
59  // Start PRU
60  *ctrl |= 2;
61 
62  // all outputs default to 50Hz, the top level vehicle code
63  // overrides this when necessary
64  set_freq(0xFFFFFFFF, 50);
65 }
66 
67 void RCOutput_AioPRU::set_freq(uint32_t chmask, uint16_t freq_hz)
68 {
69  uint8_t i;
70  uint32_t tick = TICK_PER_S / freq_hz;
71 
72  for(i = 0; i < PWM_CHAN_COUNT; i++) {
73  if(chmask & (1U << i)) {
74  pwm->channel[i].time_t = tick;
75  }
76  }
77 }
78 
79 uint16_t RCOutput_AioPRU::get_freq(uint8_t ch)
80 {
81  uint16_t ret = 0;
82 
83  if(ch < PWM_CHAN_COUNT) {
84  ret = TICK_PER_S / pwm->channel[ch].time_t;
85  }
86 
87  return ret;
88 }
89 
91 {
92  if(ch < PWM_CHAN_COUNT) {
93  pwm->channelenable |= 1U << ch;
94  }
95 }
96 
98 {
99  if(ch < PWM_CHAN_COUNT) {
100  pwm->channelenable &= !(1U << ch);
101  }
102 }
103 
104 void RCOutput_AioPRU::write(uint8_t ch, uint16_t period_us)
105 {
106  if(ch < PWM_CHAN_COUNT) {
107  if (corked) {
108  pending_mask |= (1U << ch);
109  pending[ch] = period_us;
110  } else {
111  pwm->channel[ch].time_high = TICK_PER_US * period_us;
112  }
113  }
114 }
115 
116 uint16_t RCOutput_AioPRU::read(uint8_t ch)
117 {
118  uint16_t ret = 0;
119 
120  if(ch < PWM_CHAN_COUNT) {
121  ret = (pwm->channel[ch].time_high / TICK_PER_US);
122  }
123 
124  return ret;
125 }
126 
127 void RCOutput_AioPRU::read(uint16_t* period_us, uint8_t len)
128 {
129  uint8_t i;
130 
131  if(len > PWM_CHAN_COUNT) {
132  len = PWM_CHAN_COUNT;
133  }
134 
135  for(i = 0; i < len; i++) {
136  period_us[i] = pwm->channel[i].time_high / TICK_PER_US;
137  }
138 }
139 
141 {
142  corked = true;
143 }
144 
146 {
147  if (!corked) {
148  return;
149  }
150  corked = false;
151  for (uint8_t i=0; i<PWM_CHAN_COUNT; i++) {
152  if (pending_mask & (1U<<i)) {
153  write(i, pending[i]);
154  }
155  }
156  pending_mask = 0;
157 }
#define RCOUT_PRUSS_CTRL_BASE
void cork(void) override
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
#define PWM_CHAN_COUNT
#define RCOUT_PRUSS_IRAM_BASE
uint16_t get_freq(uint8_t ch)
void disable_ch(uint8_t ch)
static void catch_sigbus(int sig)
static const uint32_t TICK_PER_S
static const uint32_t TICK_PER_US
void push(void) override
void write(uint8_t ch, uint16_t period_us)
uint16_t pending[PWM_CHAN_COUNT]
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
void enable_ch(uint8_t ch)
volatile uint32_t time_high
uint16_t read(uint8_t ch)
struct Linux::RCOutput_AioPRU::pwm::@100 channel[PWM_CHAN_COUNT]
volatile uint32_t channelenable
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define RCOUT_PRUSS_RAM_BASE
void set_freq(uint32_t chmask, uint16_t freq_hz)