New HAL and SimpleMAC for STM32W108.

This commit is contained in:
Salvatore Pitrulli 2011-03-21 13:11:52 +01:00
parent c9af578eab
commit eb588f1aec
89 changed files with 1503 additions and 1883 deletions

View file

@ -1,24 +1,221 @@
/** @file board.h
* @brief Header file x STM32W108 Kits boards
* @brief Header file x STM32W108 Kits boards abstraction.
* See @ref board for documentation.
*
*
* See hal/micro/cortexm3/stm32w108/board.h for source code.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef _BOARD_H_
#define _BOARD_H_
#ifdef BOARD_MB851
/** @addtogroup board
* @brief ST board abstraction layer
*
* This header defines API and data structures to handle ST boards with thei associated resources
* on algorithm behavior.
* See hal/micro/cortexm3/stm32w108/board.h for source code.
*@{
*/
/**
* @brief Define the number of LEDs in the specific board revision
*/
#define LEDS_MB851A 2
/**
* @brief Define the number of LEDs in the specific board revision
*/
#define LEDS_MB851B 2
/**
* @brief Define the number of LEDs in the specific board revision
*/
#define LEDS_MB851C 2
/**
* @brief Define the number of LEDs in the specific board revision
*/
#define LEDS_MB954A 2
/**
* @brief Define the number of LEDs in the specific board revision
*/
#define LEDS_MB954B 2
/**
* @brief Define the number of LEDs in the specific board revision
*/
#define LEDS_MB950A 2
/**
* @brief Define the number of LEDs in the specific board revision
*/
#define LEDS_MB951A 2
/**
* @brief Define the number of user buttons in the specific board revision
*/
#define BUTTONS_MB851A 1
/**
* @brief Define the number of user buttons in the specific board revision
*/
#define BUTTONS_MB851B 1
/**
* @brief Define the number of user buttons in the specific board revision
*/
#define BUTTONS_MB851C 1
/**
* @brief Define the number of user buttons in the specific board revision
*/
#define BUTTONS_MB954A 1
/**
* @brief Define the number of user buttons in the specific board revision
*/
#define BUTTONS_MB954B 1
/**
* @brief Define the number of user buttons in the specific board revision
*/
#define BUTTONS_MB950A 5
/**
* @brief Define the number of user buttons in the specific board revision
*/
#define BUTTONS_MB951A 0
/**
* @brief Data structure for led description
*/
typedef struct LedResourceStruct {
/** Name of the LED as printed in the board */
char *name;
/** GPIO port associated with the LED */
int8u gpioPort;
/** GPIO pin associated with the LED */
int8u gpioPin;
} LedResourceType;
typedef LedResourceType InfraRedLedResourceType;
/**
* @brief Data structure for button description
*/
typedef struct ButtonResourceStruct {
/** Name of the button as printed in the board */
char *name;
/** GPIO port associated with the button */
int8u gpioPort;
/** GPIO pin associated with the button */
int8u gpioPin;
} ButtonResourceType;
/**
* @brief Data structure for MEMS description
*/
typedef struct MemsResourceStruct {
/** Name of the MEMS device */
char *name;
/** Serial communication port associated with the MEMS */
int8u scPort;
} MemsResourceType;
/**
* @brief Data structure for temperature sensor description
*/
typedef struct TempSensorResourceStruct {
/** Name of the temperature sensor device */
char *name;
/** GPIO port associated with the sensor */
int8u gpioPort;
/** GPIO pin associated with the sensor */
int8u gpioPin;
/** Flag to indicate whether the ADC range extension bug fix is implemented */
boolean adcFix;
} TempSensorResourceType;
/**
* @brief Data structure for board user I/O
*/
typedef struct BoardIOStruct {
/** Pointer to LED resources */
const LedResourceType *leds;
/** Pointer to button resources */
const ButtonResourceType *buttons;
} BoardIOType;
/**
* @brief Flag to indicate if MEMS is present
*/
#define BOARD_HAS_MEMS (1 << 0)
/**
* @brief Flag to indicate if temeprature sensor is present
*/
#define BOARD_HAS_TEMP_SENSOR (1 << 1)
/**
* @brief Flag to indicate if external power amplifier is present
*/
#define BOARD_HAS_PA (1 << 2)
/**
* @brief Flag to indicate if EEPROM is present
*/
#define BOARD_HAS_EEPROM (1 << 3)
/**
* @brief Flag to indicate if FTDI is used as PC interface
*/
#define BOARD_HAS_FTDI (1 << 4)
/**
* @brief Flag to indicate if STM32F is used as PC interface
*/
#define BOARD_HAS_STM32F (1 << 5)
/**
* @brief Data structure describing board features
*/
typedef struct BoardResourcesStruct {
const char *name;
const int32u flags;
/** Number of buttons */
int8u buttons;
/** Number of leds */
int8u leds;
/** Board I/O description */
const BoardIOType *io;
/** Board infrared led description */
const InfraRedLedResourceType* infraredLed;
/** Board infrared MEMS description */
const MemsResourceType *mems;
/** Board infrared temeprature sensor description */
const TempSensorResourceType *temperatureSensor;
} BoardResourcesType;
extern BoardResourcesType const *boardDescription;
// Generic definitions
#define GPIO_PxCLR_BASE (GPIO_PACLR_ADDR)
#define GPIO_PxSET_BASE (GPIO_PASET_ADDR)
#define GPIO_PxOUT_BASE (GPIO_PAOUT_ADDR)
#define GPIO_PxIN_BASE (GPIO_PAIN_ADDR)
// Each port is offset from the previous port by the same amount
#define GPIO_Px_OFFSET (GPIO_PBCFGL_ADDR-GPIO_PACFGL_ADDR)
/* leds definitions */
#define LED_D1 PORTB_PIN(6)
#define LED_D3 PORTB_PIN(5)
#define LED_D1 PORTx_PIN(boardDescription->io->leds[0].gpioPort, boardDescription->io->leds[0].gpioPin) //PORTB_PIN(6)
#define LED_D3 PORTx_PIN(boardDescription->io->leds[1].gpioPort, boardDescription->io->leds[1].gpioPin) // PORTB_PIN(5)
#define DUMMY_LED 0xff
/** Description buttons definition */
#define BUTTON_S1 PORTA_PIN(7)
#define BUTTON_S1_INPUT_GPIO GPIO_PAIN
#define BUTTON_S1_OUTPUT_GPIO GPIO_PAOUT
#define BUTTON_S1_GPIO_PIN PA7_BIT
#define BUTTON_S1_WAKE_SOURCE 0x00000080
#define BUTTON_Sn(n) (PORTx_PIN(boardDescription->io->buttons[n].gpioPort, boardDescription->io->buttons[n].gpioPin))
#define BUTTON_Sn_WAKE_SOURCE(n) (1 << ((boardDescription->io->buttons[n].gpioPin) + (8 * (boardDescription->io->buttons[n].gpioPort >> 3))))
#define BUTTON_INPUT_GPIO(port) *((volatile int32u *) (GPIO_PxIN_BASE + GPIO_Px_OFFSET * port))
#define DUMMY_BUTTON 0xff
#define BUTTON_S1 (boardDescription->buttons>0 ? BUTTON_Sn(0): DUMMY_BUTTON)
#define BUTTON_S2 (boardDescription->buttons>1 ? BUTTON_Sn(1): DUMMY_BUTTON)
#define BUTTON_S3 (boardDescription->buttons>2 ? BUTTON_Sn(2): DUMMY_BUTTON)
#define BUTTON_S4 (boardDescription->buttons>3 ? BUTTON_Sn(3): DUMMY_BUTTON)
#define BUTTON_S5 (boardDescription->buttons>4 ? BUTTON_Sn(4): DUMMY_BUTTON)
#define BUTTON_S1_WAKE_SOURCE (boardDescription->buttons>0 ? BUTTON_Sn_WAKE_SOURCE(0): 0)
#define BUTTON_S2_WAKE_SOURCE (boardDescription->buttons>1 ? BUTTON_Sn_WAKE_SOURCE(1): 0)
#define BUTTON_S3_WAKE_SOURCE (boardDescription->buttons>2 ? BUTTON_Sn_WAKE_SOURCE(2): 0)
#define BUTTON_S4_WAKE_SOURCE (boardDescription->buttons>3 ? BUTTON_Sn_WAKE_SOURCE(3): 0)
#define BUTTON_S5_WAKE_SOURCE (boardDescription->buttons>4 ? BUTTON_Sn_WAKE_SOURCE(4): 0)
/** Description uart definition */
#define UART_TX PORTB_PIN(1)
@ -26,8 +223,37 @@
#define UART_RX_WAKE_SOURCE 0x00000400
/** Description temperature sensor GPIO */
#define TEMPERATURE_SENSOR_GPIO PORTB_PIN(7)
#endif /* BOARD_MB851 */
#define TEMPERATURE_SENSOR_GPIO PORTx_PIN(boardDescription->temperatureSensor->gpioPort, boardDescription->temperatureSensor->gpioPin) // PORTB_PIN(7)
/** @brief Return pointer to board description structure
*
*
* @return Pointer to board description structure
*/
BoardResourcesType const *halBoardGetDescription(void);
/**
* @brief Initialize the board description data structure after
* autodetect of the boards based on the CIB Board name field
* content. In case of invalid CIB data it will default to MB851A.
* Customer normally needs to modify this file to adapt it to their specific board.
*/
void halBoardInit(void);
/**
* @brief Perform board specific action to power up the system.
* This code depends on the actual board features and configure
* the stm32w and on board devices for proper operation.
* Customer normally needs to modify this file to adapt it to their specific board.
*/
void halBoardPowerUp(void);
/**
* @brief Perform board specific action to power down the system, usually before going to deep sleep.
* This code depends on the actual board features and configure
* the stm32w and on board devices for minimal power consumption.
* Customer normally needs to modify this file to adapt it to their specific board.
*/
void halBoardPowerDown(void);
#endif /* _BOARD_H_ */
/** @} // END addtogroup
*/

