mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
HAL_ChibiOS: default UDID_START to UID_BASE
This commit is contained in:
parent
2dc4c50953
commit
36d5c98e96
@ -12,9 +12,6 @@ build = {
|
|||||||
|
|
||||||
# MCU parameters
|
# MCU parameters
|
||||||
mcu = {
|
mcu = {
|
||||||
# location of MCU serial number
|
|
||||||
'UDID_START' : 0x1FF07A10,
|
|
||||||
|
|
||||||
# ram map, as list of (address, size-kb, flags)
|
# ram map, as list of (address, size-kb, flags)
|
||||||
# flags of 1 means DMA-capable
|
# flags of 1 means DMA-capable
|
||||||
# flags of 2 means faster memory for CPU intensive work
|
# flags of 2 means faster memory for CPU intensive work
|
||||||
|
@ -779,7 +779,11 @@ def write_mcu_config(f):
|
|||||||
f.write('#define HAL_RAM_RESERVE_START 0x%08x\n' % ram_reserve_start)
|
f.write('#define HAL_RAM_RESERVE_START 0x%08x\n' % ram_reserve_start)
|
||||||
|
|
||||||
f.write('\n// CPU serial number (12 bytes)\n')
|
f.write('\n// CPU serial number (12 bytes)\n')
|
||||||
f.write('#define UDID_START 0x%08x\n\n' % get_mcu_config('UDID_START', True))
|
udid_start = get_mcu_config('UDID_START')
|
||||||
|
if udid_start is None:
|
||||||
|
f.write('#define UDID_START UID_BASE\n\n')
|
||||||
|
else:
|
||||||
|
f.write('#define UDID_START 0x%08x\n\n' % udid_start)
|
||||||
|
|
||||||
f.write('\n// APJ board ID (for bootloaders)\n')
|
f.write('\n// APJ board ID (for bootloaders)\n')
|
||||||
f.write('#define APJ_BOARD_ID %s\n' % get_config('APJ_BOARD_ID'))
|
f.write('#define APJ_BOARD_ID %s\n' % get_config('APJ_BOARD_ID'))
|
||||||
|
Loading…
Reference in New Issue
Block a user