2014-10-26 16:18:04 -03:00
|
|
|
#ifndef __AP_HAL_LINUX_RCINPUT_NAVIO_H__
|
|
|
|
#define __AP_HAL_LINUX_RCINPUT_NAVIO_H__
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_HAL_Linux.h"
|
2014-10-26 16:18:04 -03:00
|
|
|
#include "RCInput.h"
|
2015-04-16 12:18:14 -03:00
|
|
|
#include <signal.h>
|
|
|
|
#include <pthread.h>
|
|
|
|
#include <stdio.h>
|
|
|
|
#include <stdlib.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
#include <string.h>
|
|
|
|
#include <errno.h>
|
|
|
|
#include <stdarg.h>
|
|
|
|
#include <stdint.h>
|
|
|
|
#include <signal.h>
|
|
|
|
#include <time.h>
|
|
|
|
#include <sys/time.h>
|
|
|
|
#include <sys/types.h>
|
|
|
|
#include <sys/stat.h>
|
|
|
|
#include <fcntl.h>
|
|
|
|
#include <sys/mman.h>
|
|
|
|
#include <assert.h>
|
|
|
|
#include <queue>
|
|
|
|
|
|
|
|
|
|
|
|
enum state_t{
|
2015-08-15 07:29:14 -03:00
|
|
|
RCIN_NAVIO_INITIAL_STATE = -1,
|
|
|
|
RCIN_NAVIO_ZERO_STATE = 0,
|
|
|
|
RCIN_NAVIO_ONE_STATE = 1
|
2015-04-16 12:18:14 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
//Memory table structure
|
|
|
|
typedef struct {
|
|
|
|
void **virt_pages;
|
|
|
|
void **phys_pages;
|
|
|
|
uint32_t page_count;
|
|
|
|
} memory_table_t;
|
|
|
|
|
|
|
|
|
|
|
|
//DMA control block structure
|
|
|
|
typedef struct {
|
|
|
|
uint32_t info, src, dst, length,
|
|
|
|
stride, next, pad[2];
|
|
|
|
} dma_cb_t;
|
|
|
|
|
2015-07-01 09:04:57 -03:00
|
|
|
class Memory_table {
|
|
|
|
// Allow LinuxRCInput_Navio access to private members of Memory_table
|
|
|
|
friend class Linux::LinuxRCInput_Navio;
|
|
|
|
|
|
|
|
private:
|
2015-04-16 12:18:14 -03:00
|
|
|
void** _virt_pages;
|
|
|
|
void** _phys_pages;
|
|
|
|
uint32_t _page_count;
|
|
|
|
|
2015-07-01 09:04:57 -03:00
|
|
|
public:
|
2015-04-16 12:18:14 -03:00
|
|
|
Memory_table();
|
|
|
|
Memory_table(uint32_t, int);
|
|
|
|
~Memory_table();
|
|
|
|
|
2015-07-01 09:04:57 -03:00
|
|
|
//Get virtual address from the corresponding physical address from memory_table.
|
|
|
|
void* get_virt_addr(const uint32_t phys_addr) const;
|
2015-04-16 12:18:14 -03:00
|
|
|
|
|
|
|
// This function returns physical address with help of pointer, which is offset from the beginning of the buffer.
|
2015-07-01 09:04:57 -03:00
|
|
|
void* get_page(void **pages, const uint32_t addr) const;
|
2015-04-16 12:18:14 -03:00
|
|
|
|
2015-07-01 09:04:57 -03:00
|
|
|
// This function returns offset from the beginning of the buffer using (virtual) address in 'pages' and memory_table.
|
|
|
|
uint32_t get_offset(void **pages, const uint32_t addr) const;
|
2015-04-16 12:18:14 -03:00
|
|
|
|
|
|
|
//How many bytes are available for reading in circle buffer?
|
2015-07-01 09:04:57 -03:00
|
|
|
uint32_t bytes_available(const uint32_t read_addr, const uint32_t write_addr) const;
|
2015-04-16 12:18:14 -03:00
|
|
|
|
2015-07-01 09:04:57 -03:00
|
|
|
uint32_t get_page_count() const;
|
2015-04-16 12:18:14 -03:00
|
|
|
};
|
|
|
|
|
2014-10-26 16:18:04 -03:00
|
|
|
|
|
|
|
class Linux::LinuxRCInput_Navio : public Linux::LinuxRCInput
|
2015-07-01 09:04:57 -03:00
|
|
|
{
|
|
|
|
public:
|
2014-10-26 16:18:04 -03:00
|
|
|
void init(void*);
|
|
|
|
void _timer_tick(void);
|
2015-04-16 12:18:14 -03:00
|
|
|
LinuxRCInput_Navio();
|
|
|
|
~LinuxRCInput_Navio();
|
2014-10-26 16:18:04 -03:00
|
|
|
|
2015-07-01 09:04:57 -03:00
|
|
|
private:
|
2015-04-16 12:18:14 -03:00
|
|
|
|
|
|
|
//Physical adresses of peripherals. Are different on different Raspberries.
|
|
|
|
uint32_t dma_base;
|
|
|
|
uint32_t clk_base;
|
|
|
|
uint32_t pcm_base;
|
|
|
|
|
|
|
|
//registers
|
|
|
|
static volatile uint32_t *pcm_reg;
|
|
|
|
static volatile uint32_t *clk_reg;
|
|
|
|
static volatile uint32_t *dma_reg;
|
|
|
|
|
|
|
|
Memory_table *circle_buffer;
|
|
|
|
Memory_table *con_blocks;
|
|
|
|
|
|
|
|
uint64_t curr_tick;
|
|
|
|
uint64_t prev_tick;
|
|
|
|
uint64_t delta_time;
|
|
|
|
|
|
|
|
uint32_t curr_tick_inc;
|
|
|
|
uint32_t curr_pointer;
|
|
|
|
uint32_t curr_channel;
|
|
|
|
uint32_t counter;
|
|
|
|
|
2014-10-28 11:37:25 -03:00
|
|
|
uint16_t width_s0;
|
|
|
|
uint16_t width_s1;
|
2015-04-16 12:18:14 -03:00
|
|
|
|
|
|
|
uint8_t curr_signal;
|
|
|
|
uint8_t last_signal;
|
|
|
|
|
|
|
|
state_t state;
|
|
|
|
|
|
|
|
AP_HAL::DigitalSource *enable_pin;
|
|
|
|
|
2015-07-01 09:04:57 -03:00
|
|
|
void 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);
|
2015-04-16 12:18:14 -03:00
|
|
|
void* map_peripheral(uint32_t base, uint32_t len);
|
|
|
|
void init_registers();
|
|
|
|
void init_ctrl_data();
|
|
|
|
void init_PCM();
|
|
|
|
void init_DMA();
|
|
|
|
void init_buffer();
|
2015-07-09 11:07:53 -03:00
|
|
|
static void stop_dma();
|
|
|
|
static void termination_handler(int signum);
|
2015-04-16 12:18:14 -03:00
|
|
|
void set_sigaction();
|
|
|
|
void set_physical_addresses(int version);
|
2015-07-06 19:49:04 -03:00
|
|
|
void deinit() override;
|
2015-04-16 12:18:14 -03:00
|
|
|
|
2014-10-26 16:18:04 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_HAL_LINUX_RCINPUT_NAVIO_H__
|