From 90cbb6ad26e484e534506a3e90c0c838a8633f49 Mon Sep 17 00:00:00 2001 From: Richard Allen Date: Tue, 7 Feb 2023 01:34:46 +0000 Subject: [PATCH] AP_HAL_Linux: Update GPIO and RCInput for pi version change Update version numbers according to earlier change. Fixes: 53c1c235b890bba4b8eded0a0144164c70d17be8 --- libraries/AP_HAL_Linux/GPIO_RPI.cpp | 9 ++++++--- libraries/AP_HAL_Linux/RCInput_RPI.cpp | 14 +++++++------- 2 files changed, 13 insertions(+), 10 deletions(-) diff --git a/libraries/AP_HAL_Linux/GPIO_RPI.cpp b/libraries/AP_HAL_Linux/GPIO_RPI.cpp index f64ceb06ba..168f44cec5 100644 --- a/libraries/AP_HAL_Linux/GPIO_RPI.cpp +++ b/libraries/AP_HAL_Linux/GPIO_RPI.cpp @@ -163,12 +163,15 @@ void GPIO_RPI::init() const int rpi_version = UtilRPI::from(hal.util)->get_rpi_version(); GPIO_RPI::Address peripheral_base; - if(rpi_version == 1) { + if(rpi_version == 0) { peripheral_base = Address::BCM2708_PERIPHERAL_BASE; - } else if (rpi_version == 2) { + } else if (rpi_version == 1 || rpi_version == 2) { peripheral_base = Address::BCM2709_PERIPHERAL_BASE; - } else { + } else if (rpi_version == 3) { peripheral_base = Address::BCM2711_PERIPHERAL_BASE; + } else { + AP_HAL::panic("Unknown rpi_version, cannot locate peripheral base address"); + return; } if (!openMemoryDevice()) { diff --git a/libraries/AP_HAL_Linux/RCInput_RPI.cpp b/libraries/AP_HAL_Linux/RCInput_RPI.cpp index 7f0b3fac74..2fb2256a71 100644 --- a/libraries/AP_HAL_Linux/RCInput_RPI.cpp +++ b/libraries/AP_HAL_Linux/RCInput_RPI.cpp @@ -157,7 +157,7 @@ Memory_table::Memory_table(uint32_t page_count, int version) uint32_t i; int fdMem, file; // Cache coherent adresses depends on RPI's version - uint32_t bus = version == 1 ? 0x40000000 : 0xC0000000; + uint32_t bus = version == 0 ? 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 == 1 ? 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 == 0 ? 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,17 +274,17 @@ 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 == 1) { + if (_version == 0) { // 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 == 2) { + } else if (_version == 1 || _version == 2) { // 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 == 4) { + } else if (_version == 3) { dma_base = RCIN_RPI_RPI4_DMA_BASE; clk_base = RCIN_RPI_RPI4_CLK_BASE; pcm_base = RCIN_RPI_RPI4_PCM_BASE; @@ -424,7 +424,7 @@ 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 != 4) { + if (_version != 3) { 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 { @@ -524,7 +524,7 @@ void RCInput_RPI::init() uint64_t signal_states(0); #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 - _version = 2; + _version = 1; #else _version = UtilRPI::from(hal.util)->get_rpi_version(); #endif