Merge remote-tracking branch 'upstream/master'

pull/485/head
ytsuboi 2014-09-10 03:20:05 +09:00
commit 89342dbe69
10 changed files with 569 additions and 30 deletions

View File

@ -0,0 +1,27 @@
;WITHOUT SOFTDEVICE:
;LR_IROM1 0x00000000 0x00040000 {
; ER_IROM1 0x00000000 0x00040000 {
; *.o (RESET, +First)
; *(InRoot$$Sections)
; .ANY (+RO)
; }
; RW_IRAM1 0x20000000 0x00004000 {
; .ANY (+RW +ZI)
; }
;}
;
;WITH SOFTDEVICE:
LR_IROM1 0x16000 0x002A000 {
ER_IROM1 0x16000 0x002A000 {
*.o (RESET, +First)
*(InRoot$$Sections)
.ANY (+RO)
}
RW_IRAM1 0x20002000 0x00006000 {
.ANY (+RW +ZI)
}
}

View File

@ -0,0 +1,187 @@
; mbed Microcontroller Library
; Copyright (c) 2013 Nordic Semiconductor.
;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.
; Description message
__initial_sp EQU 0x20008000
PRESERVE8
THUMB
; Vector Table Mapped to Address 0 at Reset
AREA RESET, DATA, READONLY
EXPORT __Vectors
EXPORT __Vectors_End
EXPORT __Vectors_Size
__Vectors DCD __initial_sp ; Top of Stack
DCD Reset_Handler ; Reset Handler
DCD NMI_Handler ; NMI Handler
DCD HardFault_Handler ; Hard Fault Handler
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD SVC_Handler ; SVCall Handler
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD PendSV_Handler ; PendSV Handler
DCD SysTick_Handler ; SysTick Handler
; External Interrupts
DCD POWER_CLOCK_IRQHandler ;POWER_CLOCK
DCD RADIO_IRQHandler ;RADIO
DCD UART0_IRQHandler ;UART0
DCD SPI0_TWI0_IRQHandler ;SPI0_TWI0
DCD SPI1_TWI1_IRQHandler ;SPI1_TWI1
DCD 0 ;Reserved
DCD GPIOTE_IRQHandler ;GPIOTE
DCD ADC_IRQHandler ;ADC
DCD TIMER0_IRQHandler ;TIMER0
DCD TIMER1_IRQHandler ;TIMER1
DCD TIMER2_IRQHandler ;TIMER2
DCD RTC0_IRQHandler ;RTC0
DCD TEMP_IRQHandler ;TEMP
DCD RNG_IRQHandler ;RNG
DCD ECB_IRQHandler ;ECB
DCD CCM_AAR_IRQHandler ;CCM_AAR
DCD WDT_IRQHandler ;WDT
DCD RTC1_IRQHandler ;RTC1
DCD QDEC_IRQHandler ;QDEC
DCD LPCOMP_COMP_IRQHandler ;LPCOMP_COMP
DCD SWI0_IRQHandler ;SWI0
DCD SWI1_IRQHandler ;SWI1
DCD SWI2_IRQHandler ;SWI2
DCD SWI3_IRQHandler ;SWI3
DCD SWI4_IRQHandler ;SWI4
DCD SWI5_IRQHandler ;SWI5
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD 0 ;Reserved
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset Handler
NRF_POWER_RAMON_ADDRESS EQU 0x40000524 ; NRF_POWER->RAMON address
NRF_POWER_RAMON_RAMxON_ONMODE_Msk EQU 0xF ; All RAM blocks on in onmode bit mask
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT SystemInit
IMPORT __main
LDR R0, =NRF_POWER_RAMON_ADDRESS
LDR R2, [R0]
MOVS R1, #NRF_POWER_RAMON_RAMxON_ONMODE_Msk
ORRS R2, R2, R1
STR R2, [R0]
LDR R0, =SystemInit
BLX R0
LDR R0, =__main
BX R0
ENDP
; Dummy Exception Handlers (infinite loops which can be modified)
NMI_Handler PROC
EXPORT NMI_Handler [WEAK]
B .
ENDP
HardFault_Handler\
PROC
EXPORT HardFault_Handler [WEAK]
B .
ENDP
SVC_Handler PROC
EXPORT SVC_Handler [WEAK]
B .
ENDP
PendSV_Handler PROC
EXPORT PendSV_Handler [WEAK]
B .
ENDP
SysTick_Handler PROC
EXPORT SysTick_Handler [WEAK]
B .
ENDP
Default_Handler PROC
EXPORT POWER_CLOCK_IRQHandler [WEAK]
EXPORT RADIO_IRQHandler [WEAK]
EXPORT UART0_IRQHandler [WEAK]
EXPORT SPI0_TWI0_IRQHandler [WEAK]
EXPORT SPI1_TWI1_IRQHandler [WEAK]
EXPORT GPIOTE_IRQHandler [WEAK]
EXPORT ADC_IRQHandler [WEAK]
EXPORT TIMER0_IRQHandler [WEAK]
EXPORT TIMER1_IRQHandler [WEAK]
EXPORT TIMER2_IRQHandler [WEAK]
EXPORT RTC0_IRQHandler [WEAK]
EXPORT TEMP_IRQHandler [WEAK]
EXPORT RNG_IRQHandler [WEAK]
EXPORT ECB_IRQHandler [WEAK]
EXPORT CCM_AAR_IRQHandler [WEAK]
EXPORT WDT_IRQHandler [WEAK]
EXPORT RTC1_IRQHandler [WEAK]
EXPORT QDEC_IRQHandler [WEAK]
EXPORT LPCOMP_COMP_IRQHandler [WEAK]
EXPORT SWI0_IRQHandler [WEAK]
EXPORT SWI1_IRQHandler [WEAK]
EXPORT SWI2_IRQHandler [WEAK]
EXPORT SWI3_IRQHandler [WEAK]
EXPORT SWI4_IRQHandler [WEAK]
EXPORT SWI5_IRQHandler [WEAK]
POWER_CLOCK_IRQHandler
RADIO_IRQHandler
UART0_IRQHandler
SPI0_TWI0_IRQHandler
SPI1_TWI1_IRQHandler
GPIOTE_IRQHandler
ADC_IRQHandler
TIMER0_IRQHandler
TIMER1_IRQHandler
TIMER2_IRQHandler
RTC0_IRQHandler
TEMP_IRQHandler
RNG_IRQHandler
ECB_IRQHandler
CCM_AAR_IRQHandler
WDT_IRQHandler
RTC1_IRQHandler
QDEC_IRQHandler
LPCOMP_COMP_IRQHandler
SWI0_IRQHandler
SWI1_IRQHandler
SWI2_IRQHandler
SWI3_IRQHandler
SWI4_IRQHandler
SWI5_IRQHandler
B .
ENDP
ALIGN
END

