Browse Source

HAL_ChibiOS: moved MCU config to python database

this moves the key MCU config variables related to memory to the
python MCU database, allowing the hwdef.dat to be considerably simpler
mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
c273b23940
  1. 3
      libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat
  2. 3
      libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat
  3. 3
      libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef.dat
  4. 22
      libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c
  5. 6
      libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.c
  6. 3
      libraries/AP_HAL_ChibiOS/hwdef/crazyflie2/hwdef.dat
  7. 3
      libraries/AP_HAL_ChibiOS/hwdef/f405-min/hwdef.dat
  8. 2
      libraries/AP_HAL_ChibiOS/hwdef/f4by-ch/hwdef.dat
  9. 15
      libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat
  10. 3
      libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef.dat
  11. 3
      libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef.dat
  12. 3
      libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat
  13. 3
      libraries/AP_HAL_ChibiOS/hwdef/revo-mini/hwdef.dat
  14. 16
      libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F405xx.py
  15. 16
      libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F407xx.py
  16. 12
      libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py
  17. 16
      libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F427xx.py
  18. 18
      libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F745xx.py
  19. 18
      libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F767xx.py
  20. 46
      libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
  21. 2
      libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat
  22. 2
      libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412/hwdef.dat
  23. 4
      libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef.dat

3
libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat

@ -7,9 +7,6 @@ @@ -7,9 +7,6 @@
# MCU class and specific type
MCU STM32F4xx STM32F405xx
RAM_SIZE_KB 128
CCM_RAM_SIZE_KB 64
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_KAKUTEF4
# board ID for firmware load

3
libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat

@ -9,9 +9,6 @@ @@ -9,9 +9,6 @@
# MCU class and specific type
MCU STM32F4xx STM32F405xx
RAM_SIZE_KB 128
CCM_RAM_SIZE_KB 64
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_MATEKF405
# board ID for firmware load

3
libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef.dat

@ -22,9 +22,6 @@ STM32_ST_USE_TIMER 5 @@ -22,9 +22,6 @@ STM32_ST_USE_TIMER 5
FLASH_SIZE_KB 1024
FLASH_RESERVE_START_KB 64
CCM_RAM_SIZE_KB 64
RAM_SIZE_KB 128
# order of I2C buses
I2C_ORDER I2C2

22
libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c

