AP_HAL_Linux: Add RCInput_RPI, merge common code
This commit is contained in:
parent
112df0a0a6
commit
47d43c64ef
@ -1,8 +1,8 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2
|
||||
#include "GPIO.h"
|
||||
#include "RCInput_Navio.h"
|
||||
#include "RCInput_RPI.h"
|
||||
#include "Util_RPI.h"
|
||||
|
||||
#include <stdio.h>
|
||||
@ -24,54 +24,54 @@
|
||||
|
||||
|
||||
//Parametres
|
||||
#define RCIN_NAVIO_BUFFER_LENGTH 8
|
||||
#define RCIN_NAVIO_SAMPLE_FREQ 500
|
||||
#define RCIN_NAVIO_DMA_CHANNEL 0
|
||||
#define RCIN_NAVIO_MAX_COUNTER 1300
|
||||
#define PPM_INPUT_NAVIO RPI_GPIO_4
|
||||
#define RCIN_NAVIO_MAX_SIZE_LINE 50
|
||||
#define RCIN_RPI_BUFFER_LENGTH 8
|
||||
#define RCIN_RPI_SAMPLE_FREQ 500
|
||||
#define RCIN_RPI_DMA_CHANNEL 0
|
||||
#define RCIN_RPI_MAX_COUNTER 1300
|
||||
#define PPM_INPUT_RPI RPI_GPIO_4
|
||||
#define RCIN_RPI_MAX_SIZE_LINE 50
|
||||
|
||||
//Memory Addresses
|
||||
#define RCIN_NAVIO_RPI1_DMA_BASE 0x20007000
|
||||
#define RCIN_NAVIO_RPI1_CLK_BASE 0x20101000
|
||||
#define RCIN_NAVIO_RPI1_PCM_BASE 0x20203000
|
||||
#define RCIN_RPI_RPI1_DMA_BASE 0x20007000
|
||||
#define RCIN_RPI_RPI1_CLK_BASE 0x20101000
|
||||
#define RCIN_RPI_RPI1_PCM_BASE 0x20203000
|
||||
|
||||
#define RCIN_NAVIO_RPI2_DMA_BASE 0x3F007000
|
||||
#define RCIN_NAVIO_RPI2_CLK_BASE 0x3F101000
|
||||
#define RCIN_NAVIO_RPI2_PCM_BASE 0x3F203000
|
||||
#define RCIN_RPI_RPI2_DMA_BASE 0x3F007000
|
||||
#define RCIN_RPI_RPI2_CLK_BASE 0x3F101000
|
||||
#define RCIN_RPI_RPI2_PCM_BASE 0x3F203000
|
||||
|
||||
#define RCIN_NAVIO_GPIO_LEV0_ADDR 0x7e200034
|
||||
#define RCIN_NAVIO_DMA_LEN 0x1000
|
||||
#define RCIN_NAVIO_CLK_LEN 0xA8
|
||||
#define RCIN_NAVIO_PCM_LEN 0x24
|
||||
#define RCIN_NAVIO_TIMER_BASE 0x7e003004
|
||||
#define RCIN_RPI_GPIO_LEV0_ADDR 0x7e200034
|
||||
#define RCIN_RPI_DMA_LEN 0x1000
|
||||
#define RCIN_RPI_CLK_LEN 0xA8
|
||||
#define RCIN_RPI_PCM_LEN 0x24
|
||||
#define RCIN_RPI_TIMER_BASE 0x7e003004
|
||||
|
||||
#define RCIN_NAVIO_DMA_SRC_INC (1<<8)
|
||||
#define RCIN_NAVIO_DMA_DEST_INC (1<<4)
|
||||
#define RCIN_NAVIO_DMA_NO_WIDE_BURSTS (1<<26)
|
||||
#define RCIN_NAVIO_DMA_WAIT_RESP (1<<3)
|
||||
#define RCIN_NAVIO_DMA_D_DREQ (1<<6)
|
||||
#define RCIN_NAVIO_DMA_PER_MAP(x) ((x)<<16)
|
||||
#define RCIN_NAVIO_DMA_END (1<<1)
|
||||
#define RCIN_NAVIO_DMA_RESET (1<<31)
|
||||
#define RCIN_NAVIO_DMA_INT (1<<2)
|
||||
#define RCIN_RPI_DMA_SRC_INC (1<<8)
|
||||
#define RCIN_RPI_DMA_DEST_INC (1<<4)
|
||||
#define RCIN_RPI_DMA_NO_WIDE_BURSTS (1<<26)
|
||||
#define RCIN_RPI_DMA_WAIT_RESP (1<<3)
|
||||
#define RCIN_RPI_DMA_D_DREQ (1<<6)
|
||||
#define RCIN_RPI_DMA_PER_MAP(x) ((x)<<16)
|
||||
#define RCIN_RPI_DMA_END (1<<1)
|
||||
#define RCIN_RPI_DMA_RESET (1<<31)
|
||||
#define RCIN_RPI_DMA_INT (1<<2)
|
||||
|
||||
#define RCIN_NAVIO_DMA_CS (0x00/4)
|
||||
#define RCIN_NAVIO_DMA_CONBLK_AD (0x04/4)
|
||||
#define RCIN_NAVIO_DMA_DEBUG (0x20/4)
|
||||
#define RCIN_RPI_DMA_CS (0x00/4)
|
||||
#define RCIN_RPI_DMA_CONBLK_AD (0x04/4)
|
||||
#define RCIN_RPI_DMA_DEBUG (0x20/4)
|
||||
|
||||
#define RCIN_NAVIO_PCM_CS_A (0x00/4)
|
||||
#define RCIN_NAVIO_PCM_FIFO_A (0x04/4)
|
||||
#define RCIN_NAVIO_PCM_MODE_A (0x08/4)
|
||||
#define RCIN_NAVIO_PCM_RXC_A (0x0c/4)
|
||||
#define RCIN_NAVIO_PCM_TXC_A (0x10/4)
|
||||
#define RCIN_NAVIO_PCM_DREQ_A (0x14/4)
|
||||
#define RCIN_NAVIO_PCM_INTEN_A (0x18/4)
|
||||
#define RCIN_NAVIO_PCM_INT_STC_A (0x1c/4)
|
||||
#define RCIN_NAVIO_PCM_GRAY (0x20/4)
|
||||
#define RCIN_RPI_PCM_CS_A (0x00/4)
|
||||
#define RCIN_RPI_PCM_FIFO_A (0x04/4)
|
||||
#define RCIN_RPI_PCM_MODE_A (0x08/4)
|
||||
#define RCIN_RPI_PCM_RXC_A (0x0c/4)
|
||||
#define RCIN_RPI_PCM_TXC_A (0x10/4)
|
||||
#define RCIN_RPI_PCM_DREQ_A (0x14/4)
|
||||
#define RCIN_RPI_PCM_INTEN_A (0x18/4)
|
||||
#define RCIN_RPI_PCM_INT_STC_A (0x1c/4)
|
||||
#define RCIN_RPI_PCM_GRAY (0x20/4)
|
||||
|
||||
#define RCIN_NAVIO_PCMCLK_CNTL 38
|
||||
#define RCIN_NAVIO_PCMCLK_DIV 39
|
||||
#define RCIN_RPI_PCMCLK_CNTL 38
|
||||
#define RCIN_RPI_PCMCLK_DIV 39
|
||||
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
@ -79,9 +79,9 @@ extern const AP_HAL::HAL& hal;
|
||||
using namespace Linux;
|
||||
|
||||
|
||||
volatile uint32_t *RCInput_Navio::pcm_reg;
|
||||
volatile uint32_t *RCInput_Navio::clk_reg;
|
||||
volatile uint32_t *RCInput_Navio::dma_reg;
|
||||
volatile uint32_t *RCInput_RPI::pcm_reg;
|
||||
volatile uint32_t *RCInput_RPI::clk_reg;
|
||||
volatile uint32_t *RCInput_RPI::dma_reg;
|
||||
|
||||
Memory_table::Memory_table()
|
||||
{
|
||||
@ -192,22 +192,22 @@ uint32_t Memory_table::get_page_count() const
|
||||
}
|
||||
|
||||
//Physical addresses of peripheral depends on Raspberry Pi's version
|
||||
void RCInput_Navio::set_physical_addresses(int version)
|
||||
void RCInput_RPI::set_physical_addresses(int version)
|
||||
{
|
||||
if (version == 1) {
|
||||
dma_base = RCIN_NAVIO_RPI1_DMA_BASE;
|
||||
clk_base = RCIN_NAVIO_RPI1_CLK_BASE;
|
||||
pcm_base = RCIN_NAVIO_RPI1_PCM_BASE;
|
||||
dma_base = RCIN_RPI_RPI1_DMA_BASE;
|
||||
clk_base = RCIN_RPI_RPI1_CLK_BASE;
|
||||
pcm_base = RCIN_RPI_RPI1_PCM_BASE;
|
||||
}
|
||||
else if (version == 2) {
|
||||
dma_base = RCIN_NAVIO_RPI2_DMA_BASE;
|
||||
clk_base = RCIN_NAVIO_RPI2_CLK_BASE;
|
||||
pcm_base = RCIN_NAVIO_RPI2_PCM_BASE;
|
||||
dma_base = RCIN_RPI_RPI2_DMA_BASE;
|
||||
clk_base = RCIN_RPI_RPI2_CLK_BASE;
|
||||
pcm_base = RCIN_RPI_RPI2_PCM_BASE;
|
||||
}
|
||||
}
|
||||
|
||||
//Map peripheral to virtual memory
|
||||
void* RCInput_Navio::map_peripheral(uint32_t base, uint32_t len)
|
||||
void* RCInput_RPI::map_peripheral(uint32_t base, uint32_t len)
|
||||
{
|
||||
int fd = open("/dev/mem", O_RDWR);
|
||||
void * vaddr;
|
||||
@ -226,7 +226,7 @@ void* RCInput_Navio::map_peripheral(uint32_t base, uint32_t len)
|
||||
}
|
||||
|
||||
//Method to init DMA control block
|
||||
void RCInput_Navio::init_dma_cb(dma_cb_t** cbp, uint32_t mode, uint32_t source, uint32_t dest, uint32_t length, uint32_t stride, uint32_t next_cb)
|
||||
void RCInput_RPI::init_dma_cb(dma_cb_t** cbp, uint32_t mode, uint32_t source, uint32_t dest, uint32_t length, uint32_t stride, uint32_t next_cb)
|
||||
{
|
||||
(*cbp)->info = mode;
|
||||
(*cbp)->src = source;
|
||||
@ -236,13 +236,13 @@ void RCInput_Navio::init_dma_cb(dma_cb_t** cbp, uint32_t mode, uint32_t source,
|
||||
(*cbp)->stride = stride;
|
||||
}
|
||||
|
||||
void RCInput_Navio::stop_dma()
|
||||
void RCInput_RPI::stop_dma()
|
||||
{
|
||||
dma_reg[RCIN_NAVIO_DMA_CS | RCIN_NAVIO_DMA_CHANNEL << 8] = 0;
|
||||
dma_reg[RCIN_RPI_DMA_CS | RCIN_RPI_DMA_CHANNEL << 8] = 0;
|
||||
}
|
||||
|
||||
/* We need to be sure that the DMA is stopped upon termination */
|
||||
void RCInput_Navio::termination_handler(int signum)
|
||||
void RCInput_RPI::termination_handler(int signum)
|
||||
{
|
||||
stop_dma();
|
||||
hal.scheduler->panic("Interrupted");
|
||||
@ -250,7 +250,7 @@ void RCInput_Navio::termination_handler(int signum)
|
||||
|
||||
|
||||
//This function is used to init DMA control blocks (setting sampling GPIO register, destination adresses, synchronization)
|
||||
void RCInput_Navio::init_ctrl_data()
|
||||
void RCInput_RPI::init_ctrl_data()
|
||||
{
|
||||
uint32_t phys_fifo_addr;
|
||||
uint32_t dest = 0;
|
||||
@ -276,13 +276,13 @@ void RCInput_Navio::init_ctrl_data()
|
||||
// fprintf(stderr, "ERROR SEARCH1\n");
|
||||
|
||||
uint32_t i = 0;
|
||||
for (i = 0; i < 56 * 128 * RCIN_NAVIO_BUFFER_LENGTH; i++) // 8 * 56 * 128 == 57344
|
||||
for (i = 0; i < 56 * 128 * RCIN_RPI_BUFFER_LENGTH; i++) // 8 * 56 * 128 == 57344
|
||||
{
|
||||
//Transfer timer every 56th sample
|
||||
if(i % 56 == 0) {
|
||||
cbp_curr = (dma_cb_t*)con_blocks->get_page(con_blocks->_virt_pages, cbp);
|
||||
|
||||
init_dma_cb(&cbp_curr, RCIN_NAVIO_DMA_NO_WIDE_BURSTS | RCIN_NAVIO_DMA_WAIT_RESP | RCIN_NAVIO_DMA_DEST_INC | RCIN_NAVIO_DMA_SRC_INC, RCIN_NAVIO_TIMER_BASE,
|
||||
init_dma_cb(&cbp_curr, RCIN_RPI_DMA_NO_WIDE_BURSTS | RCIN_RPI_DMA_WAIT_RESP | RCIN_RPI_DMA_DEST_INC | RCIN_RPI_DMA_SRC_INC, RCIN_RPI_TIMER_BASE,
|
||||
(uintptr_t) circle_buffer->get_page(circle_buffer->_phys_pages, dest),
|
||||
8,
|
||||
0,
|
||||
@ -295,7 +295,7 @@ void RCInput_Navio::init_ctrl_data()
|
||||
|
||||
// Transfer GPIO (1 byte)
|
||||
cbp_curr = (dma_cb_t*)con_blocks->get_page(con_blocks->_virt_pages, cbp);
|
||||
init_dma_cb(&cbp_curr, RCIN_NAVIO_DMA_NO_WIDE_BURSTS | RCIN_NAVIO_DMA_WAIT_RESP, RCIN_NAVIO_GPIO_LEV0_ADDR,
|
||||
init_dma_cb(&cbp_curr, RCIN_RPI_DMA_NO_WIDE_BURSTS | RCIN_RPI_DMA_WAIT_RESP, RCIN_RPI_GPIO_LEV0_ADDR,
|
||||
(uintptr_t) circle_buffer->get_page(circle_buffer->_phys_pages, dest),
|
||||
1,
|
||||
0,
|
||||
@ -310,8 +310,8 @@ void RCInput_Navio::init_ctrl_data()
|
||||
each sample of GPIO is limited by writing to PCA queue.
|
||||
*/
|
||||
cbp_curr = (dma_cb_t*)con_blocks->get_page(con_blocks->_virt_pages, cbp);
|
||||
init_dma_cb(&cbp_curr, RCIN_NAVIO_DMA_NO_WIDE_BURSTS | RCIN_NAVIO_DMA_WAIT_RESP | RCIN_NAVIO_DMA_D_DREQ | RCIN_NAVIO_DMA_PER_MAP(2),
|
||||
RCIN_NAVIO_TIMER_BASE, phys_fifo_addr,
|
||||
init_dma_cb(&cbp_curr, RCIN_RPI_DMA_NO_WIDE_BURSTS | RCIN_RPI_DMA_WAIT_RESP | RCIN_RPI_DMA_D_DREQ | RCIN_RPI_DMA_PER_MAP(2),
|
||||
RCIN_RPI_TIMER_BASE, phys_fifo_addr,
|
||||
4,
|
||||
0,
|
||||
(uintptr_t)con_blocks->get_page(con_blocks->_phys_pages,
|
||||
@ -329,27 +329,27 @@ void RCInput_Navio::init_ctrl_data()
|
||||
See BCM2835 documentation:
|
||||
http://www.raspberrypi.org/wp-content/uploads/2012/02/BCM2835-ARM-Peripherals.pdf
|
||||
*/
|
||||
void RCInput_Navio::init_PCM()
|
||||
void RCInput_RPI::init_PCM()
|
||||
{
|
||||
pcm_reg[RCIN_NAVIO_PCM_CS_A] = 1; // Disable Rx+Tx, Enable PCM block
|
||||
pcm_reg[RCIN_RPI_PCM_CS_A] = 1; // Disable Rx+Tx, Enable PCM block
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
clk_reg[RCIN_NAVIO_PCMCLK_CNTL] = 0x5A000006; // Source=PLLD (500MHz)
|
||||
clk_reg[RCIN_RPI_PCMCLK_CNTL] = 0x5A000006; // Source=PLLD (500MHz)
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
clk_reg[RCIN_NAVIO_PCMCLK_DIV] = 0x5A000000 | ((50000/RCIN_NAVIO_SAMPLE_FREQ)<<12); // Set pcm div. If we need to configure DMA frequency.
|
||||
clk_reg[RCIN_RPI_PCMCLK_DIV] = 0x5A000000 | ((50000/RCIN_RPI_SAMPLE_FREQ)<<12); // Set pcm div. If we need to configure DMA frequency.
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
clk_reg[RCIN_NAVIO_PCMCLK_CNTL] = 0x5A000016; // Source=PLLD and enable
|
||||
clk_reg[RCIN_RPI_PCMCLK_CNTL] = 0x5A000016; // Source=PLLD and enable
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
pcm_reg[RCIN_NAVIO_PCM_TXC_A] = 0<<31 | 1<<30 | 0<<20 | 0<<16; // 1 channel, 8 bits
|
||||
pcm_reg[RCIN_RPI_PCM_TXC_A] = 0<<31 | 1<<30 | 0<<20 | 0<<16; // 1 channel, 8 bits
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
pcm_reg[RCIN_NAVIO_PCM_MODE_A] = (10 - 1) << 10; //PCM mode
|
||||
pcm_reg[RCIN_RPI_PCM_MODE_A] = (10 - 1) << 10; //PCM mode
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
pcm_reg[RCIN_NAVIO_PCM_CS_A] |= 1<<4 | 1<<3; // Clear FIFOs
|
||||
pcm_reg[RCIN_RPI_PCM_CS_A] |= 1<<4 | 1<<3; // Clear FIFOs
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
pcm_reg[RCIN_NAVIO_PCM_DREQ_A] = 64<<24 | 64<<8; // DMA Req when one slot is free?
|
||||
pcm_reg[RCIN_RPI_PCM_DREQ_A] = 64<<24 | 64<<8; // DMA Req when one slot is free?
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
pcm_reg[RCIN_NAVIO_PCM_CS_A] |= 1<<9; // Enable DMA
|
||||
pcm_reg[RCIN_RPI_PCM_CS_A] |= 1<<9; // Enable DMA
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
pcm_reg[RCIN_NAVIO_PCM_CS_A] |= 1<<2; // Enable Tx
|
||||
pcm_reg[RCIN_RPI_PCM_CS_A] |= 1<<2; // Enable Tx
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
}
|
||||
|
||||
@ -357,75 +357,79 @@ void RCInput_Navio::init_PCM()
|
||||
See BCM2835 documentation:
|
||||
http://www.raspberrypi.org/wp-content/uploads/2012/02/BCM2835-ARM-Peripherals.pdf
|
||||
*/
|
||||
void RCInput_Navio::init_DMA()
|
||||
void RCInput_RPI::init_DMA()
|
||||
{
|
||||
dma_reg[RCIN_NAVIO_DMA_CS | RCIN_NAVIO_DMA_CHANNEL << 8] = RCIN_NAVIO_DMA_RESET; //Reset DMA
|
||||
dma_reg[RCIN_RPI_DMA_CS | RCIN_RPI_DMA_CHANNEL << 8] = RCIN_RPI_DMA_RESET; //Reset DMA
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
dma_reg[RCIN_NAVIO_DMA_CS | RCIN_NAVIO_DMA_CHANNEL << 8] = RCIN_NAVIO_DMA_INT | RCIN_NAVIO_DMA_END;
|
||||
dma_reg[RCIN_NAVIO_DMA_CONBLK_AD | RCIN_NAVIO_DMA_CHANNEL << 8] = reinterpret_cast<uintptr_t>(con_blocks->get_page(con_blocks->_phys_pages, 0));//Set first control block address
|
||||
dma_reg[RCIN_NAVIO_DMA_DEBUG | RCIN_NAVIO_DMA_CHANNEL << 8] = 7; // clear debug error flags
|
||||
dma_reg[RCIN_NAVIO_DMA_CS | RCIN_NAVIO_DMA_CHANNEL << 8] = 0x10880001; // go, mid priority, wait for outstanding writes
|
||||
dma_reg[RCIN_RPI_DMA_CS | RCIN_RPI_DMA_CHANNEL << 8] = RCIN_RPI_DMA_INT | RCIN_RPI_DMA_END;
|
||||
dma_reg[RCIN_RPI_DMA_CONBLK_AD | RCIN_RPI_DMA_CHANNEL << 8] = reinterpret_cast<uintptr_t>(con_blocks->get_page(con_blocks->_phys_pages, 0));//Set first control block address
|
||||
dma_reg[RCIN_RPI_DMA_DEBUG | RCIN_RPI_DMA_CHANNEL << 8] = 7; // clear debug error flags
|
||||
dma_reg[RCIN_RPI_DMA_CS | RCIN_RPI_DMA_CHANNEL << 8] = 0x10880001; // go, mid priority, wait for outstanding writes
|
||||
}
|
||||
|
||||
|
||||
//We must stop DMA when the process is killed
|
||||
void RCInput_Navio::set_sigaction()
|
||||
void RCInput_RPI::set_sigaction()
|
||||
{
|
||||
for (int i = 0; i < 64; i++) {
|
||||
//catch all signals (like ctrl+c, ctrl+z, ...) to ensure DMA is disabled
|
||||
struct sigaction sa;
|
||||
memset(&sa, 0, sizeof(sa));
|
||||
sa.sa_handler = RCInput_Navio::termination_handler;
|
||||
sa.sa_handler = RCInput_RPI::termination_handler;
|
||||
sigaction(i, &sa, NULL);
|
||||
}
|
||||
}
|
||||
|
||||
//Initial setup of variables
|
||||
RCInput_Navio::RCInput_Navio():
|
||||
RCInput_RPI::RCInput_RPI():
|
||||
prev_tick(0),
|
||||
delta_time(0),
|
||||
curr_tick_inc(1000/RCIN_NAVIO_SAMPLE_FREQ),
|
||||
curr_tick_inc(1000/RCIN_RPI_SAMPLE_FREQ),
|
||||
curr_pointer(0),
|
||||
curr_channel(0),
|
||||
width_s0(0),
|
||||
curr_signal(0),
|
||||
last_signal(228),
|
||||
state(RCIN_NAVIO_INITIAL_STATE)
|
||||
{
|
||||
state(RCIN_RPI_INITIAL_STATE)
|
||||
{
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2
|
||||
int version = 2;
|
||||
#else
|
||||
int version = UtilRPI::from(hal.util)->get_rpi_version();
|
||||
#endif
|
||||
set_physical_addresses(version);
|
||||
|
||||
//Init memory for buffer and for DMA control blocks. See comments in "init_ctrl_data()" to understand values "2" and "113"
|
||||
circle_buffer = new Memory_table(RCIN_NAVIO_BUFFER_LENGTH * 2, version);
|
||||
con_blocks = new Memory_table(RCIN_NAVIO_BUFFER_LENGTH * 113, version);
|
||||
circle_buffer = new Memory_table(RCIN_RPI_BUFFER_LENGTH * 2, version);
|
||||
con_blocks = new Memory_table(RCIN_RPI_BUFFER_LENGTH * 113, version);
|
||||
}
|
||||
|
||||
RCInput_Navio::~RCInput_Navio()
|
||||
RCInput_RPI::~RCInput_RPI()
|
||||
{
|
||||
delete circle_buffer;
|
||||
delete con_blocks;
|
||||
}
|
||||
|
||||
void RCInput_Navio::deinit()
|
||||
void RCInput_RPI::deinit()
|
||||
{
|
||||
stop_dma();
|
||||
}
|
||||
|
||||
//Initializing necessary registers
|
||||
void RCInput_Navio::init_registers()
|
||||
void RCInput_RPI::init_registers()
|
||||
{
|
||||
dma_reg = (uint32_t*)map_peripheral(dma_base, RCIN_NAVIO_DMA_LEN);
|
||||
pcm_reg = (uint32_t*)map_peripheral(pcm_base, RCIN_NAVIO_PCM_LEN);
|
||||
clk_reg = (uint32_t*)map_peripheral(clk_base, RCIN_NAVIO_CLK_LEN);
|
||||
dma_reg = (uint32_t*)map_peripheral(dma_base, RCIN_RPI_DMA_LEN);
|
||||
pcm_reg = (uint32_t*)map_peripheral(pcm_base, RCIN_RPI_PCM_LEN);
|
||||
clk_reg = (uint32_t*)map_peripheral(clk_base, RCIN_RPI_CLK_LEN);
|
||||
}
|
||||
|
||||
void RCInput_Navio::init(void*)
|
||||
void RCInput_RPI::init(void*)
|
||||
{
|
||||
|
||||
init_registers();
|
||||
|
||||
//Enable PPM input
|
||||
enable_pin = hal.gpio->channel(PPM_INPUT_NAVIO);
|
||||
enable_pin = hal.gpio->channel(PPM_INPUT_RPI);
|
||||
enable_pin->mode(HAL_GPIO_INPUT);
|
||||
|
||||
//Configuration
|
||||
@ -448,13 +452,13 @@ void RCInput_Navio::init(void*)
|
||||
|
||||
|
||||
//Processing signal
|
||||
void RCInput_Navio::_timer_tick()
|
||||
void RCInput_RPI::_timer_tick()
|
||||
{
|
||||
int j;
|
||||
void* x;
|
||||
|
||||
//Now we are getting address in which DMAC is writing at current moment
|
||||
dma_cb_t* ad = (dma_cb_t*) con_blocks->get_virt_addr(dma_reg[RCIN_NAVIO_DMA_CONBLK_AD | RCIN_NAVIO_DMA_CHANNEL << 8]);
|
||||
dma_cb_t* ad = (dma_cb_t*) con_blocks->get_virt_addr(dma_reg[RCIN_RPI_DMA_CONBLK_AD | RCIN_RPI_DMA_CHANNEL << 8]);
|
||||
for(j = 1; j >= -1; j--){
|
||||
x = circle_buffer->get_virt_addr((ad + j)->dst);
|
||||
if(x != NULL) {
|
||||
@ -464,8 +468,8 @@ void RCInput_Navio::_timer_tick()
|
||||
//How many bytes have DMA transfered (and we can process)?
|
||||
counter = circle_buffer->bytes_available(curr_pointer, circle_buffer->get_offset(circle_buffer->_virt_pages, (uintptr_t)x));
|
||||
//We can't stay in method for a long time, because it may lead to delays
|
||||
if (counter > RCIN_NAVIO_MAX_COUNTER) {
|
||||
counter = RCIN_NAVIO_MAX_COUNTER;
|
||||
if (counter > RCIN_RPI_MAX_COUNTER) {
|
||||
counter = RCIN_RPI_MAX_COUNTER;
|
||||
}
|
||||
|
||||
//Processing ready bytes
|
||||
@ -483,21 +487,21 @@ void RCInput_Navio::_timer_tick()
|
||||
delta_time = curr_tick - prev_tick;
|
||||
prev_tick = curr_tick;
|
||||
switch (state) {
|
||||
case RCIN_NAVIO_INITIAL_STATE:
|
||||
state = RCIN_NAVIO_ZERO_STATE;
|
||||
case RCIN_RPI_INITIAL_STATE:
|
||||
state = RCIN_RPI_ZERO_STATE;
|
||||
break;
|
||||
case RCIN_NAVIO_ZERO_STATE:
|
||||
case RCIN_RPI_ZERO_STATE:
|
||||
if (curr_signal == 0) {
|
||||
width_s0 = (uint16_t) delta_time;
|
||||
state = RCIN_NAVIO_ONE_STATE;
|
||||
state = RCIN_RPI_ONE_STATE;
|
||||
break;
|
||||
}
|
||||
else
|
||||
break;
|
||||
case RCIN_NAVIO_ONE_STATE:
|
||||
case RCIN_RPI_ONE_STATE:
|
||||
if (curr_signal == 1) {
|
||||
width_s1 = (uint16_t) delta_time;
|
||||
state = RCIN_NAVIO_ZERO_STATE;
|
||||
state = RCIN_RPI_ZERO_STATE;
|
||||
_process_rc_pulse(width_s0, width_s1);
|
||||
break;
|
||||
}
|
@ -1,5 +1,5 @@
|
||||
#ifndef __AP_HAL_LINUX_RCINPUT_NAVIO_H__
|
||||
#define __AP_HAL_LINUX_RCINPUT_NAVIO_H__
|
||||
#ifndef __AP_HAL_LINUX_RCINPUT_RPI_H__
|
||||
#define __AP_HAL_LINUX_RCINPUT_RPI_H__
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include "RCInput.h"
|
||||
@ -24,9 +24,9 @@
|
||||
|
||||
|
||||
enum state_t{
|
||||
RCIN_NAVIO_INITIAL_STATE = -1,
|
||||
RCIN_NAVIO_ZERO_STATE = 0,
|
||||
RCIN_NAVIO_ONE_STATE = 1
|
||||
RCIN_RPI_INITIAL_STATE = -1,
|
||||
RCIN_RPI_ZERO_STATE = 0,
|
||||
RCIN_RPI_ONE_STATE = 1
|
||||
};
|
||||
|
||||
|
||||
@ -45,8 +45,8 @@ typedef struct {
|
||||
} dma_cb_t;
|
||||
|
||||
class Memory_table {
|
||||
// Allow RCInput_Navio access to private members of Memory_table
|
||||
friend class Linux::RCInput_Navio;
|
||||
// Allow RCInput_RPI access to private members of Memory_table
|
||||
friend class Linux::RCInput_RPI;
|
||||
|
||||
private:
|
||||
void** _virt_pages;
|
||||
@ -74,13 +74,13 @@ public:
|
||||
};
|
||||
|
||||
|
||||
class Linux::RCInput_Navio : public Linux::RCInput
|
||||
class Linux::RCInput_RPI : public Linux::RCInput
|
||||
{
|
||||
public:
|
||||
void init(void*);
|
||||
void _timer_tick(void);
|
||||
RCInput_Navio();
|
||||
~RCInput_Navio();
|
||||
RCInput_RPI();
|
||||
~RCInput_RPI();
|
||||
|
||||
private:
|
||||
|
||||
@ -131,4 +131,4 @@ private:
|
||||
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_LINUX_RCINPUT_NAVIO_H__
|
||||
#endif // __AP_HAL_LINUX_RCINPUT_RPI_H__
|
Loading…
Reference in New Issue
Block a user