View File

@ -0,0 +1,151 @@
/* Linker script to configure memory regions. */
MEMORY
{
FLASH (rx) : ORIGIN = 0x00016000, LENGTH = 0x2A000
RAM (rwx) : ORIGIN = 0x20002000, LENGTH = 0x6000
}
OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
/* Linker script to place sections and symbol values. Should be used together
* with other linker script that defines memory regions FLASH and RAM.
* It references following symbols, which must be defined in code:
* Reset_Handler : Entry of reset handler
*
* It defines following symbols, which code can use without definition:
* __exidx_start
* __exidx_end
* __etext
* __data_start__
* __preinit_array_start
* __preinit_array_end
* __init_array_start
* __init_array_end
* __fini_array_start
* __fini_array_end
* __data_end__
* __bss_start__
* __bss_end__
* __end__
* end
* __HeapLimit
* __StackLimit
* __StackTop
* __stack
*/
ENTRY(Reset_Handler)
SECTIONS
{
.text :
{
KEEP(*(.Vectors))
*(.text*)
KEEP(*(.init))
KEEP(*(.fini))
/* .ctors */
*crtbegin.o(.ctors)
*crtbegin?.o(.ctors)
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
*(SORT(.ctors.*))
*(.ctors)
/* .dtors */
*crtbegin.o(.dtors)
*crtbegin?.o(.dtors)
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
*(SORT(.dtors.*))
*(.dtors)
*(.rodata*)
KEEP(*(.eh_frame*))
} > FLASH
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > FLASH
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} > FLASH
__exidx_end = .;
__etext = .;
.data : AT (__etext)
{
__data_start__ = .;
*(vtable)
*(.data*)
. = ALIGN(4);
/* preinit data */
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP(*(.preinit_array))
PROVIDE_HIDDEN (__preinit_array_end = .);
. = ALIGN(4);
/* init data */
PROVIDE_HIDDEN (__init_array_start = .);
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
PROVIDE_HIDDEN (__init_array_end = .);
. = ALIGN(4);
/* finit data */
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP(*(SORT(.fini_array.*)))
KEEP(*(.fini_array))
PROVIDE_HIDDEN (__fini_array_end = .);
*(.jcr)
. = ALIGN(4);
/* All data end */
__data_end__ = .;
} > RAM
.bss :
{
. = ALIGN(4);
__bss_start__ = .;
*(.bss*)
*(COMMON)
. = ALIGN(4);
__bss_end__ = .;
} > RAM
.heap (COPY):
{
__end__ = .;
end = __end__;
*(.heap*)
__HeapLimit = .;
} > RAM
/* .stack_dummy section doesn't contains any symbols. It is only
* used for linker to calculate size of stack sections, and assign
* values to stack symbols later */
.stack_dummy (COPY):
{
*(.stack*)
} > RAM
/* Set stack top to end of RAM, and stack limit move down by
* size of stack_dummy section */
__StackTop = ORIGIN(RAM) + LENGTH(RAM);
__StackLimit = __StackTop - SIZEOF(.stack_dummy);
PROVIDE(__stack = __StackTop);
/* Check if data + heap + stack exceeds RAM limit */
ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack")
}

View File

@ -0,0 +1,91 @@
/* Copyright (c) 2013 Nordic Semiconductor. All Rights Reserved.
*
* The information contained herein is property of Nordic Semiconductor ASA.
* Terms and conditions of usage are described in detail in NORDIC
* SEMICONDUCTOR STANDARD SOFTWARE LICENSE AGREEMENT.
*
* Licensees are granted free, non-transferable use of the information. NO
* WARRANTY of ANY KIND is provided. This heading must NOT be removed from
* the file.
*
*/
#include "bootloader_util.h"
#include <stdint.h>
/**
* @brief Function for aborting current handler mode and jump to to other application/bootloader.
*
* @details This functions will use the address provide (reset handler) to be executed after
* handler mode is exited. It creates an initial stack to ensure correct reset behavior
* when the reset handler is executed.
*
* @param[in] reset_handler Address of the reset handler to be executed when handler mode exits.
*
* @note This function must never be called directly from 'C' but is intended only to be used from
* \ref bootloader_util_reset. This function will never return but issue a reset into
* provided address.
*/
__asm void isr_abort(uint32_t reset_handler)
{
xPSR_RESET EQU 0x21000000 ; Default value of xPSR after System Reset.
EXC_RETURN_CMD EQU 0xFFFFFFF9 ; EXC_RETURN for ARM Cortex. When loaded to PC the current interrupt service routine (handler mode) willl exit and the stack will be popped. Execution will continue in thread mode.
LDR R4,=MASK_ONES ; Fill with ones before jumping to reset handling. We be popped as R12 when exiting ISR (Cleaning up the registers).
LDR R5,=MASK_ONES ; Fill with ones before jumping to reset handling. We be popped as LR when exiting ISR. Ensures no return to application.
MOV R6, R0 ; Move address of reset handler to R6. Will be popped as PC when exiting ISR. Ensures the reset handler will be executed when exist ISR.
LDR R7,=xPSR_RESET ; Move reset value of xPSR to R7. Will be popped as xPSR when exiting ISR.
PUSH {r4-r7} ; Push everything to new stack to allow interrupt handler to fetch it on exiting the ISR.
LDR R4,=MASK_ZEROS ; Fill with zeros before jumping to reset handling. We be popped as R0 when exiting ISR (Cleaning up of the registers).
LDR R5,=MASK_ZEROS ; Fill with zeros before jumping to reset handling. We be popped as R1 when exiting ISR (Cleaning up of the registers).
LDR R6,=MASK_ZEROS ; Fill with zeros before jumping to reset handling. We be popped as R2 when exiting ISR (Cleaning up of the registers).
LDR R7,=MASK_ZEROS ; Fill with zeros before jumping to reset handling. We be popped as R3 when exiting ISR (Cleaning up of the registers).
PUSH {r4-r7} ; Push zeros (R4-R7) to stack to prepare for exiting the interrupt routine.
LDR R0,=EXC_RETURN_CMD ; Load the execution return command into register.
BX R0 ; No return - Handler mode will be exited. Stack will be popped and execution will continue in reset handler initializing other application.
ALIGN
}
/**
* @brief Function for aborting current application/bootloader jump to to other app/bootloader.
*
* @details This functions will use the address provide to swap the stack pointer and then load
* the address of the reset handler to be executed. It will check current system mode
* (thread/handler) and if in thread mode it will reset into other application.
* If in handler mode \ref isr_abort will be executed to ensure correct exit of handler
* mode and jump into reset handler of other application.
*
* @param[in] start_addr Start address of other application. This address must point to the
initial stack pointer of the application.
*
* @note This function will never return but issue a reset into provided application.
*/
__asm static void bootloader_util_reset(uint32_t start_addr)
{
MASK_ONES EQU 0xFFFFFFFF ; Ones, to be loaded into register as default value before reset.
MASK_ZEROS EQU 0x00000000 ; Zeros, to be loaded into register as default value before reset.
LDR R1, [R0] ; Get App initial MSP for bootloader.
MSR MSP, R1 ; Set the main stack pointer to the applications MSP.
LDR R0,[R0, #0x04] ; Load Reset handler into register 0.
LDR R2, =MASK_ZEROS ; Load zeros to R2
MRS R3, IPSR ; Load IPSR to R3 to check for handler or thread mode
CMP R2, R3 ; Compare, if 0 then we are in thread mode and can continue to reset handler of bootloader
BNE isr_abort ; If not zero we need to exit current ISR and jump to reset handler of bootloader
LDR R4, =MASK_ONES ; Load ones to R4 to be placed in Link Register.
MOV LR, R4 ; Clear the link register and set to ones to ensure no return.
BX R0 ; Branch to reset handler of bootloader
ALIGN
}
void bootloader_util_app_start(uint32_t start_addr)
{
bootloader_util_reset(start_addr);
}

View File

@ -0,0 +1,81 @@
/* Copyright (c) 2012 Nordic Semiconductor. All Rights Reserved.
*
* The information contained herein is property of Nordic Semiconductor ASA.
* Terms and conditions of usage are described in detail in NORDIC
* SEMICONDUCTOR STANDARD SOFTWARE LICENSE AGREEMENT.
*
* Licensees are granted free, non-transferable use of the information. NO
* WARRANTY of ANY KIND is provided. This heading must NOT be removed from
* the file.
*
*/
#include "dfu_app_handler.h"
#include "bootloader_util.h"
#include "nrf_sdm.h"
#include "app_error.h"
#define IRQ_ENABLED 0x01 /**< Field identifying if an interrupt is enabled. */
#define MAX_NUMBER_INTERRUPTS 32 /**< Maximum number of interrupts available. */
static void dfu_app_reset_prepare(void); /**< Forward declare of default reset handler. */
static dfu_app_reset_prepare_t m_reset_prepare = dfu_app_reset_prepare; /**< Callback function to application to prepare for system reset. Allows application to cleanup of service and memory prior to reset. */
/**@brief Default reset prepare handler if application hasn't registered a handler.
*/
static void dfu_app_reset_prepare(void)
{
// Reset prepare should be handled by application.
// This function can be extended to include default handling if application does not implement
// own handler.
}
/**@brief Function for disabling all interrupts before jumping from bootloader to application.
*/
static void interrupts_disable(void)
{
uint32_t interrupt_setting_mask;
uint32_t irq = 0; // We start from first interrupt, i.e. interrupt 0.
// Fetch the current interrupt settings.
interrupt_setting_mask = NVIC->ISER[0];
for (; irq < MAX_NUMBER_INTERRUPTS; irq++)
{
if (interrupt_setting_mask & (IRQ_ENABLED << irq))
{
// The interrupt was enabled, and hence disable it.
NVIC_DisableIRQ((IRQn_Type)irq);
}
}
}
/**@brief Function for preparing the reset, disabling SoftDevice and jump to the bootloader.
*/
void bootloader_start(void)
{
m_reset_prepare();
uint32_t err_code = sd_power_gpregret_set(BOOTLOADER_DFU_START);
APP_ERROR_CHECK(err_code);
err_code = sd_softdevice_disable();
APP_ERROR_CHECK(err_code);
interrupts_disable();
err_code = sd_softdevice_vector_table_base_set(NRF_UICR->BOOTLOADERADDR);
APP_ERROR_CHECK(err_code);
bootloader_util_app_start(NRF_UICR->BOOTLOADERADDR);
}
void dfu_app_reset_prepare_set(dfu_app_reset_prepare_t reset_prepare_func)
{
m_reset_prepare = reset_prepare_func;
}

View File

@ -49,7 +49,7 @@ class WaitusTest(DefaultTest):
if i > 2: # we will ignore first few measurements
delta = time() - start
deviation = abs(delta - 1)
deviation_ok = True if delta > 0 and deviation <= 0.05 else False # +/-5%
deviation_ok = True if delta > 0 and deviation <= 0.10 else False # +/-10%
test_result = test_result and deviation_ok
msg = "OK" if deviation_ok else "FAIL"
print ". in %.2f sec (%.2f) [%s]" % (delta, deviation, msg)

View File

@ -437,7 +437,7 @@ class NRF51822(Target):
def __init__(self):
Target.__init__(self)
self.core = "Cortex-M0"
self.extra_labels = ["NORDIC", "NRF51822_MKIT", "MCU_NRF51822"]
self.extra_labels = ["NORDIC", "NRF51822_MKIT", "MCU_NRF51822", "MCU_NORDIC_16K"]
self.supported_toolchains = ["ARM", "GCC_ARM"]
self.is_disk_virtual = True
@ -475,6 +475,36 @@ class NRF51822(Target):
sdh.tofile(f, format='hex')
class ARCH_BLE(NRF51822):
def __init__(self):
NRF51822.__init__(self)
self.extra_labels = ['NORDIC', 'MCU_NRF51822', 'MCU_NORDIC_16K']
self.macros = ['TARGET_NRF51822']
self.supported_form_factors = ["ARDUINO"]
class HRM1017(NRF51822):
def __init__(self):
NRF51822.__init__(self)
self.extra_labels = ['NORDIC', 'MCU_NRF51822', 'MCU_NORDIC_16K']
self.macros = ['TARGET_NRF51822']
class RBLAB_NRF51822(NRF51822):
def __init__(self):
NRF51822.__init__(self)
self.extra_labels = ['NORDIC', 'MCU_NRF51822', 'MCU_NORDIC_16K']
self.macros = ['TARGET_NRF51822']
class NRF51_DK(NRF51822):
def __init__(self):
NRF51822.__init__(self)
self.extra_labels = ['NORDIC', 'MCU_NRF51822', 'MCU_NORDIC_32K']
self.macros = ['TARGET_NRF51822']
self.supported_form_factors = ["ARDUINO"]
class LPC1549(LPCTarget):
def __init__(self):
LPCTarget.__init__(self)
@ -547,20 +577,6 @@ class XADOW_M0(LPCTarget):
self.default_toolchain = "uARM"
class ARCH_BLE(NRF51822):
def __init__(self):
NRF51822.__init__(self)
self.extra_labels = ['NORDIC', 'MCU_NRF51822']
self.macros = ['TARGET_NRF51822']
self.supported_form_factors = ["ARDUINO"]
class NRF51_DK(NRF51822):
def __init__(self):
NRF51822.__init__(self)
self.extra_labels = ['NORDIC', 'MCU_NRF51822']
self.macros = ['TARGET_NRF51822']
self.supported_form_factors = ["ARDUINO"]
class ARCH_PRO(LPCTarget):
def __init__(self):
LPCTarget.__init__(self)
@ -586,13 +602,6 @@ class LPCCAPPUCCINO(LPC11U37_501):
LPC11U37_501.__init__(self)
class HRM1017(NRF51822):
def __init__(self):
NRF51822.__init__(self)
self.extra_labels = ['NORDIC', 'MCU_NRF51822']
self.macros = ['TARGET_NRF51822']
class ARM_MPS2(Target):
def __init__(self):
Target.__init__(self)
@ -602,13 +611,6 @@ class ARM_MPS2(Target):
self.default_toolchain = "ARM"
class RBLAB_NRF51822(NRF51822):
def __init__(self):
NRF51822.__init__(self)
self.extra_labels = ['NORDIC', 'MCU_NRF51822']
self.macros = ['TARGET_NRF51822']
class OC_MBUINO(LPC11U24):
def __init__(self):
LPC11U24.__init__(self)