View file

@ -20,8 +20,8 @@
#include <stdio.h>
#include <sys/stat.h>
#define RESERVED 0
//#define DUMMY_MALLOC
#define IAP_BOOTLOADER_APP_SWITCH_SIGNATURE 0xb001204d
#define IAP_BOOTLOADER_MODE_UART 0
/* Includes ----------------------------------------------------------------------*/
#include PLATFORM_HEADER
void NMI_Handler(void);
@ -72,7 +72,7 @@ VAR_AT_SEGMENT(const HalFixedAddressTableType halFixedAddressTable, __FAT__);
/* function prototypes ------------------------------------------------------*/
void Reset_Handler(void) __attribute__((__interrupt__));
extern int main(void);
extern void halInternalSwitchToXtal(void);
/******************************************************************************
*
@ -121,6 +121,20 @@ void (* const g_pfnVectors[])(void) =
halDebugIsr, // 32
};
static void setStackPointer(int32u address) __attribute__((noinline));
static void setStackPointer(int32u address)
{
// This code is needed to generate the instruction below
// that GNU ASM is refusing to add
// asm("MOVS SP, r0");
asm(".short 0x4685");
}
static const int16u blOffset[] = {
0x0715 - 0x03ad - 0x68,
0x0719 - 0x03ad - 0x6C
};
/*******************************************************************************
* Function Name : Reset_Handler
* Description : This is the code that gets called when the processor first starts execution
@ -244,6 +258,21 @@ void Reset_Handler(void)
while(1) { ; }
}
//USART bootloader software activation check
if ((*((int32u *)RAM_BOTTOM) == IAP_BOOTLOADER_APP_SWITCH_SIGNATURE) && (*((int8u *)(RAM_BOTTOM+4)) == IAP_BOOTLOADER_MODE_UART)){
int8u cut = *(volatile int8u *) 0x08040798;
int16u offset = 0;
typedef void (*EntryPoint)(void);
offset = (halFixedAddressTable.baseTable.version == 3) ? blOffset[cut - 2] : 0;
*((int32u *)RAM_BOTTOM) = 0;
if (offset) {
halInternalSwitchToXtal();
}
EntryPoint entryPoint = (EntryPoint)(*(int32u *)(FIB_BOTTOM+4) - offset);
setStackPointer(*(int32u *)FIB_BOTTOM);
entryPoint();
}
INTERRUPTS_OFF();
asm("CPSIE i");
@ -302,12 +331,10 @@ caddr_t _sbrk ( int incr )
return (caddr_t) prev_heap;
}
#else
# ifdef DUMMY_MALLOC
caddr_t _sbrk ( int incr )
{
return NULL;
}
# endif
#endif
int _lseek (int file,
int ptr,

View file

@ -13,71 +13,65 @@ GROUP(
These are used by the startup in order to allocate stacks for the different modes.
*/
__Stack_Size = 0x500 ;
__Stack_Size = 0x400 ;
PROVIDE ( _Stack_Size = __Stack_Size ) ;
__Stack_Init = _estack - __Stack_Size ;
__Stack_Init = 0x20000000;
_estack = __Stack_Init + __Stack_Size;
/*"PROVIDE" allows to easily override these values from an object file or the commmand line.*/
PROVIDE ( _Stack_Init = __Stack_Init ) ;
/*
There will be a link error if there is not this amount of RAM free at the end.
*/
_Minimum_Stack_Size = 0x500 ;
/*
this sends all unreferenced IRQHandlers to reset
*/
PROVIDE(Default_Handler = 0 );
PROVIDE(NMI_Handler = Default_Handler );
PROVIDE(HardFault_Handler = Default_Handler );
PROVIDE(MemManage_Handler = Default_Handler );
PROVIDE(BusFault_Handler = Default_Handler );
PROVIDE(UsageFault_Handler = Default_Handler );
PROVIDE(SVC_Handler = Default_Handler );
PROVIDE(DebugMonitor_Handler = Default_Handler );
PROVIDE(PendSV_Handler = Default_Handler );
PROVIDE(SysTick_Handler = Default_Handler );
PROVIDE(halTimer1Isr = Default_Handler );
PROVIDE(halTimer2Isr = Default_Handler );
PROVIDE(halManagementIsr = Default_Handler );
PROVIDE(halBaseBandIsr = Default_Handler );
PROVIDE(halSleepTimerIsr = Default_Handler );
PROVIDE(halSc1Isr = Default_Handler );
PROVIDE(halSc2Isr = Default_Handler );
PROVIDE(halSecurityIsr = Default_Handler );
PROVIDE(halStackMacTimerIsr = Default_Handler );
PROVIDE(stmRadioTransmitIsr = Default_Handler );
PROVIDE(stmRadioReceiveIsr = Default_Handler );
PROVIDE(halAdcIsr = Default_Handler );
PROVIDE(halIrqAIsr = Default_Handler );
PROVIDE(halIrqBIsr = Default_Handler );
PROVIDE(halIrqCIsr = Default_Handler );
PROVIDE(halIrqDIsr = Default_Handler );
PROVIDE(halDebugIsr = Default_Handler );
/*PROVIDE(stSerialPrintf = printf );*/
PROVIDE(NMI_Handler = 0 );
PROVIDE(HardFault_Handler = 0 );
PROVIDE(MemManage_Handler = 0 );
PROVIDE(BusFault_Handler = 0 );
PROVIDE(UsageFault_Handler = 0 );
PROVIDE(SVC_Handler = 0 );
PROVIDE(DebugMonitor_Handler = 0 );
PROVIDE(PendSV_Handler = 0 );
PROVIDE(SysTick_Handler = 0 );
PROVIDE(halTimer1Isr = 0 );
PROVIDE(halTimer2Isr = 0 );
PROVIDE(halManagementIsr = 0 );
PROVIDE(halBaseBandIsr = 0 );
PROVIDE(halSleepTimerIsr = 0 );
PROVIDE(halSc1Isr = 0 );
PROVIDE(halSc2Isr = 0 );
PROVIDE(halSecurityIsr = 0 );
PROVIDE(halStackMacTimerIsr = 0 );
PROVIDE(stmRadioTransmitIsr = 0 );
PROVIDE(stmRadioReceiveIsr = 0 );
PROVIDE(halAdcIsr = 0 );
PROVIDE(halIrqAIsr = 0 );
PROVIDE(halIrqBIsr = 0 );
PROVIDE(halIrqCIsr = 0 );
PROVIDE(halIrqDIsr = 0 );
PROVIDE(halDebugIsr = 0 );
/******************************************************************************/
/* Peripheral memory map */
/******************************************************************************/
/*this allows to compile the ST lib in "non-debug" mode*/
_BOOTLOADER_SIZE = 0x3000 ;
_ROM_base = DEFINED(ST_BTL) ? (0x08000000 + _BOOTLOADER_SIZE) : 0x08000000 ;
/* include the memory spaces definitions sub-script */
MEMORY
{
RAM_region (xrw) : ORIGIN = 0x20000000, LENGTH = 8K
ROM_region (rx) : ORIGIN = 0x08000000, LENGTH = 128K-3K
NVM_region (rx) : ORIGIN = 0x0801F400, LENGTH = 3K
ROM_region (rx) : ORIGIN = 0x08000000, LENGTH = 128K-2K
NVM_region (rx) : ORIGIN = 0x0801F800, LENGTH = 2K
FIB_region (ra) : ORIGIN = 0x08040000, LENGTH = 2K
}
/* higher address of the user mode stack */
_estack = 0x20002000;
/* Sections management for FLASH mode */
@ -87,9 +81,12 @@ SECTIONS
{
/* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */
.isr_vector :
.isr_vector (DEFINED(ST_BTL) ? (0x08000000 + _BOOTLOADER_SIZE) : 0x08000000) :
{
. = ALIGN(4);
__ApplicationFlashStart = . ;
/* . = . + _ROM_base ;*/
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >ROM_region
@ -113,24 +110,12 @@ SECTIONS
*(.rodata*)
*(.glue_7)
*(.glue_7t)
. = ALIGN(1024);
*(.elf_text)
. = ALIGN(1024);
/*. = ALIGN(4);*/
. = ALIGN(4);
_etext = .;
/* This is used by the startup in order to initialize the .data section */
/* This is used by the startup in order to initialize the .data secion */
_sidata = _etext;
} >ROM_region
.coffee 0x08010000 :
{
_coffee_start = ABSOLUTE(.);
. = ALIGN(1024);
*(.coffeefiles)
. = ORIGIN(NVM_region) - _coffee_start;
} > ROM_region = 0x00
NVM (NOLOAD):
{
. = ALIGN(1024);
@ -146,6 +131,12 @@ SECTIONS
. = ALIGN(4);
} > FIB_region
/*
.FAT (NOLOAD):
{
KEEP(*(.FAT))
} > FIB_region
*/
/* after that it's only debugging information. */
@ -153,10 +144,10 @@ SECTIONS
The program executes knowing that the data is in the RAM
but the loader puts the initial values in the FLASH (inidata).
It is one task of the startup to copy the initial values from FLASH to RAM. */
.data : AT ( _sidata )
.data _estack : AT ( _sidata )
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data section */
/* This is used by the startup in order to initialize the .data secion */
_sdata = . ;
*(.data)
@ -165,9 +156,9 @@ SECTIONS
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_edata = . ;
ASSERT(_sidata + SIZEOF(.data) < LOADADDR(.coffee), ".data section overflow in ROM");
} >RAM_region
/* This is the uninitialized data section */
.bss :
@ -177,6 +168,7 @@ SECTIONS
_sbss = .;
*(.bss)
*(.bss.*)
*(COMMON)
. = ALIGN(4);
@ -186,21 +178,6 @@ SECTIONS
PROVIDE ( end = _ebss );
PROVIDE ( _end = _ebss );
/* This is the user stack section
This is just to check that there is enough RAM left for the User mode stack
It should generate an error if it's full.
*/
._usrstack :
{
. = ALIGN(4);
_susrstack = . ;
. = . + _Minimum_Stack_Size ;
. = ALIGN(4);
_eusrstack = . ;
} >RAM_region
__exidx_start = .;
__exidx_end = .;
@ -247,3 +224,5 @@ SECTIONS
.debug_typenames 0 : { *(.debug_typenames) }
.debug_varnames 0 : { *(.debug_varnames) }
}
__ApplicationFlashEnd = _sidata + (_edata - _sdata);

View file

@ -1,37 +0,0 @@
define symbol __ICFEDIT_intvec_start__ = 0x08000000;
/*-Memory Regions-*/
define symbol __ICFEDIT_region_ROM_start__ = 0x08000000;
define symbol __ICFEDIT_region_ROM_end__ = 0x0800FFFF;
define symbol __ICFEDIT_region_CFS_start__ = 0x08010000; /* Reserved for contiki flash file system. COFFEE_ADDRESS must be changed also in cfs-coffee-arch.h */
define symbol __ICFEDIT_region_CFS_end__ = 0x0801F3FF;
define symbol __ICFEDIT_region_NVM_start__ = 0x0801F400;
define symbol __ICFEDIT_region_NVM_end__ = 0x0801FFFF;
define symbol __ICFEDIT_region_FIB_start__ = 0x08040000;
define symbol __ICFEDIT_region_FIB_end__ = 0x080407FF;
define symbol __ICFEDIT_region_RAM_start__ = 0x20000000;
define symbol __ICFEDIT_region_RAM_end__ = 0x20001FFF;
/*-Sizes-*/
define symbol __ICFEDIT_size_cstack__ = 0x500;
define memory mem with size = 4G;
define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__];
define region CFS_region = mem:[from __ICFEDIT_region_CFS_start__ to __ICFEDIT_region_CFS_end__];
define region NVM_region = mem:[from __ICFEDIT_region_NVM_start__ to __ICFEDIT_region_NVM_end__];
define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__];
define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { };
initialize by copy { readwrite };
do not initialize { section .noinit,
section FAT,
section NVM };
place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec };
place at address mem:__ICFEDIT_region_FIB_start__ { section FAT };
place in ROM_region { readonly };
place in CFS_region { section .coffeefiles };
place in NVM_region { section NVM };
place in RAM_region { readwrite,
block CSTACK };