@ -33,15 +33,12 @@ @@ -33,15 +33,12 @@
#define MIN_ALIGNMENT 8
#if defined(CCM_RAM_SIZE)
#ifndef CCM_BASE_ADDRESS
#define CCM_BASE_ADDRESS 0x10000000
#endif
#if defined(CCM_RAM_SIZE_KB)
static memory_heap_t ccm_heap;
static bool ccm_heap_initialised = false;
#endif
#if defined(DTCM_RAM_SIZE) && defined(DTCM_BASE_ADDRESS)
#if defined(DTCM_RAM_SIZE_KB)
static memory_heap_t dtcm_heap;
static bool dtcm_heap_initialised = false;
#endif
@ -49,10 +46,10 @@ static bool dtcm_heap_initialised = false; @@ -49,10 +46,10 @@ static bool dtcm_heap_initialised = false;
void *malloc_ccm(size_t size)
{
void *p = NULL;
#if defined(CCM_RAM_SIZE)
#if defined(CCM_RAM_SIZE_KB)
if (!ccm_heap_initialised) {
ccm_heap_initialised = true;
chHeapObjectInit(&ccm_heap, (void *)CCM_BASE_ADDRESS, CCM_RAM_SIZE*1024);
chHeapObjectInit(&ccm_heap, (void *)CCM_BASE_ADDRESS, CCM_RAM_SIZE_KB*1024);
}
p = chHeapAllocAligned(&ccm_heap, size, CH_HEAP_ALIGNMENT);
if (p != NULL) {
@ -67,10 +64,10 @@ void *malloc_ccm(size_t size) @@ -67,10 +64,10 @@ void *malloc_ccm(size_t size)
void *malloc_dtcm(size_t size)
{
void *p = NULL;
#if defined(DTCM_RAM_SIZE)
#if defined(DTCM_RAM_SIZE_KB)
if (!dtcm_heap_initialised) {
dtcm_heap_initialised = true;
chHeapObjectInit(&dtcm_heap, (void *)DTCM_BASE_ADDRESS, DTCM_RAM_SIZE*1024);
chHeapObjectInit(&dtcm_heap, (void *)DTCM_BASE_ADDRESS, DTCM_RAM_SIZE_KB*1024);
}
p = chHeapAllocAligned(&dtcm_heap, size, CH_HEAP_ALIGNMENT);
if (p != NULL) {
@ -114,9 +111,10 @@ void *malloc(size_t size) @@ -114,9 +111,10 @@ void *malloc(size_t size)
*/
void *malloc_dma(size_t size)
{
#if defined(DTCM_RAM_SIZE)
#if defined(DTCM_RAM_SIZE_KB)
return malloc_dtcm(size);
#else
// if we don't have DTCM memory then assume that main heap is DMA-safe
void *p = chHeapAllocAligned(NULL, size, MIN_ALIGNMENT);
if (p) {
memset(p, 0, size);
@ -149,13 +147,13 @@ size_t mem_available(void) @@ -149,13 +147,13 @@ size_t mem_available(void)
// we also need to add in memory that is not yet allocated to the heap
totalp += chCoreGetStatusX();
#if defined(CCM_RAM_SIZE)
#if defined(CCM_RAM_SIZE_KB)
size_t ccm_available = 0;
chHeapStatus(&ccm_heap, &ccm_available, NULL);
totalp += ccm_available;
#endif
#if defined(DTCM_RAM_SIZE) && defined(DTCM_BASE_ADDRESS)
#if defined(DTCM_RAM_SIZE_KB)
size_t dtcm_available = 0;
chHeapStatus(&dtcm_heap, &dtcm_available, NULL);
totalp += dtcm_available;

6
libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.c

@ -178,12 +178,6 @@ static USBDescriptor vcom_strings[] = { @@ -178,12 +178,6 @@ static USBDescriptor vcom_strings[] = {
{0, NULL}, // version
};
// start of 12 byte CPU ID
#ifndef UDID_START
#define UDID_START 0x1FFF7A10
#endif
/*
handle substitution of variables in strings for USB descriptors
*/

3
libraries/AP_HAL_ChibiOS/hwdef/crazyflie2/hwdef.dat

@ -4,9 +4,6 @@ @@ -4,9 +4,6 @@
# MCU class and specific type
MCU STM32F4xx STM32F405xx
RAM_SIZE_KB 128
CCM_RAM_SIZE_KB 64
# board ID for firmware load
APJ_BOARD_ID 70

3
libraries/AP_HAL_ChibiOS/hwdef/f405-min/hwdef.dat

@ -4,9 +4,6 @@ @@ -4,9 +4,6 @@
# MCU class and specific type
MCU STM32F4xx STM32F405xx
RAM_SIZE_KB 128
CCM_RAM_SIZE_KB 64
# board ID for firmware load
APJ_BOARD_ID 3

2
libraries/AP_HAL_ChibiOS/hwdef/f4by-ch/hwdef.dat

@ -3,8 +3,6 @@ @@ -3,8 +3,6 @@
# MCU class and specific type
MCU STM32F4xx STM32F407xx
RAM_SIZE_KB 128
CCM_RAM_SIZE_KB 64
# board ID for firmware load
APJ_BOARD_ID 20

15
libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat

@ -5,13 +5,6 @@ @@ -5,13 +5,6 @@
# but without the TFT interface
MCU STM32F7xx STM32F767xx
# use SRAM1 and SRAM2 as main memory, giving the fastest possible
# memory. Use DTCM for DMA memory as it needs no data cache operations
RAM_SIZE_KB 384
RAM_BASE_ADDRESS 0x20020000
define DTCM_RAM_SIZE 128
define DTCM_BASE_ADDRESS 0x20000000
# crystal frequency
OSCILLATOR_HZ 16000000
@ -245,10 +238,10 @@ define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE @@ -245,10 +238,10 @@ define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
DMA_PRIORITY SDMMC* UART8* ADC* SPI* TIM*
#define CH_DBG_ENABLE_ASSERTS TRUE
#define CH_DBG_ENABLE_CHECKS TRUE
#define CH_DBG_SYSTEM_STATE_CHECK TRUE
#define CH_DBG_ENABLE_STACK_CHECK TRUE
define CH_DBG_ENABLE_ASSERTS TRUE
define CH_DBG_ENABLE_CHECKS TRUE
define CH_DBG_SYSTEM_STATE_CHECK TRUE
define CH_DBG_ENABLE_STACK_CHECK TRUE
# define HAL_SPI_CHECK_CLOCK_FREQ 1

3
libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef.dat

@ -28,9 +28,6 @@ FLASH_RESERVE_START_KB 16 @@ -28,9 +28,6 @@ FLASH_RESERVE_START_KB 16
# space to reserve for storage at end of flash
FLASH_RESERVE_END_KB 0
# this board has 64k of CCM memory
CCM_RAM_SIZE_KB 64
# serial port for stdout
STDOUT_SERIAL SD7
STDOUT_BAUDRATE 57600

3
libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef.dat

@ -4,9 +4,6 @@ @@ -4,9 +4,6 @@
# MCU class and specific type
MCU STM32F4xx STM32F405xx
RAM_SIZE_KB 128
CCM_RAM_SIZE_KB 64
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_MINIPIX
# board ID for firmware load

3
libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat

@ -22,9 +22,6 @@ STM32_ST_USE_TIMER 5 @@ -22,9 +22,6 @@ STM32_ST_USE_TIMER 5
FLASH_SIZE_KB 1024
FLASH_RESERVE_START_KB 64
CCM_RAM_SIZE_KB 64
RAM_SIZE_KB 128
# order of I2C buses
I2C_ORDER I2C2

3
libraries/AP_HAL_ChibiOS/hwdef/revo-mini/hwdef.dat

@ -4,9 +4,6 @@ @@ -4,9 +4,6 @@
# MCU class and specific type
MCU STM32F4xx STM32F405xx
RAM_SIZE_KB 128
CCM_RAM_SIZE_KB 64
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_REVOMINI
# board ID for firmware load

16
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F405xx.py

@ -10,6 +10,22 @@ build = { @@ -10,6 +10,22 @@ build = {
"CHIBIOS_PLATFORM_MK" : "os/hal/ports/STM32/STM32F4xx/platform.mk"
}
# MCU parameters
mcu = {
# location of MCU serial number
'UDID_START' : 0x1FFF7A10,
# base address of main memory
'RAM_BASE_ADDRESS' : 0x20000000,
# size of main memory
'RAM_SIZE_KB' : 128,
# CCM ram address and size
'CCM_BASE_ADDRESS' : 0x10000000,
'CCM_RAM_SIZE_KB' : 64,
}
AltFunction_map = {
# format is PIN:FUNCTION : AFNUM
# extracted from tabula-AF-F405.csv

16
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F407xx.py

@ -10,6 +10,22 @@ build = { @@ -10,6 +10,22 @@ build = {
"CHIBIOS_PLATFORM_MK" : "os/hal/ports/STM32/STM32F4xx/platform.mk"
}
# MCU parameters
mcu = {
# location of MCU serial number
'UDID_START' : 0x1FFF7A10,
# base address of main memory
'RAM_BASE_ADDRESS' : 0x20000000,
# size of main memory
'RAM_SIZE_KB' : 128,
# CCM ram address and size
'CCM_BASE_ADDRESS' : 0x10000000,
'CCM_RAM_SIZE_KB' : 64,
}
DMA_Map = {
# format is (DMA_TABLE, StreamNum, Channel)
# extracted from tabula-STM32F4x7-dma.csv

12
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py

@ -10,6 +10,18 @@ build = { @@ -10,6 +10,18 @@ build = {
"CHIBIOS_PLATFORM_MK" : "os/hal/ports/STM32/STM32F4xx/platform.mk"
}
# MCU parameters
mcu = {
# location of MCU serial number
'UDID_START' : 0x1FFF7A10,
# base address of main memory
'RAM_BASE_ADDRESS' : 0x20000000,
# size of main memory
'RAM_SIZE_KB' : 256
}
DMA_Map = {
# format is (DMA_TABLE, StreamNum, Channel)
# extracted from tabula-stm32f412-ref-manual-196.csv

16
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F427xx.py

@ -10,6 +10,22 @@ build = { @@ -10,6 +10,22 @@ build = {
"CHIBIOS_PLATFORM_MK" : "os/hal/ports/STM32/STM32F4xx/platform.mk"
}
# MCU parameters
mcu = {
# location of MCU serial number
'UDID_START' : 0x1FFF7A10,
# base address of main memory
'RAM_BASE_ADDRESS' : 0x20000000,
# size of main memory
'RAM_SIZE_KB' : 192,
# CCM ram address and size
'CCM_BASE_ADDRESS' : 0x10000000,
'CCM_RAM_SIZE_KB' : 64,
}
DMA_Map = {
# format is (DMA_TABLE, StreamNum, Channel)
# extracted from tabula-STM32F4x7-dma.csv

18
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F745xx.py

@ -10,6 +10,24 @@ build = { @@ -10,6 +10,24 @@ build = {
"CHIBIOS_PLATFORM_MK" : "os/hal/ports/STM32/STM32F7xx/platform.mk"
}
# MCU parameters
mcu = {
# location of MCU serial number
'UDID_START' : 0x1FF0F420,
# base address of main memory. We use SRAM1/SRAM2 as main memory
# for maximum speed (using the dcache). DMA will be done from DTCM
# memory
'RAM_BASE_ADDRESS' : 0x20010000,
# size of main memory
'RAM_SIZE_KB' : 256,
# DTCM ram address and size
'DTCM_BASE_ADDRESS' : 0x20000000,
'DTCM_RAM_SIZE_KB' : 64,
}
DMA_Map = {
# format is (DMA_TABLE, StreamNum, Channel)
# extracted from tabula-STM32F745-222.csv

18
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F767xx.py

@ -25,6 +25,24 @@ pincount = { @@ -25,6 +25,24 @@ pincount = {
}
# MCU parameters
mcu = {
# location of MCU serial number
'UDID_START' : 0x1FF0F420,
# base address of main memory. We use SRAM1/SRAM2 as main memory
# for maximum speed (using the dcache). DMA will be done from DTCM
# memory
'RAM_BASE_ADDRESS' : 0x20020000,
# size of main memory
'RAM_SIZE_KB' : 384,
# DTCM ram address and size
'DTCM_BASE_ADDRESS' : 0x20000000,
'DTCM_RAM_SIZE_KB' : 128,
}
DMA_Map = {
# format is (DMA_TABLE, StreamNum, Channel)
"ADC1" : [(2,0,0),(2,4,0)],

46
libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py

@ -322,6 +322,17 @@ def get_config(name, column=0, required=True, default=None, type=None, spaces=Fa @@ -322,6 +322,17 @@ def get_config(name, column=0, required=True, default=None, type=None, spaces=Fa
error("Badly formed config value %s (got %s)" % (name, ret))
return ret
def get_mcu_config(name, required=False):
'''get a value from the mcu dictionary'''
lib = get_mcu_lib(mcu_type)
if not hasattr(lib, 'mcu'):
error("Missing mcu config for %s" % mcu_type)
if not name in lib.mcu:
if required:
error("Missing required mcu config %s for %s" % (name, mcu_type))
return None
return lib.mcu[name]
def enable_can(f):
'''setup for a CAN enabled board'''
f.write('#define HAL_WITH_UAVCAN 1\n')
@ -384,19 +395,36 @@ def write_mcu_config(f): @@ -384,19 +395,36 @@ def write_mcu_config(f):
flash_size = get_config('FLASH_SIZE_KB', type=int)
f.write('#define BOARD_FLASH_SIZE %u\n' % flash_size)
f.write('#define CRT1_AREAS_NUMBER 1\n')
if mcu_type in ['STM32F427xx', 'STM32F407xx','STM32F405xx']:
def_ccm_size = 64
else:
def_ccm_size = None
ccm_size = get_config(
'CCM_RAM_SIZE_KB', default=def_ccm_size, required=False, type=int)
# get core-coupled-memory if available (not be DMA capable)
ccm_size = get_mcu_config('CCM_RAM_SIZE_KB')
if ccm_size is not None:
f.write('#define CCM_RAM_SIZE %u\n' % ccm_size)
f.write('\n// core-coupled memory\n')
f.write('#define CCM_RAM_SIZE_KB %u\n' % ccm_size)
f.write('#define CCM_BASE_ADDRESS 0x%08x\n' % get_mcu_config('CCM_BASE_ADDRESS', True))
# get DTCM memory if available (DMA-capable with no cache flush/invalidate)
dtcm_size = get_mcu_config('DTCM_RAM_SIZE_KB')
if dtcm_size is not None:
f.write('\n// DTCM memory\n')
f.write('#define DTCM_RAM_SIZE_KB %u\n' % dtcm_size)
f.write('#define DTCM_BASE_ADDRESS 0x%08x\n' % get_mcu_config('DTCM_BASE_ADDRESS', True))
flash_reserve_start = get_config(
'FLASH_RESERVE_START_KB', default=16, type=int)
f.write('\n// location of loaded firmware\n')
f.write('#define FLASH_LOAD_ADDRESS 0x%08x\n' % flash_reserve_start)
f.write('\n')
ram_size_kb = get_mcu_config('RAM_SIZE_KB', True)
ram_base_address = get_mcu_config('RAM_BASE_ADDRESS', True)
f.write('// main memory size and address\n')
f.write('#define HAL_RAM_SIZE_KB %uU\n' % ram_size_kb)
f.write('#define HAL_RAM_BASE_ADDRESS 0x%08x\n' % ram_base_address)
f.write('\n// CPU serial number (12 bytes)\n')
f.write('#define UDID_START 0x%08x\n\n' % get_mcu_config('UDID_START', True))
lib = get_mcu_lib(mcu_type)
build_info = lib.build
# setup build variables
@ -415,8 +443,8 @@ def write_ldscript(fname): @@ -415,8 +443,8 @@ def write_ldscript(fname):
flash_reserve_end = get_config('FLASH_RESERVE_END_KB', default=0, type=int)
# ram size
ram_size = get_config('RAM_SIZE_KB', default=192, type=int)
ram_base = get_config('RAM_BASE_ADDRESS', default=0x20000000, type=int)
ram_size = get_mcu_config('RAM_SIZE_KB', True)
ram_base = get_mcu_config('RAM_BASE_ADDRESS', True)
flash_base = 0x08000000 + flash_reserve_start * 1024
flash_length = flash_size - (flash_reserve_start + flash_reserve_end)

2
libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat

@ -23,8 +23,6 @@ STM32_PWM_USE_TIM3 TRUE @@ -23,8 +23,6 @@ STM32_PWM_USE_TIM3 TRUE
# board voltage
STM32_VDD 330U
RAM_SIZE_KB 256
# flash size
FLASH_SIZE_KB 1024

2
libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412/hwdef.dat

@ -23,8 +23,6 @@ STM32_PWM_USE_TIM3 TRUE @@ -23,8 +23,6 @@ STM32_PWM_USE_TIM3 TRUE
# board voltage
STM32_VDD 330U
RAM_SIZE_KB 256
# flash size
FLASH_SIZE_KB 1024

4
libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef.dat

@ -4,10 +4,6 @@ @@ -4,10 +4,6 @@
# MCU class and specific type
MCU STM32F4xx STM32F405xx
RAM_SIZE_KB 128
CCM_RAM_SIZE_KB 64
# board ID for firmware load
APJ_BOARD_ID 70

Loading…
Cancel
Save