APM:Libraries
RCOutput_AioPRU.h
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 #pragma once
12 
13 #include "AP_HAL_Linux.h"
14 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
15 #define RCOUT_PRUSS_RAM_BASE 0x4a300000
16 #define RCOUT_PRUSS_CTRL_BASE 0x4a322000
17 #define RCOUT_PRUSS_IRAM_BASE 0x4a334000
18 #else
19 #define RCOUT_PRUSS_RAM_BASE 0x4a302000
20 #define RCOUT_PRUSS_CTRL_BASE 0x4a324000
21 #define RCOUT_PRUSS_IRAM_BASE 0x4a338000
22 #endif
23 #define PWM_CHAN_COUNT 12
24 
25 namespace Linux {
26 
28  void init();
29  void set_freq(uint32_t chmask, uint16_t freq_hz);
30  uint16_t get_freq(uint8_t ch);
31  void enable_ch(uint8_t ch);
32  void disable_ch(uint8_t ch);
33  void write(uint8_t ch, uint16_t period_us);
34  uint16_t read(uint8_t ch);
35  void read(uint16_t* period_us, uint8_t len);
36  void cork(void) override;
37  void push(void) override;
38 
39 private:
40  static const uint32_t TICK_PER_US = 200;
41  static const uint32_t TICK_PER_S = 200000000;
42 
43  struct pwm {
44  volatile uint32_t channelenable;
45  struct {
46  volatile uint32_t time_high;
47  volatile uint32_t time_t;
49  };
50 
51  volatile struct pwm *pwm;
53  uint32_t pending_mask;
54  bool corked;
55 };
56 
57 }
void cork(void) override
uint16_t get_freq(uint8_t ch)
void disable_ch(uint8_t ch)
static const uint32_t TICK_PER_S
#define PWM_CHAN_COUNT
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]
void enable_ch(uint8_t ch)
volatile uint32_t time_high
uint16_t read(uint8_t ch)
volatile struct pwm * pwm
struct Linux::RCOutput_AioPRU::pwm::@100 channel[PWM_CHAN_COUNT]
volatile uint32_t channelenable
void set_freq(uint32_t chmask, uint16_t freq_hz)