View file

@ -1,13 +1,21 @@
if( isdefinedsymbol(ST_BTL) ) {
define symbol __ICFEDIT_intvec_start__ = 0x08003000;
define symbol __ICFEDIT_region_ROM_start__ = 0x08003000;
} else {
define symbol __ICFEDIT_intvec_start__ = 0x08000000;
/*-Memory Regions-*/
define symbol __ICFEDIT_region_ROM_start__ = 0x08000000;
}
/*-Memory Regions-*/
define symbol __ICFEDIT_region_ROM_end__ = 0x0801FFFF;
define symbol __ICFEDIT_region_FIB_start__ = 0x08040000;
define symbol __ICFEDIT_region_FIB_end__ = 0x080407FF;
define symbol __ICFEDIT_region_RAM_start__ = 0x20000000;
define symbol __ICFEDIT_region_RAM_end__ = 0x20001FFF;
/*-Sizes-*/
define symbol __ICFEDIT_size_cstack__ = 0x500;
define symbol __ICFEDIT_size_cstack__ = 0x400;
define memory mem with size = 4G;
@ -15,16 +23,17 @@ define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFED
define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__];
define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { };
define block FLASH_IMAGE with fixed order { readonly section .intvec, readonly } ;
initialize by copy { readwrite };
do not initialize { section .noinit,
section FAT,
section NVM };
place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec };
place at address mem:__ICFEDIT_region_FIB_start__ { section FAT };
place in ROM_region { readonly };
place in ROM_region { block FLASH_IMAGE };
place at end of ROM_region { section NVM };
place in RAM_region { readwrite,
block CSTACK };

View file

@ -31,10 +31,24 @@ extern "C" {
__root __no_init const HalFixedAddressTableType halFixedAddressTable @ __FAT__;
extern const HalVectorTableType __vector_table[];
extern void halInternalSwitchToXtal(void);
#define IAP_BOOTLOADER_APP_SWITCH_SIGNATURE 0xb001204d
#define IAP_BOOTLOADER_MODE_UART 0
__interwork int __low_level_init(void);
static void setStackPointer(int32u address)
{
asm("MOVS SP, r0");
}
static const int16u blOffset[] = {
0x0715 - 0x03ad - 0x68,
0x0719 - 0x03ad - 0x6C
};
__interwork int __low_level_init(void)
{
//Ensure there is enough margin on VREG_1V8 for stable RAM reads by
@ -154,6 +168,21 @@ __interwork int __low_level_init(void)
while(1) { ; }
}
//USART bootloader software activation check
if ((*((int32u *)RAM_BOTTOM) == IAP_BOOTLOADER_APP_SWITCH_SIGNATURE) && (*((int8u *)(RAM_BOTTOM+4)) == IAP_BOOTLOADER_MODE_UART)){
int8u cut = *(volatile int8u *) 0x08040798;
int16u offset = 0;
typedef void (*EntryPoint)(void);
offset = (halFixedAddressTable.baseTable.version == 3) ? blOffset[cut - 2] : 0;
*((int32u *)RAM_BOTTOM) = 0;
if (offset) {
halInternalSwitchToXtal();
}
EntryPoint entryPoint = (EntryPoint)(*(int32u *)(FIB_BOTTOM+4) - offset);
setStackPointer(*(int32u *)FIB_BOTTOM);
entryPoint();
}
INTERRUPTS_OFF();
asm("CPSIE i");

View file

@ -2,6 +2,9 @@
#define __REGS_H__ 1
#define ReadRegister(a) a
#define WriteRegister(a, b) a = b
/* FLASH_BASE block */
#define DATA_FLASH_BASE_BASE (0x00000000u)
#define DATA_FLASH_BASE_END (0x0001FFFFu)