mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: Ethernet related memory allocations
This commit is contained in:
parent
3b79ff0ad3
commit
f66327d97d
|
@ -0,0 +1,35 @@
|
|||
/*
|
||||
ChibiOS - Copyright (C) 2006..2015 Giovanni Di Sirio
|
||||
|
||||
Licensed under the Apache License, Version 2.0 (the "License");
|
||||
you may not use this file except in compliance with the License.
|
||||
You may obtain a copy of the License at
|
||||
|
||||
http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
Unless required by applicable law or agreed to in writing, software
|
||||
distributed under the License is distributed on an "AS IS" BASIS,
|
||||
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
See the License for the specific language governing permissions and
|
||||
limitations under the License.
|
||||
*/
|
||||
|
||||
/*
|
||||
this file is included by the board specific ldscript.ld which is
|
||||
generated from hwdef.dat
|
||||
*/
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
/* Special section for Ethernet DMA non cache-able areas.*/
|
||||
.eth (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
__eth_base__ = .;
|
||||
*(.eth)
|
||||
*(.eth.*)
|
||||
*(.bss.__eth_*)
|
||||
. = ALIGN(4);
|
||||
__eth_end__ = .;
|
||||
} > eth_ram
|
||||
|
||||
}
|
|
@ -65,11 +65,10 @@
|
|||
/*
|
||||
* Memory attributes settings.
|
||||
*/
|
||||
// Disable ChibiOS memory protection which is fixed to SRAM1-3
|
||||
#define STM32_NOCACHE_ENABLE FALSE
|
||||
//#define STM32_NOCACHE_MPU_REGION MPU_REGION_6
|
||||
//#define STM32_NOCACHE_RBAR 0x24000000U
|
||||
//#define STM32_NOCACHE_RASR MPU_RASR_SIZE_16K
|
||||
#define STM32_NOCACHE_ENABLE TRUE
|
||||
#define STM32_NOCACHE_MPU_REGION MPU_REGION_6
|
||||
#define STM32_NOCACHE_RBAR 0x30040000U
|
||||
#define STM32_NOCACHE_RASR MPU_RASR_SIZE_32K
|
||||
|
||||
// enable memory protection on SRAM4, used for bdshot
|
||||
#define STM32_NOCACHE_MPU_REGION_1 MPU_REGION_5
|
||||
|
|
|
@ -30,7 +30,7 @@ mcu = {
|
|||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x24000000, 512, 4), # AXI SRAM.
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x30040000, 32, 0), # SRAM3.
|
||||
#(0x30040000, 32, 0), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
|
@ -40,7 +40,7 @@ mcu = {
|
|||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x30040000, 32, 0), # SRAM3.
|
||||
#(0x30040000, 32, 0), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
|
@ -52,10 +52,11 @@ mcu = {
|
|||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x30040000, 32, 0), # SRAM3.
|
||||
#(0x30040000, 32, 0), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
'ETHERNET_RAM' : (0x30040000, 32, 0), # SRAM3
|
||||
'EXPECTED_CLOCK' : 400000000,
|
||||
|
||||
'EXPECTED_CLOCKS' : [
|
||||
|
|
|
@ -33,7 +33,6 @@ mcu = {
|
|||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x30040000, 32, 0), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
|
@ -42,7 +41,6 @@ mcu = {
|
|||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x20000000, 64, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x24000000, 128, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x30040000, 32, 0), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
'INSTRUCTION_RAM' : (0x00000400, 63), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
|
@ -57,10 +55,10 @@ mcu = {
|
|||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x30040000, 32, 0), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
'ETHERNET_RAM' : (0x30040000, 32, 0), # SRAM3
|
||||
'EXPECTED_CLOCK' : 400000000,
|
||||
|
||||
# this MCU has M7 instructions and hardware double precision
|
||||
|
|
Loading…
Reference in New Issue