Multi-platform test application, added K82 to Kinetis port

pull/5/head
Daniele Lacamera 2019-04-03 15:04:58 +02:00
parent b5fd49a82a
commit b918014203
15 changed files with 466 additions and 28 deletions

View File

@ -21,6 +21,7 @@ SPI_FLASH?=0
ALLOW_DOWNGRADE?=0
NVM_FLASH_WRITEONCE?=0
V?=0
SPMATH?=1
@ -46,18 +47,12 @@ include arch.mk
## DSA Settings
ifeq ($(FASTMATH),1)
MATH_OBJS:=./lib/wolfssl/wolfcrypt/src/integer.o
CFLAGS+=-DUSE_FAST_MATH
else
MATH_OBJS:=./lib/wolfssl/wolfcrypt/src/sp_int.o
endif
ifeq ($(SIGN),ECC256)
KEYGEN_TOOL=tools/ecc256/ecc256_keygen
SIGN_TOOL=tools/ecc256/ecc256_sign
PRIVATE_KEY=ecc256.der
OBJS+= \
$(ECC_EXTRA_OBJS) \
$(MATH_OBJS) \
./lib/wolfssl/wolfcrypt/src/ecc.o \
./lib/wolfssl/wolfcrypt/src/ge_low_mem.o \
@ -65,7 +60,7 @@ ifeq ($(SIGN),ECC256)
./lib/wolfssl/wolfcrypt/src/wc_port.o \
./src/ecc256_pub_key.o \
./src/xmalloc.o
CFLAGS+=-DWOLFBOOT_SIGN_ECC256 -DXMALLOC_USER
CFLAGS+=-DWOLFBOOT_SIGN_ECC256 -DXMALLOC_USER $(ECC_EXTRA_CFLAGS)
else
KEYGEN_TOOL=tools/ed25519/ed25519_keygen
SIGN_TOOL=tools/ed25519/ed25519_sign
@ -146,7 +141,9 @@ wolfboot-align.bin: wolfboot.bin
@echo
test-app/image.bin:
@make -C test-app TARGET=$(TARGET) EXT_FLASH=$(EXT_FLASH) SPI_FLASH=$(SPI_FLASH) ARCH=$(ARCH) V=$(V)
@make -C test-app TARGET=$(TARGET) EXT_FLASH=$(EXT_FLASH) SPI_FLASH=$(SPI_FLASH) ARCH=$(ARCH) V=$(V) \
KINETIS=$(KINETIS) KINETIS_CPU=$(KINETIS_CPU) KINETIS_DRIVERS=$(KINETIS_DRIVERS) \
KINETIS_CMSIS=$(KINETIS_CMSIS) NVM_FLASH_WRITEONCE=$(NVM_FLASH_WRITEONCE)
@rm -f src/*.o hal/*.o
include tools/test.mk

27
arch.mk
View File

@ -1,5 +1,12 @@
## CPU Architecture selection via $ARCH
# check for FASTMATH or SP_MATH
ifeq ($(SPMATH),1)
MATH_OBJS:=./lib/wolfssl/wolfcrypt/src/sp_int.o
else
MATH_OBJS:=./lib/wolfssl/wolfcrypt/src/integer.o
endif
## ARM
ifeq ($(ARCH),ARM)
CROSS_COMPILE:=arm-none-eabi-
@ -12,16 +19,23 @@ ifeq ($(ARCH),ARM)
ifeq ($(CORTEX_M0),1)
CFLAGS+=-mcpu=cortex-m0
LDFLAGS+=-mcpu=cortex-m0
MATH_OBJS += ./lib/wolfssl/wolfcrypt/src/sp_c32.o
ifeq ($(SPMATH),1)
MATH_OBJS += ./lib/wolfssl/wolfcrypt/src/sp_c32.o
endif
else
ifeq ($(NO_ASM),1)
MATH_OBJS += ./lib/wolfssl/wolfcrypt/src/sp_c32.o
ifeq ($(SPMATH),1)
MATH_OBJS += ./lib/wolfssl/wolfcrypt/src/sp_c32.o
endif
CFLAGS+=-mcpu=cortex-m3
LDFLAGS+=-mcpu=cortex-m3
else
CFLAGS+=-mcpu=cortex-m3 -DWOLFSSL_SP_ASM -DWOLFSSL_SP_ARM_CORTEX_M_ASM -fomit-frame-pointer
CFLAGS+=-mcpu=cortex-m3 -fomit-frame-pointer
LDFLAGS+=-mcpu=cortex-m3
MATH_OBJS += ./lib/wolfssl/wolfcrypt/src/sp_cortexm.o
ifeq ($(SPMATH),1)
CFLAGS+=-DWOLFSSL_SP_ASM -DWOLFSSL_SP_ARM_CORTEX_M_ASM
MATH_OBJS += ./lib/wolfssl/wolfcrypt/src/sp_cortexm.o
endif
endif
endif
endif
@ -51,4 +65,9 @@ endif
ifeq ($(TARGET),kinetis)
CFLAGS+= -I$(KINETIS_DRIVERS)/drivers -I$(KINETIS_DRIVERS) -DCPU_$(KINETIS_CPU) -I$(KINETIS_CMSIS)/Include -DDEBUG_CONSOLE_ASSERT_DISABLE=1
OBJS+= $(KINETIS_DRIVERS)/drivers/fsl_clock.o $(KINETIS_DRIVERS)/drivers/fsl_ftfx_flash.o $(KINETIS_DRIVERS)/drivers/fsl_ftfx_cache.o $(KINETIS_DRIVERS)/drivers/fsl_ftfx_controller.o
## The following lines can be used to enable HW acceleration
##ifeq ($(KINETIS_CPU),MK82FN256VLL15)
## ECC_EXTRA_CFLAGS+=-DFREESCALE_LTC_ECC -DFREESCALE_USE_LTC
## ECC_EXTRA_OBJS+=./lib/wolfssl/wolfcrypt/src/port/nxp/ksdk_port.o $(KINETIS_DRIVERS)/drivers/fsl_ltc.o
##endif
endif

View File

@ -35,7 +35,6 @@ static int flash_init = 0;
#endif
#ifdef __WOLFBOOT
#define CPU_CORE_CLOCK 120000000U
static void CLOCK_CONFIG_SetFllExtRefDiv(uint8_t frdiv)
{
@ -44,6 +43,13 @@ static void CLOCK_CONFIG_SetFllExtRefDiv(uint8_t frdiv)
static void do_flash_init(void);
/* Assert hook needed by Kinetis SDK */
void __assert_func(const char *a, int b, const char *c, const char *d)
{
while(1)
;
}
/* This are the registers for the NV flash configuration area.
* Access these field by setting the relative flags in NV_Flash_Config.
*/
@ -68,13 +74,51 @@ const uint8_t __attribute__((section(".flash_config"))) NV_Flash_Config[NVTYPE_L
0xFF
};
/* Assert hook needed by Kinetis SDK */
void __assert_func(const char *a, int b, const char *c, const char *d)
#if defined(CPU_MK82FN256VLL15)
struct stage1_config
{
while(1)
;
}
uint32_t tag;
uint32_t crcStartAddress;
uint32_t crcByteCount;
uint32_t crcExpectedValue;
uint8_t enabledPeripherals;
uint8_t i2cSlaveAddress;
uint16_t peripheralDetectionTimeoutMs;
uint16_t usbVid;
uint16_t usbPid;
uint32_t usbStringsPointer;
uint8_t clockFlags;
uint8_t clockDivider;
uint8_t bootFlags;
uint8_t RESERVED1;
uint32_t mmcauConfigPointer;
uint32_t keyBlobPointer;
uint8_t RESERVED2[8];
uint32_t qspiConfigBlockPtr;
uint8_t RESERVED3[12];
};
const struct stage1_config __attribute__((section(".stage1_config")))
NV_Stage1_Config = {
.tag = 0x6766636BU, /* Magic Number */
.crcStartAddress = 0xFFFFFFFFU, /* Disable CRC check */
.crcByteCount = 0xFFFFFFFFU, /* Disable CRC check */
.crcExpectedValue = 0xFFFFFFFFU, /* Disable CRC check */
.enabledPeripherals = 0x17, /* Enable all peripherals */
.i2cSlaveAddress = 0xFF, /* Use default I2C address */
.peripheralDetectionTimeoutMs = 0x01F4U, /* Use default timeout */
.usbVid = 0xFFFFU, /* Use default USB Vendor ID */
.usbPid = 0xFFFFU, /* Use default USB Product ID */
.usbStringsPointer = 0xFFFFFFFFU, /* Use default USB Strings */
.clockFlags = 0x01, /* Enable High speed mode */
.clockDivider = 0xFF, /* Use clock divider 1 */
.bootFlags = 0x01, /* Enable communication with host */
.mmcauConfigPointer = 0xFFFFFFFFU, /* No MMCAU configuration */
.keyBlobPointer = 0x000001000, /* keyblob data is at 0x1000 */
.qspiConfigBlockPtr = 0xFFFFFFFFU /* No QSPI configuration */
};
#endif
#define MCG_PLL_DISABLE 0U /*!< MCGPLLCLK disabled */
#define OSC_CAP0P 0U /*!< Oscillator 0pF capacitor load */
@ -82,6 +126,10 @@ void __assert_func(const char *a, int b, const char *c, const char *d)
#define SIM_OSC32KSEL_RTC32KCLK_CLK 2U /*!< OSC32KSEL select: RTC32KCLK clock (32.768kHz) */
#define SIM_PLLFLLSEL_IRC48MCLK_CLK 3U /*!< PLLFLL select: IRC48MCLK clock */
#define SIM_PLLFLLSEL_MCGPLLCLK_CLK 1U /*!< PLLFLL select: MCGPLLCLK clock */
#define SIM_CLKDIV1_RUN_MODE_MAX_CORE_DIV 1U /*!< SIM CLKDIV1 maximum run mode core/system divider configurations */
#define SIM_CLKDIV1_RUN_MODE_MAX_BUS_DIV 3U /*!< SIM CLKDIV1 maximum run mode bus divider configurations */
#define SIM_CLKDIV1_RUN_MODE_MAX_FLEXBUS_DIV 3U /*!< SIM CLKDIV1 maximum run mode flexbus divider configurations */
#define SIM_CLKDIV1_RUN_MODE_MAX_FLASH_DIV 7U /*!< SIM CLKDIV1 maximum run mode flash divider configurations */
static void CLOCK_CONFIG_FllStableDelay(void)
{
@ -92,7 +140,6 @@ static void CLOCK_CONFIG_FllStableDelay(void)
}
}
/* Clock configuration for K64F */
const mcg_config_t mcgConfig_BOARD_BootClockRUN =
{
.mcgMode = kMCG_ModePEE, /* PEE - PLL Engaged External */
@ -103,19 +150,34 @@ const mcg_config_t mcgConfig_BOARD_BootClockRUN =
.drs = kMCG_DrsLow, /* Low frequency range */
.dmx32 = kMCG_Dmx32Default, /* DCO has a default range of 25% */
.oscsel = kMCG_OscselOsc, /* Selects System Oscillator (OSCCLK) */
#if defined(CPU_MK64FN1M0VLL12)
.pll0Config =
{
.enableMode = MCG_PLL_DISABLE, /* MCGPLLCLK disabled */
.prdiv = 0x13U, /* PLL Reference divider: divided by 20 */
.vdiv = 0x18U, /* VCO divider: multiplied by 48 */
},
#elif defined(CPU_MK82FN256VLL15)
.pll0Config =
{
.enableMode = MCG_PLL_DISABLE, /* MCGPLLCLK disabled */
.prdiv = 0x0U, /* PLL Reference divider: divided by 1 */
.vdiv = 0x9U, /* VCO divider: multiplied by 25 */
},
#else
# error("The selected Kinetis MPU does not have a clock line configuration. Please edit hal/kinetis.c")
#endif
};
#if defined(CPU_MK64FN1M0VLL12)
const sim_clock_config_t simConfig_BOARD_BootClockRUN =
{
.pllFllSel = SIM_PLLFLLSEL_MCGPLLCLK_CLK, /* PLLFLL select: MCGPLLCLK clock */
.er32kSrc = SIM_OSC32KSEL_RTC32KCLK_CLK, /* OSC32KSEL select: RTC32KCLK clock (32.768kHz) */
.clkdiv1 = 0x1240000U, /* SIM_CLKDIV1 - OUTDIV1: /1, OUTDIV2: /2, OUTDIV3: /3, OUTDIV4: /5 */
};
const osc_config_t oscConfig_BOARD_BootClockRUN =
{
.freq = 50000000U, /* Oscillator frequency: 50000000Hz */
@ -127,13 +189,41 @@ const osc_config_t oscConfig_BOARD_BootClockRUN =
}
};
#elif defined(CPU_MK82FN256VLL15)
const sim_clock_config_t simConfig_BOARD_BootClockRUN = {
.pllFllSel = SIM_PLLFLLSEL_MCGPLLCLK_CLK, /* PLLFLL select: MCGPLLCLK clock */
.pllFllDiv = 0, /* PLLFLLSEL clock divider divisor: divided by 1 */
.pllFllFrac = 0, /* PLLFLLSEL clock divider fraction: multiplied by 1 */
.er32kSrc = SIM_OSC32KSEL_RTC32KCLK_CLK, /* OSC32KSEL select: RTC32KCLK clock (32.768kHz) */
.clkdiv1 = 0x1150000U, /* SIM_CLKDIV1 - OUTDIV1: /1, OUTDIV2: /2, OUTDIV3: /2, OUTDIV4: /6 */
};
const osc_config_t oscConfig_BOARD_BootClockRUN = {
.freq = 12000000U, /* Oscillator frequency: 12000000Hz */
.capLoad = (OSC_CAP0P), /* Oscillator capacity load: 0pF */
.workMode = kOSC_ModeOscLowPower, /* Oscillator low power */
.oscerConfig = {
.enableMode =
kOSC_ErClkEnable, /* Enable external reference clock, disable external reference clock in STOP mode */
.erclkDiv = 0, /* Divider for OSCERCLK: divided by 1 */
}
};
#endif
void hal_init(void)
{
/* Disable MPU */
SYSMPU_Enable(SYSMPU, false);
/* Set the system clock dividers in SIM to safe value. */
#if defined(CPU_MK64FN1M0VLL12)
CLOCK_SetSimSafeDivs();
#elif defined(CPU_MK82FN256VLL15)
CLOCK_SetOutDiv(SIM_CLKDIV1_RUN_MODE_MAX_CORE_DIV, SIM_CLKDIV1_RUN_MODE_MAX_BUS_DIV,
SIM_CLKDIV1_RUN_MODE_MAX_FLEXBUS_DIV, SIM_CLKDIV1_RUN_MODE_MAX_FLASH_DIV);
#endif
/* Initializes OSC0 according to board configuration. */
CLOCK_InitOsc0(&oscConfig_BOARD_BootClockRUN);
CLOCK_SetXtal0Freq(oscConfig_BOARD_BootClockRUN.freq);
@ -151,6 +241,45 @@ void hal_init(void)
CLOCK_SetSimConfig(&simConfig_BOARD_BootClockRUN);
do_flash_init();
}
#if 0
void BOARD_BootClockHSRUN(void)
{
/* In HSRUN mode, the maximum allowable change in frequency of the system/bus/core/flash is
* restricted to x2, to follow this restriction, enter HSRUN mode should follow:
* 1.set CLKDIV1 to safe divider value.
* 2.set the PLL or FLL output target frequency for HSRUN mode.
* 3.switch to HSRUN mode.
* 4.switch to HSRUN mode target requency value.
*/
/* Set the system clock dividers in SIM to safe value. */
CLOCK_SetOutDiv(SIM_CLKDIV1_RUN_MODE_MAX_CORE_DIV, SIM_CLKDIV1_RUN_MODE_MAX_BUS_DIV,
SIM_CLKDIV1_RUN_MODE_MAX_FLEXBUS_DIV, SIM_CLKDIV1_RUN_MODE_MAX_FLASH_DIV);
/* Initializes OSC0 according to board configuration. */
CLOCK_InitOsc0(&oscConfig_BOARD_BootClockHSRUN);
CLOCK_SetXtal0Freq(oscConfig_BOARD_BootClockHSRUN.freq);
/* Configure the Internal Reference clock (MCGIRCLK). */
CLOCK_SetInternalRefClkConfig(mcgConfig_BOARD_BootClockHSRUN.irclkEnableMode, mcgConfig_BOARD_BootClockHSRUN.ircs,
mcgConfig_BOARD_BootClockHSRUN.fcrdiv);
/* Configure FLL external reference divider (FRDIV). */
CLOCK_CONFIG_SetFllExtRefDiv(mcgConfig_BOARD_BootClockHSRUN.frdiv);
/* Set MCG to PEE mode. */
CLOCK_BootToPeeMode(mcgConfig_BOARD_BootClockHSRUN.oscsel, kMCG_PllClkSelPll0,
&mcgConfig_BOARD_BootClockHSRUN.pll0Config);
/* Set HSRUN power mode */
SMC_SetPowerModeProtection(SMC, kSMC_AllowPowerModeAll);
SMC_SetPowerModeHsrun(SMC);
while (SMC_GetPowerModeState(SMC) != kSMC_PowerStateHsrun)
{
}
/* Set the clock configuration in SIM module. */
CLOCK_SetSimConfig(&simConfig_BOARD_BootClockHSRUN);
/* Set SystemCoreClock variable. */
SystemCoreClock = BOARD_BOOTCLOCKHSRUN_CORE_CLOCK;
}
#endif
void hal_prepare_boot(void)
{

View File

@ -11,6 +11,8 @@ SECTIONS
{
_start_text = .;
KEEP(*(.isr_vector))
. = 0x3c0;
KEEP(*(.stage1_config))
. = 0x400;
KEEP(*(.flash_config))
. = ALIGN(8);

View File

@ -44,6 +44,7 @@
# define USE_FAST_MATH
# define WOLFSSL_SHA512
# define NO_ASN
# define NO_BIG_INT
#endif
#ifdef WOLFBOOT_SIGN_ECC256
@ -53,12 +54,19 @@
# define ECC_ALT_SIZE
# define NO_ECC_SIGN
# define NO_ECC_EXPORT
# define USE_FAST_MATH
# define WOLFSSL_SHA512
# ifdef FREESCALE_USE_LTC
# define LTC_MAX_ECC_BITS (256)
# define LTC_MAX_INT_BYTES (128)
# define LTC_BASE ((LTC_Type *)LTC0_BASE)
# else
# define NO_BIG_INT
# define USE_FAST_MATH
# define WOLFSSL_SP_SMALL
# define SP_WORD_SIZE 32
# define WOLFSSL_HAVE_SP_ECC
# define WOLFSSL_SP_MATH
# endif
# define NO_ASN
//# define NO_ECC_SIGN
# define NO_ECC_DHE
@ -69,5 +77,4 @@
# define NO_AES
# define NO_CMAC
# define NO_CODING
# define NO_BIG_INT
# define NO_RSA

@ -1 +1 @@
Subproject commit b528997d30fab68fa64f4c49314f8275e77fd948
Subproject commit e4059a65b9b53ea2817b81afe6a0562ad6a5d342

View File

@ -1,6 +1,6 @@
MEMORY
{
FLASH (rx) : ORIGIN = 0x00020100, LENGTH = 0x001FF00
FLASH (rx) : ORIGIN = 0x0020100, LENGTH = 0x001FF00
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00010000
}

View File

@ -1,9 +1,10 @@
TARGET?=none
ARCH?=ARM
KINETIS_CMSIS?=$(KINETIS)/CMSIS
CFLAGS:=-g -ggdb -Wall -Wstack-usage=200 -ffreestanding -Wno-unused -DPLATFORM_$(TARGET) -I../include -nostartfiles
APP_OBJS:=main.o led.o system.o timer.o ../hal/$(TARGET).o ../src/libwolfboot.o
APP_OBJS:=$(TARGET).o led.o system.o timer.o ../hal/$(TARGET).o ../src/libwolfboot.o
include ../arch.mk
ifeq ($(ARCH),RISCV)
@ -30,6 +31,15 @@ ifeq ($(SPI_FLASH),1)
APP_OBJS+=../hal/spi/spi_drv_$(TARGET).o ../src/spi_flash.o
endif
ifeq ($(TARGET),kinetis)
CFLAGS+= -I$(KINETIS_DRIVERS)/drivers -I$(KINETIS_DRIVERS) -DCPU_$(KINETIS_CPU) -I$(KINETIS_CMSIS)/Include -DDEBUG_CONSOLE_ASSERT_DISABLE=1 -DNVM_FLASH_WRITEONCE=1
APP_OBJS+= $(KINETIS_DRIVERS)/drivers/fsl_clock.o $(KINETIS_DRIVERS)/drivers/fsl_ftfx_flash.o $(KINETIS_DRIVERS)/drivers/fsl_ftfx_cache.o \
$(KINETIS_DRIVERS)/drivers/fsl_ftfx_controller.o $(KINETIS_DRIVERS)/drivers/fsl_gpio.o
endif
standalone:CFLAGS+=-DTEST_APP_STANDALONE
standalone:LDFLAGS:=$(CFLAGS) -T standalone.ld -Wl,-gc-sections -Wl,-Map=image.map
image.bin: image.elf
@echo "\t[BIN] $@"
$(Q)$(OBJCOPY) -O binary $^ $@
@ -38,8 +48,6 @@ image.elf: $(APP_OBJS) $(LSCRIPT)
@echo "\t[LD] $@"
$(Q)$(LD) $(LDFLAGS) $(APP_OBJS) -o $@
standalone:CFLAGS+=-DPLATFORM_stm32f4
standalone:LDFLAGS:=-T standalone.ld -Wl,-gc-sections -Wl,-Map=image.map -nostdlib
standalone: image.bin

32
test-app/hifive1.c 100644
View File

@ -0,0 +1,32 @@
/* main.c
*
* Copyright (C) 2018 wolfSSL Inc.
*
* This file is part of wolfBoot.
*
* wolfBoot is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* wolfBoot is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1335, USA
*/
#include <stdlib.h>
#include <stdint.h>
#include <string.h>
#ifdef PLATFORM_hifive1
void main(void) {
while(1)
;
}
#endif

149
test-app/kinetis.c 100644
View File

@ -0,0 +1,149 @@
/* main.c
*
* Copyright (C) 2018 wolfSSL Inc.
*
* This file is part of wolfBoot.
*
* wolfBoot is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* wolfBoot is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1335, USA
*/
#include <stdlib.h>
#include <stdint.h>
#include <string.h>
#include "fsl_common.h"
#include "fsl_port.h"
#include "fsl_gpio.h"
#include "fsl_clock.h"
#include "wolfboot/wolfboot.h"
/* FRDM-K64 board */
#if defined(CPU_MK64FN1M0VLL12)
#define BOARD_LED_GPIO GPIOB
#define BOARD_LED_GPIO_PORT PORTB
#define BOARD_LED_GPIO_CLOCK kCLOCK_PortB
#define BOARD_LED_GPIO_PIN 23U
/* FRDM-K82 board */
#elif defined (CPU_MK82FN256VLL15)
#define BOARD_LED_GPIO_PORT PORTC
#define BOARD_LED_GPIO_CLOCK kCLOCK_PortC
#define BOARD_LED_GPIO GPIOC
#define BOARD_LED_GPIO_PIN 8U
#endif
#ifdef TEST_APP_STANDALONE
/* This are the registers for the NV flash configuration area.
* Access these field by setting the relative flags in NV_Flash_Config.
*/
#define NVTYPE_LEN (16)
const uint8_t __attribute__((section(".flash_config"))) NV_Flash_Config[NVTYPE_LEN] = {
/* Backdoor comparison key (2 words) */
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
/* P-Flash protection 1 */
0xFF, 0xFF,
/* P-Flash protection 2 */
0xFF, 0xFF,
/* Flash security register */
((0xFE)),
/* Flash option register */
0xFF,
/* EERAM protection register */
0xFF,
/* D-Flash protection register */
0xFF
};
#if defined(CPU_MK82FN256VLL15)
struct stage1_config
{
uint32_t tag;
uint32_t crcStartAddress;
uint32_t crcByteCount;
uint32_t crcExpectedValue;
uint8_t enabledPeripherals;
uint8_t i2cSlaveAddress;
uint16_t peripheralDetectionTimeoutMs;
uint16_t usbVid;
uint16_t usbPid;
uint32_t usbStringsPointer;
uint8_t clockFlags;
uint8_t clockDivider;
uint8_t bootFlags;
uint8_t RESERVED1;
uint32_t mmcauConfigPointer;
uint32_t keyBlobPointer;
uint8_t RESERVED2[8];
uint32_t qspiConfigBlockPtr;
uint8_t RESERVED3[12];
};
const struct stage1_config __attribute__((section(".stage1_config")))
NV_Stage1_Config = {
.tag = 0x6766636BU, /* Magic Number */
.crcStartAddress = 0xFFFFFFFFU, /* Disable CRC check */
.crcByteCount = 0xFFFFFFFFU, /* Disable CRC check */
.crcExpectedValue = 0xFFFFFFFFU, /* Disable CRC check */
.enabledPeripherals = 0x17, /* Enable all peripherals */
.i2cSlaveAddress = 0xFF, /* Use default I2C address */
.peripheralDetectionTimeoutMs = 0x01F4U, /* Use default timeout */
.usbVid = 0xFFFFU, /* Use default USB Vendor ID */
.usbPid = 0xFFFFU, /* Use default USB Product ID */
.usbStringsPointer = 0xFFFFFFFFU, /* Use default USB Strings */
.clockFlags = 0x01, /* Enable High speed mode */
.clockDivider = 0xFF, /* Use clock divider 1 */
.bootFlags = 0x01, /* Enable communication with host */
.mmcauConfigPointer = 0xFFFFFFFFU, /* No MMCAU configuration */
.keyBlobPointer = 0x000001000, /* keyblob data is at 0x1000 */
.qspiConfigBlockPtr = 0xFFFFFFFFU /* No QSPI configuration */
};
#endif
#endif
void main(void) {
int i = 0;
#ifdef CPU_MK64FN1M0VLL12
/* Immediately disable Watchdog after boot */
/* Write Keys to unlock register */
*((volatile unsigned short *)0x4005200E) = 0xC520;
*((volatile unsigned short *)0x4005200E) = 0xD928;
/* disable watchdog via STCTRLH register */
*((volatile unsigned short *)0x40052000) = 0x01D2u;
#endif
gpio_pin_config_t led_config = {
kGPIO_DigitalOutput, 0,
};
CLOCK_EnableClock(BOARD_LED_GPIO_CLOCK);
PORT_SetPinMux(BOARD_LED_GPIO_PORT, BOARD_LED_GPIO_PIN, kPORT_MuxAsGpio);
GPIO_PinWrite(BOARD_LED_GPIO, BOARD_LED_GPIO_PIN, led_config.outputLogic);
BOARD_LED_GPIO->PDDR |= (1U << BOARD_LED_GPIO_PIN);
GPIO_PortClear(BOARD_LED_GPIO, 1u << BOARD_LED_GPIO_PIN);
while(1) {
for(i = 0; i < 7200000; i++) {
}
GPIO_PortToggle(BOARD_LED_GPIO, 1 << BOARD_LED_GPIO_PIN);
}
while(1)
__WFI();
}

52
test-app/nrf52.c 100644
View File

@ -0,0 +1,52 @@
/* main.c
*
* Copyright (C) 2018 wolfSSL Inc.
*
* This file is part of wolfBoot.
*
* wolfBoot is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* wolfBoot is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1335, USA
*/
#include <stdlib.h>
#include <stdint.h>
#include <string.h>
#include "wolfboot/wolfboot.h"
#define GPIO_BASE (0x50000000)
#define GPIO_OUT *((volatile uint32_t *)(GPIO_BASE + 0x504))
#define GPIO_OUTSET *((volatile uint32_t *)(GPIO_BASE + 0x508))
#define GPIO_OUTCLR *((volatile uint32_t *)(GPIO_BASE + 0x50C))
#define GPIO_PIN_CNF ((volatile uint32_t *)(GPIO_BASE + 0x700)) // Array
static void gpiotoggle(uint32_t pin)
{
uint32_t reg_val = GPIO_OUT;
GPIO_OUTCLR = reg_val & (1 << pin);
GPIO_OUTSET = (~reg_val) & (1 << pin);
}
void main(void)
{
uint32_t pin = 19;
int i;
GPIO_PIN_CNF[pin] = 1; /* Output */
while(1) {
gpiotoggle(pin);
for (i = 0; i < 800000; i++) // Wait a bit.
asm volatile ("nop");
}
}

33
test-app/samr21.c 100644
View File

@ -0,0 +1,33 @@
/* main.c
*
* Copyright (C) 2018 wolfSSL Inc.
*
* This file is part of wolfBoot.
*
* wolfBoot is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* wolfBoot is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1335, USA
*/
#include <stdlib.h>
#include <stdint.h>
#include <string.h>
#include "hal.h"
#include "wolfboot/wolfboot.h"
void main(void) {
asm volatile ("cpsie i");
while(1)
WFI();
}

View File

@ -10,6 +10,11 @@ SECTIONS
{
_start_text = .;
KEEP(*(.isr_vector))
. = 0x3c0;
KEEP(*(.stage1_config))
. = 0x400;
KEEP(*(.flash_config))
. = ALIGN(8);
*(.text*)
*(.rodata*)
. = ALIGN(4);

View File

@ -162,4 +162,9 @@ void isr_tim2(void)
time_elapsed++;
}
#else
void isr_tim2(void)
{
}
#endif /** PLATFORM_stm32f4 **/