mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: Fix RPI check using enumerations
This commit is contained in:
parent
3caa6400e1
commit
df3ee3086a
|
@ -160,14 +160,14 @@ void GPIO_RPI::closeMemoryDevice()
|
|||
|
||||
void GPIO_RPI::init()
|
||||
{
|
||||
const int rpi_version = UtilRPI::from(hal.util)->get_rpi_version();
|
||||
const LINUX_BOARD_TYPE rpi_version = UtilRPI::from(hal.util)->detect_linux_board_type();
|
||||
|
||||
GPIO_RPI::Address peripheral_base;
|
||||
if(rpi_version == 0) {
|
||||
if(rpi_version == LINUX_BOARD_TYPE::RPI_ZERO_1) {
|
||||
peripheral_base = Address::BCM2708_PERIPHERAL_BASE;
|
||||
} else if (rpi_version == 1 || rpi_version == 2) {
|
||||
} else if (rpi_version == LINUX_BOARD_TYPE::RPI_2_3_ZERO2) {
|
||||
peripheral_base = Address::BCM2709_PERIPHERAL_BASE;
|
||||
} else if (rpi_version == 3) {
|
||||
} else if (rpi_version == LINUX_BOARD_TYPE::RPI_4) {
|
||||
peripheral_base = Address::BCM2711_PERIPHERAL_BASE;
|
||||
} else {
|
||||
AP_HAL::panic("Unknown rpi_version, cannot locate peripheral base address");
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
|
||||
#include "GPIO.h"
|
||||
#include "RCInput_RPI.h"
|
||||
#include "Util_RPI.h"
|
||||
|
||||
|
||||
#ifdef DEBUG
|
||||
#define debug(fmt, args ...) do { fprintf(stderr,"[RCInput_RPI]: %s:%d: " fmt, __FUNCTION__, __LINE__, ## args); } while (0)
|
||||
|
@ -152,12 +152,12 @@ Memory_table::Memory_table()
|
|||
}
|
||||
|
||||
// Init Memory table
|
||||
Memory_table::Memory_table(uint32_t page_count, int version)
|
||||
Memory_table::Memory_table(const uint32_t page_count, const LINUX_BOARD_TYPE version)
|
||||
{
|
||||
uint32_t i;
|
||||
int fdMem, file;
|
||||
// Cache coherent adresses depends on RPI's version
|
||||
uint32_t bus = version == 0 ? 0x40000000 : 0xC0000000;
|
||||
uint32_t bus = version == LINUX_BOARD_TYPE::RPI_ZERO_1 ? 0x40000000 : 0xC0000000;
|
||||
uint64_t pageInfo;
|
||||
void *offset;
|
||||
|
||||
|
@ -199,7 +199,7 @@ Memory_table::Memory_table(uint32_t page_count, int version)
|
|||
munmap(_virt_pages[i], PAGE_SIZE);
|
||||
|
||||
void * prev_virt = _virt_pages[i];
|
||||
_virt_pages[i] = mmap(_virt_pages[i], PAGE_SIZE, PROT_READ | PROT_WRITE, MAP_SHARED | MAP_FIXED | MAP_NORESERVE | MAP_LOCKED, fdMem, ((uintptr_t)_phys_pages[i] & (version == 0 ? 0xFFFFFFFFFFFFFFFF : ~bus)));
|
||||
_virt_pages[i] = mmap(_virt_pages[i], PAGE_SIZE, PROT_READ | PROT_WRITE, MAP_SHARED | MAP_FIXED | MAP_NORESERVE | MAP_LOCKED, fdMem, ((uintptr_t)_phys_pages[i] & (version == LINUX_BOARD_TYPE::RPI_ZERO_1 ? 0xFFFFFFFFFFFFFFFF : ~bus)));
|
||||
if (_virt_pages[i] == MAP_FAILED) {
|
||||
fprintf(stderr, "Failed phys2virt prev_virt=%p phys_page=%p %m\n", prev_virt, _phys_pages[i]);
|
||||
printf("Make sure that CONFIG_STRICT_DEVMEM is disabled\n");
|
||||
|
@ -274,22 +274,22 @@ uint32_t Memory_table::get_page_count() const
|
|||
// Physical addresses of peripheral depends on Raspberry Pi's version
|
||||
void RCInput_RPI::set_physical_addresses()
|
||||
{
|
||||
if (_version == 0) {
|
||||
if (_version == LINUX_BOARD_TYPE::RPI_ZERO_1) {
|
||||
// 1 & zero are the same
|
||||
dma_base = RCIN_RPI_RPI1_DMA_BASE;
|
||||
clk_base = RCIN_RPI_RPI1_CLK_BASE;
|
||||
pcm_base = RCIN_RPI_RPI1_PCM_BASE;
|
||||
} else if (_version == 1 || _version == 2) {
|
||||
} else if (_version == LINUX_BOARD_TYPE::RPI_2_3_ZERO2) {
|
||||
// 2 & 3 are the same
|
||||
dma_base = RCIN_RPI_RPI2_DMA_BASE;
|
||||
clk_base = RCIN_RPI_RPI2_CLK_BASE;
|
||||
pcm_base = RCIN_RPI_RPI2_PCM_BASE;
|
||||
} else if (_version == 3) {
|
||||
} else if (_version == LINUX_BOARD_TYPE::RPI_4) {
|
||||
dma_base = RCIN_RPI_RPI4_DMA_BASE;
|
||||
clk_base = RCIN_RPI_RPI4_CLK_BASE;
|
||||
pcm_base = RCIN_RPI_RPI4_PCM_BASE;
|
||||
} else {
|
||||
fprintf(stderr,"unknown RPI _version=%i\n", _version);
|
||||
fprintf(stderr,"Unknown Linux Board version!\n");
|
||||
exit(-1);
|
||||
}
|
||||
}
|
||||
|
@ -424,10 +424,11 @@ void RCInput_RPI::init_PCM()
|
|||
hal.scheduler->delay_microseconds(100);
|
||||
clk_reg[RCIN_RPI_PCMCLK_CNTL] = 0x5A000006; // Source=PLLD (500MHz)
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
if (_version != 3) {
|
||||
if (_version != LINUX_BOARD_TYPE::RPI_4) {
|
||||
clk_reg[RCIN_RPI_PCMCLK_DIV] = 0x5A000000 | ((RCIN_RPI_PLL_CLK/RCIN_RPI_SAMPLE_FREQ)<<12); // Set pcm div for BCM2835 500MHZ clock. If we need to configure DMA frequency.
|
||||
}
|
||||
else {
|
||||
// RPI-4
|
||||
clk_reg[RCIN_RPI_PCMCLK_DIV] = 0x5A000000 | ((RCIN_RPI4_PLL_CLK/RCIN_RPI_SAMPLE_FREQ)<< 12); // Set pcm div for BCM2711 700MHz clock. If we need to configure DMA frequency.
|
||||
}
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
|
@ -524,9 +525,9 @@ void RCInput_RPI::init()
|
|||
uint64_t signal_states(0);
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2
|
||||
_version = 1;
|
||||
_version = LINUX_BOARD_TYPE::RPI_2_3_ZERO2;
|
||||
#else
|
||||
_version = UtilRPI::from(hal.util)->get_rpi_version();
|
||||
_version = UtilRPI::from(hal.util)->detect_linux_board_type();
|
||||
#endif
|
||||
|
||||
set_physical_addresses();
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
#include <assert.h>
|
||||
#include <queue>
|
||||
|
||||
#include "Util_RPI.h"
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
|
||||
#define RCIN_RPI_CHN_NUM 8
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OBAL_V1
|
||||
|
@ -61,7 +63,7 @@ private:
|
|||
|
||||
public:
|
||||
Memory_table();
|
||||
Memory_table(uint32_t, int);
|
||||
Memory_table(const uint32_t, const LINUX_BOARD_TYPE);
|
||||
~Memory_table();
|
||||
|
||||
//Get virtual address from the corresponding physical address from memory_table.
|
||||
|
@ -132,7 +134,7 @@ private:
|
|||
} rc_channels[RCIN_RPI_CHN_NUM];
|
||||
|
||||
bool _initialized = false;
|
||||
int _version =0;
|
||||
LINUX_BOARD_TYPE _version = LINUX_BOARD_TYPE::UNKNOWN_BOARD;
|
||||
|
||||
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);
|
||||
void* map_peripheral(uint32_t base, uint32_t len);
|
||||
|
|
|
@ -27,47 +27,67 @@ using namespace Linux;
|
|||
|
||||
UtilRPI::UtilRPI()
|
||||
{
|
||||
_check_rpi_version_by_rev();
|
||||
_get_board_type_using_peripheral_base ();
|
||||
}
|
||||
|
||||
int UtilRPI::_check_rpi_version_by_rev()
|
||||
|
||||
//
|
||||
// previous appraoch was using /proc/device-tree/system/linux,revision
|
||||
// now we use /proc/device-tree/soc/ranges see: https://forums.raspberrypi.com//viewtopic.php?t=244031
|
||||
void UtilRPI::_get_board_type_using_peripheral_base()
|
||||
{
|
||||
// assume 2 if unknown
|
||||
_rpi_version = 2;
|
||||
const char *SOC[]= {"Broadcom BCM2835","Broadcom BCM2836","Broadcom BCM2837","Broadcom BCM2711"};
|
||||
const char *revision_file_ = "/proc/device-tree/system/linux,revision";
|
||||
uint8_t revision[4] = { 0 };
|
||||
uint32_t cpu = 0;
|
||||
FILE *fd;
|
||||
FILE *fp;
|
||||
uint32_t base=0x00;
|
||||
unsigned char buf[32];
|
||||
_linux_board_version = LINUX_BOARD_TYPE::UNKNOWN_BOARD;
|
||||
fp = fopen("/proc/device-tree/soc/ranges" , "rb");
|
||||
if (fp) {
|
||||
const uint16_t len = fread(buf, 1, sizeof(buf), fp);
|
||||
if (len >= 8) {
|
||||
base = buf[4]<<24 | buf[5]<<16 | buf[6]<<8 | buf[7];
|
||||
if (!base)
|
||||
base = buf[8]<<24 | buf[9]<<16 | buf[10]<<8 | buf[11];
|
||||
if (!base)
|
||||
base = buf[8]<<24 | buf[9]<<16 | buf[10]<<8 | buf[11];
|
||||
if (!base && (len>15))
|
||||
base = buf[12]<<24 | buf[13]<<16 | buf[14]<<8 | buf[15];
|
||||
|
||||
if ((fd = fopen(revision_file_, "rb")) == NULL) {
|
||||
printf("Can't open '%s'\n", revision_file_);
|
||||
}
|
||||
else {
|
||||
if (fread(revision, 1, sizeof(revision), fd) == 4) {
|
||||
cpu = (revision[2] >> 4) & 0xf;
|
||||
|
||||
_rpi_version = cpu;
|
||||
|
||||
if (_rpi_version==0) {
|
||||
_rpi_version=1; //RPI-Zero
|
||||
fclose(fp);
|
||||
}
|
||||
|
||||
printf("SOC: %s use intern: %d \r\n",SOC[cpu], _rpi_version);
|
||||
}
|
||||
else {
|
||||
printf("Revision data too short\n");
|
||||
}
|
||||
fclose(fd);
|
||||
switch (base) {
|
||||
case 0x0:
|
||||
_linux_board_version = LINUX_BOARD_TYPE::UNKNOWN_BOARD;
|
||||
printf("Cannot detect board-type \r\n");
|
||||
break;
|
||||
case 0x20000000:
|
||||
_linux_board_version = LINUX_BOARD_TYPE::RPI_ZERO_1;
|
||||
printf("RPI Zero / 1 \r\n");
|
||||
printf("Peripheral base address is %x\n", base);
|
||||
break;
|
||||
case 0x3f000000:
|
||||
_linux_board_version = LINUX_BOARD_TYPE::RPI_2_3_ZERO2;
|
||||
printf("RPI 2, 3 or Zero-2 \r\n");
|
||||
printf("Peripheral base address is %x\n", base);
|
||||
break;
|
||||
case 0xfe000000:
|
||||
_linux_board_version = LINUX_BOARD_TYPE::RPI_4;
|
||||
printf("RPI 4 \r\n");
|
||||
printf("Peripheral base address is %x\n", base);
|
||||
break;
|
||||
case 0x40000000:
|
||||
_linux_board_version = LINUX_BOARD_TYPE::ALLWINNWER_H616;
|
||||
printf("AllWinner-H616 \r\n");
|
||||
break;
|
||||
}
|
||||
|
||||
return _rpi_version;
|
||||
return ;
|
||||
}
|
||||
|
||||
|
||||
int UtilRPI::get_rpi_version() const
|
||||
LINUX_BOARD_TYPE UtilRPI::detect_linux_board_type() const
|
||||
{
|
||||
return _rpi_version;
|
||||
return _linux_board_version;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -4,6 +4,14 @@
|
|||
|
||||
namespace Linux {
|
||||
|
||||
enum class LINUX_BOARD_TYPE: int {
|
||||
RPI_ZERO_1=0,
|
||||
RPI_2_3_ZERO2=1,
|
||||
RPI_4=2,
|
||||
ALLWINNWER_H616=100,
|
||||
UNKNOWN_BOARD=999
|
||||
};
|
||||
|
||||
class UtilRPI : public Util {
|
||||
public:
|
||||
UtilRPI();
|
||||
|
@ -13,14 +21,14 @@ public:
|
|||
}
|
||||
|
||||
/* return the Raspberry Pi version */
|
||||
int get_rpi_version() const;
|
||||
LINUX_BOARD_TYPE detect_linux_board_type() const;
|
||||
|
||||
protected:
|
||||
// Called in the constructor once
|
||||
int _check_rpi_version_by_rev();
|
||||
void _get_board_type_using_peripheral_base();
|
||||
|
||||
private:
|
||||
int _rpi_version = 0;
|
||||
LINUX_BOARD_TYPE _linux_board_version = LINUX_BOARD_TYPE::UNKNOWN_BOARD;
|
||||
};
|
||||
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue