You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@mynewt.apache.org by ml...@apache.org on 2020/03/29 17:59:54 UTC

[mynewt-core] branch master updated: bsp/pinetime: Add bsp for PineTime smartwatch

This is an automated email from the ASF dual-hosted git repository.

mlaz pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/mynewt-core.git


The following commit(s) were added to refs/heads/master by this push:
     new 89c3805  bsp/pinetime: Add bsp for PineTime smartwatch
     new 220ddec  Merge pull request #2253 from caspermeijn/bsp-pinetime
89c3805 is described below

commit 89c38058336a7662b54cb6fc7889893c7e096675
Author: Casper Meijn <ca...@meijn.net>
AuthorDate: Thu Mar 26 13:42:07 2020 +0100

    bsp/pinetime: Add bsp for PineTime smartwatch
    
    This adds the bsp boilerplate including the pin definitions for the
    peripherals.
---
 hw/bsp/pinetime/boot-pinetime.ld                   |  25 ++
 hw/bsp/pinetime/bsp.yml                            |  62 +++++
 hw/bsp/pinetime/include/bsp/bsp.h                  |  96 +++++++
 hw/bsp/pinetime/pinetime.ld                        |  27 ++
 hw/bsp/pinetime/pinetime_debug.sh                  |  38 +++
 hw/bsp/pinetime/pinetime_download.sh               |  50 ++++
 hw/bsp/pinetime/pkg.yml                            |  37 +++
 .../src/arch/cortex_m4/gcc_startup_nrf52.s         | 301 +++++++++++++++++++++
 hw/bsp/pinetime/src/hal_bsp.c                      |  99 +++++++
 hw/bsp/pinetime/src/sbrk.c                         |  58 ++++
 hw/bsp/pinetime/syscfg.yml                         |  69 +++++
 11 files changed, 862 insertions(+)

diff --git a/hw/bsp/pinetime/boot-pinetime.ld b/hw/bsp/pinetime/boot-pinetime.ld
new file mode 100644
index 0000000..d1f1b99
--- /dev/null
+++ b/hw/bsp/pinetime/boot-pinetime.ld
@@ -0,0 +1,25 @@
+/* Linker script for Nordic Semiconductor nRF5 devices
+ *
+ * Version: Sourcery G++ 4.5-1
+ * Support: https://support.codesourcery.com/GNUToolchain/
+ *
+ * Copyright (c) 2007, 2008, 2009, 2010 CodeSourcery, Inc.
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions.  No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply.
+ */
+MEMORY
+{
+  FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 0x4000
+  RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x10000
+}
+
+/* The bootloader does not contain an image header */
+_imghdr_size = 0x0;
diff --git a/hw/bsp/pinetime/bsp.yml b/hw/bsp/pinetime/bsp.yml
new file mode 100644
index 0000000..c89953d
--- /dev/null
+++ b/hw/bsp/pinetime/bsp.yml
@@ -0,0 +1,62 @@
+#
+# Licensed to the Apache Software Foundation (ASF) under one
+# or more contributor license agreements.  See the NOTICE file
+# distributed with this work for additional information
+# regarding copyright ownership.  The ASF licenses this file
+# to you 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.
+#
+
+bsp.arch: cortex_m4
+bsp.compiler: compiler/arm-none-eabi-m4
+bsp.linkerscript:
+    - "hw/bsp/pinetime/pinetime.ld"
+    - "@apache-mynewt-core/hw/mcu/nordic/nrf52xxx/nrf52.ld"
+bsp.linkerscript.BOOT_LOADER.OVERWRITE:
+    - "hw/bsp/pinetime/boot-pinetime.ld"
+    - "@apache-mynewt-core/hw/mcu/nordic/nrf52xxx/nrf52.ld"
+bsp.part2linkerscript: "hw/bsp/pinetime/split-pinetime.ld"
+bsp.downloadscript: "hw/bsp/pinetime/pinetime_download.sh"
+bsp.debugscript: "hw/bsp/pinetime/pinetime_debug.sh"
+
+bsp.flash_map:
+    areas:
+        # System areas.
+        FLASH_AREA_BOOTLOADER:
+            device: 0
+            offset: 0x00000000
+            size: 16kB
+        FLASH_AREA_IMAGE_0:
+            device: 0
+            offset: 0x00008000
+            size: 232kB
+        FLASH_AREA_IMAGE_1:
+            device: 0
+            offset: 0x00042000
+            size: 232kB
+        FLASH_AREA_IMAGE_SCRATCH:
+            device: 0
+            offset: 0x0007c000
+            size: 4kB
+
+        # User areas.
+        FLASH_AREA_REBOOT_LOG:
+            user_id: 0
+            device: 0
+            offset: 0x00004000
+            size: 16kB
+        FLASH_AREA_NFFS:
+            user_id: 1
+            device: 0
+            offset: 0x0007d000
+            size: 12kB
diff --git a/hw/bsp/pinetime/include/bsp/bsp.h b/hw/bsp/pinetime/include/bsp/bsp.h
new file mode 100644
index 0000000..b7015b2
--- /dev/null
+++ b/hw/bsp/pinetime/include/bsp/bsp.h
@@ -0,0 +1,96 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you 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.
+ */
+
+#ifndef H_BSP_
+#define H_BSP_
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Define special stackos sections */
+#define sec_data_core   __attribute__((section(".data.core")))
+#define sec_bss_core    __attribute__((section(".bss.core")))
+#define sec_bss_nz_core __attribute__((section(".bss.core.nz")))
+
+/* More convenient section placement macros. */
+#define bssnz_t         sec_bss_nz_core
+
+/** Defined in MCU linker script. */
+extern uint8_t _ram_start;
+
+#define RAM_SIZE        0x10000
+
+/* Battery charger SMG40561 */
+#define CHARGER_POWER_PRESENCE_PIN  19 /* P0.19 POWER PRESENCE INDICATION IN */
+#define CHARGER_CHARGE_PIN      12 /* P0.12 CHARGE INDICATION         IN */
+#define BATTERY_VOLTAGE_PIN     31 /* P0.31 BATTERYVOLTAGE (Analog)   IN */
+
+/* Periphiral power control */
+#define POWER_CONTROL_PIN       24 /* P0.24 3V3POWERCONTROL      OUT */
+
+/* 2 wire power button */
+#define PUSH_BUTTON_IN_PIN      13 /* P0.13 PUSH BUTTON_IN       IN */
+#define PUSH_BUTTON_OUT_PIN     15 /* P0.15 PUSH BUTTON_OUT      OUT */
+
+/* Vibrator motor */
+#define VIBRATOR_PIN            16 /* P0.16 VIBRATOR             OUT */
+
+/* LCD display */
+#define LCD_SPI_CLOCK_PIN        2 /* P0.02 SPI-SCK, LCD_SCK     OUT */
+#define LCD_SPI_MOSI_PIN         3 /* P0.03 SPI-MOSI, LCD_SDI    OUT */
+#define LCD_DET_PIN              9 /* P0.09 LCD_DET              OUT */
+#define LCD_WRITE_PIN           18 /* P0.18 LCD_RS               OUT */
+#define LCD_BACKLIGHT_LOW_PIN   14 /* P0.14 LCD_BACKLIGHT_LOW    OUT */
+#define LCD_BACKLIGHT_MED_PIN   22 /* P0.22 LCD_BACKLIGHT_MID    OUT */
+#define LCD_BACKLIGHT_HIGH_PIN  23 /* P0.23 LCD_BACKLIGHT_HIGH   OUT */
+#define LCD_CHIP_SELECT_PIN     25 /* P0.25 LCD_CS               OUT */
+#define LCD_RESET_PIN           26 /* P0.26 LCD_RESET            OUT */
+
+/* SPI NOR Flash PM25LV512 */
+#define FLASH_CLOCK_PIN          2 /* P0.02 SPI-SCK, LCD_SCK     OUT */
+#define FLASH_MOSI_PIN           3 /* P0.03 SPI-MOSI, LCD_SDI    OUT */
+#define FLASH_MISO_PIN           4 /* P0.04 SPI-MISO             IN */
+#define FLASH_SELECT_PIN         5 /* P0.05 SPI-CE#(SPI-NOR)     OUT */
+
+/* Accelerometer i2c BMA421 */
+#define ACCELEROMETER_DATA_PIN   6 /* P0.06 BMA421-SDA, HRS3300-SDA, TP-SDA  I/O */
+#define ACCELEROMETER_CLOCK_PIN  7 /* P0.07 BMA421-SCL, HRS3300-SCL, TP-SCL  OUT */
+#define ACCELEROMETER_INT_PIN    8 /* P0.08 BMA421-INT                       IN */
+
+/* Touchscreen controller i2c */
+#define TOUCH_DATA_PIN           6 /* P0.06 BMA421-SDA, HRS3300-SDA, TP-SDA  I/O */
+#define TOUCH_CLOCK_PIN          7 /* P0.07 BMA421-SCL, HRS3300-SCL, TP-SCL  OUT */
+#define TOUCH_INT_PIN           28 /* P0.28 TP_INT                           IN */
+#define TOUCH_RESET_PIN         10 /* P0.10 TP_RESET                         OUT */
+
+/* Heartrate sensor i2c */
+#define HEARTRATE_DATA_PIN       6 /* P0.06 BMA421-SDA, HRS3300-SDA, TP-SDA  I/O */
+#define HEARTRATE_CLOCK_PIN      7 /* P0.07 BMA421-SCL, HRS3300-SCL, TP-SCL  OUT */
+#define HEARTRATE_INT_PIN       30 /* P0.30 HRS3300-TEST                     IN */
+
+/* apps/blinky support */
+#define LED_BLINK_PIN   LCD_BACKLIGHT_HIGH_PIN
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/hw/bsp/pinetime/pinetime.ld b/hw/bsp/pinetime/pinetime.ld
new file mode 100644
index 0000000..53baaed
--- /dev/null
+++ b/hw/bsp/pinetime/pinetime.ld
@@ -0,0 +1,27 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you 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.
+ */
+
+MEMORY
+{
+  FLASH (rx) : ORIGIN = 0x00008000, LENGTH = 0x3a000
+  RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x10000
+}
+
+/* This linker script is used for images and thus contains an image header */
+_imghdr_size = 0x20;
diff --git a/hw/bsp/pinetime/pinetime_debug.sh b/hw/bsp/pinetime/pinetime_debug.sh
new file mode 100755
index 0000000..ab903eb
--- /dev/null
+++ b/hw/bsp/pinetime/pinetime_debug.sh
@@ -0,0 +1,38 @@
+#!/bin/sh
+# Licensed to the Apache Software Foundation (ASF) under one
+# or more contributor license agreements.  See the NOTICE file
+# distributed with this work for additional information
+# regarding copyright ownership.  The ASF licenses this file
+# to you 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.
+#
+
+# Called with following variables set:
+#  - CORE_PATH is absolute path to @apache-mynewt-core
+#  - BSP_PATH is absolute path to hw/bsp/bsp_name
+#  - BIN_BASENAME is the path to prefix to target binary,
+#    .elf appended to name is the ELF file
+#  - FEATURES holds the target features string
+#  - EXTRA_JTAG_CMD holds extra parameters to pass to jtag software
+#  - RESET set if target should be reset when attaching
+#  - NO_GDB set if we should not start gdb to debug
+#
+. $CORE_PATH/hw/scripts/openocd.sh
+
+FILE_NAME=$BIN_BASENAME.elf
+CFG="-f interface/stlink.cfg -f target/nrf52.cfg"
+# Exit openocd when gdb detaches.
+EXTRA_JTAG_CMD="$EXTRA_JTAG_CMD; nrf52.cpu configure -event gdb-detach {if {[nrf52.cpu curstate] eq \"halted\"} resume;shutdown}"
+
+openocd_debug
+
diff --git a/hw/bsp/pinetime/pinetime_download.sh b/hw/bsp/pinetime/pinetime_download.sh
new file mode 100755
index 0000000..0f1cdd6
--- /dev/null
+++ b/hw/bsp/pinetime/pinetime_download.sh
@@ -0,0 +1,50 @@
+#!/bin/sh
+# Licensed to the Apache Software Foundation (ASF) under one
+# or more contributor license agreements.  See the NOTICE file
+# distributed with this work for additional information
+# regarding copyright ownership.  The ASF licenses this file
+# to you 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.
+#
+
+# Called with following variables set:
+#  - CORE_PATH is absolute path to @apache-mynewt-core
+#  - BSP_PATH is absolute path to hw/bsp/bsp_name
+#  - BIN_BASENAME is the path to prefix to target binary,
+#    .elf appended to name is the ELF file
+#  - IMAGE_SLOT is the image slot to download to (for non-mfg-image, non-boot)
+#  - FEATURES holds the target features string
+#  - EXTRA_JTAG_CMD holds extra parameters to pass to jtag software
+#  - MFG_IMAGE is "1" if this is a manufacturing image
+#  - FLASH_OFFSET contains the flash offset to download to
+#  - BOOT_LOADER is set if downloading a bootloader
+
+. $CORE_PATH/hw/scripts/openocd.sh
+
+CFG="-f interface/stlink.cfg -f target/nrf52.cfg"
+
+if [ "$MFG_IMAGE" ]; then
+    FLASH_OFFSET=0
+fi
+
+# We write the config registers for BPROT so that NVMC write
+# protection gets disabled for all blocks of the flash
+# We also write the DISABLEINDEBUG register so that, write
+# protection gets disabled in debug register by default
+CFG_POST_INIT="mww 0x40000600 0;mww 0x40000604 0;mww 0x40000608 1;\
+               mww 0x40000610 0;mww 0x40000614 0;
+              "
+
+common_file_to_load
+openocd_load
+openocd_reset_run
diff --git a/hw/bsp/pinetime/pkg.yml b/hw/bsp/pinetime/pkg.yml
new file mode 100644
index 0000000..4cdebe9
--- /dev/null
+++ b/hw/bsp/pinetime/pkg.yml
@@ -0,0 +1,37 @@
+#
+# Licensed to the Apache Software Foundation (ASF) under one
+# or more contributor license agreements.  See the NOTICE file
+# distributed with this work for additional information
+# regarding copyright ownership.  The ASF licenses this file
+# to you 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.
+#
+
+pkg.name: "hw/bsp/pinetime"
+pkg.type: bsp
+pkg.description: "BSP definition for the Pine64 PineTime smartwatch"
+pkg.author: "Apache Mynewt <de...@mynewt.apache.org>"
+pkg.homepage: "http://mynewt.apache.org/"
+pkg.keywords:
+    - nrf52
+    - Pine64
+    - PineTime
+
+pkg.cflags:
+    - '-DNRF52'
+    # TODO: Move to more specific variable, however this currently causes a build failure '-DNRF52832_XXAA'
+
+pkg.deps:
+    - '@apache-mynewt-core/hw/mcu/nordic/nrf52xxx'
+    - '@apache-mynewt-core/kernel/os'
+    - '@apache-mynewt-core/libc/baselibc'
diff --git a/hw/bsp/pinetime/src/arch/cortex_m4/gcc_startup_nrf52.s b/hw/bsp/pinetime/src/arch/cortex_m4/gcc_startup_nrf52.s
new file mode 100644
index 0000000..8ce6ee5
--- /dev/null
+++ b/hw/bsp/pinetime/src/arch/cortex_m4/gcc_startup_nrf52.s
@@ -0,0 +1,301 @@
+/*
+Copyright (c) 2015, Nordic Semiconductor ASA
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+
+* Redistributions of source code must retain the above copyright notice, this
+  list of conditions and the following disclaimer.
+
+* Redistributions in binary form must reproduce the above copyright notice,
+  this list of conditions and the following disclaimer in the documentation
+  and/or other materials provided with the distribution.
+
+* Neither the name of Nordic Semiconductor ASA nor the names of its
+  contributors may be used to endorse or promote products derived from
+  this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+
+/*
+NOTE: Template files (including this one) are application specific and therefore
+expected to be copied into the application project folder prior to its use!
+*/
+
+    .syntax unified
+    .arch armv7-m
+
+    .section .stack
+    .align 3
+    .equ    Stack_Size, 432
+    .globl    __StackTop
+    .globl    __StackLimit
+__StackLimit:
+    .space    Stack_Size
+    .size __StackLimit, . - __StackLimit
+__StackTop:
+    .size __StackTop, . - __StackTop
+
+    .section .heap
+    .align 3
+#ifdef __HEAP_SIZE
+    .equ    Heap_Size, __HEAP_SIZE
+#else
+    .equ    Heap_Size, 0
+#endif
+    .globl    __HeapBase
+    .globl    __HeapLimit
+__HeapBase:
+    .if    Heap_Size
+    .space    Heap_Size
+    .endif
+    .size __HeapBase, . - __HeapBase
+__HeapLimit:
+    .size __HeapLimit, . - __HeapLimit
+
+    .section .isr_vector
+    .align 2
+    .globl __isr_vector
+__isr_vector:
+    .long    __StackTop            /* Top of Stack */
+    .long   Reset_Handler               /* Reset Handler */
+    .long   NMI_Handler                 /* NMI Handler */
+    .long   HardFault_Handler           /* Hard Fault Handler */
+    .long   0                           /* Reserved */
+    .long   0                           /* Reserved */
+    .long   0                           /* Reserved */
+    .long   0                           /* Reserved */
+    .long   0                           /* Reserved */
+    .long   0                           /* Reserved */
+    .long   0                           /* Reserved */
+    .long   SVC_Handler                 /* SVCall Handler */
+    .long   0                           /* Reserved */
+    .long   0                           /* Reserved */
+    .long   PendSV_Handler              /* PendSV Handler */
+    .long   SysTick_Handler             /* SysTick Handler */
+
+  /* External Interrupts */
+    .long   POWER_CLOCK_IRQHandler
+    .long   RADIO_IRQHandler
+    .long   UARTE0_UART0_IRQHandler
+    .long   SPIM0_SPIS0_TWIM0_TWIS0_SPI0_TWI0_IRQHandler
+    .long   SPIM1_SPIS1_TWIM1_TWIS1_SPI1_TWI1_IRQHandler
+    .long   NFCT_IRQHandler
+    .long   GPIOTE_IRQHandler
+    .long   SAADC_IRQHandler
+    .long   TIMER0_IRQHandler
+    .long   TIMER1_IRQHandler
+    .long   TIMER2_IRQHandler
+    .long   RTC0_IRQHandler
+    .long   TEMP_IRQHandler
+    .long   RNG_IRQHandler
+    .long   ECB_IRQHandler
+    .long   CCM_AAR_IRQHandler
+    .long   WDT_IRQHandler
+    .long   RTC1_IRQHandler
+    .long   QDEC_IRQHandler
+    .long   COMP_LPCOMP_IRQHandler
+    .long   SWI0_EGU0_IRQHandler
+    .long   SWI1_EGU1_IRQHandler
+    .long   SWI2_EGU2_IRQHandler
+    .long   SWI3_EGU3_IRQHandler
+    .long   SWI4_EGU4_IRQHandler
+    .long   SWI5_EGU5_IRQHandler
+    .long   TIMER3_IRQHandler
+    .long   TIMER4_IRQHandler
+    .long   PWM0_IRQHandler
+    .long   PDM_IRQHandler
+    .long   0                         /*Reserved */
+    .long   0                         /*Reserved */
+    .long   MWU_IRQHandler
+    .long   PWM1_IRQHandler
+    .long   PWM2_IRQHandler
+    .long   SPIM2_SPIS2_SPI2_IRQHandler
+    .long   RTC2_IRQHandler
+    .long   I2S_IRQHandler
+
+    .size    __isr_vector, . - __isr_vector
+
+/* Reset Handler */
+
+    .text
+    .thumb
+    .thumb_func
+    .align 1
+    .globl    Reset_Handler
+    .type    Reset_Handler, %function
+Reset_Handler:
+    .fnstart
+
+    /* Clear BSS */
+    mov     r0, #0
+    ldr     r2, =__bss_start__
+    ldr     r3, =__bss_end__
+.bss_zero_loop:
+    cmp     r2, r3
+    itt     lt
+    strlt   r0, [r2], #4
+    blt    .bss_zero_loop
+
+
+/*     Loop to copy data from read only memory to RAM. The ranges
+ *      of copy from/to are specified by following symbols evaluated in
+ *      linker script.
+ *      __etext: End of code section, i.e., begin of data sections to copy from.
+ *      __data_start__/__data_end__: RAM address range that data should be
+ *      copied to. Both must be aligned to 4 bytes boundary.  */
+    ldr    r1, =__etext
+    ldr    r2, =__data_start__
+    ldr    r3, =__data_end__
+
+    subs    r3, r2
+    ble     .LC0
+
+.LC1:
+    subs    r3, 4
+    ldr    r0, [r1,r3]
+    str    r0, [r2,r3]
+    bgt    .LC1
+
+.LC0:
+
+    LDR     R0, =__HeapBase
+    LDR     R1, =__HeapLimit
+    BL      _sbrkInit
+
+    LDR     R0, =SystemInit
+    BLX     R0
+
+    BL      hal_system_init
+
+    LDR     R0, =_start
+    BX      R0
+
+    .pool
+    .cantunwind
+    .fnend
+    .size   Reset_Handler,.-Reset_Handler
+
+    .section ".text"
+
+
+/* Dummy Exception Handlers (infinite loops which can be modified) */
+
+    .weak   NMI_Handler
+    .type   NMI_Handler, %function
+NMI_Handler:
+    B       .
+    .size   NMI_Handler, . - NMI_Handler
+
+
+    .weak   HardFault_Handler
+    .type   HardFault_Handler, %function
+HardFault_Handler:
+    B       .
+    .size   HardFault_Handler, . - HardFault_Handler
+
+
+    .weak   MemoryManagement_Handler
+    .type   MemoryManagement_Handler, %function
+MemoryManagement_Handler:
+    B       .
+    .size   MemoryManagement_Handler, . - MemoryManagement_Handler
+
+
+    .weak   BusFault_Handler
+    .type   BusFault_Handler, %function
+BusFault_Handler:
+    B       .
+    .size   BusFault_Handler, . - BusFault_Handler
+
+
+    .weak   UsageFault_Handler
+    .type   UsageFault_Handler, %function
+UsageFault_Handler:
+    B       .
+    .size   UsageFault_Handler, . - UsageFault_Handler
+
+
+    .weak   SVC_Handler
+    .type   SVC_Handler, %function
+SVC_Handler:
+    B       .
+    .size   SVC_Handler, . - SVC_Handler
+
+
+    .weak   PendSV_Handler
+    .type   PendSV_Handler, %function
+PendSV_Handler:
+    B       .
+    .size   PendSV_Handler, . - PendSV_Handler
+
+
+    .weak   SysTick_Handler
+    .type   SysTick_Handler, %function
+SysTick_Handler:
+    B       .
+    .size   SysTick_Handler, . - SysTick_Handler
+
+
+/* IRQ Handlers */
+
+    .globl  Default_Handler
+    .type   Default_Handler, %function
+Default_Handler:
+    B       .
+    .size   Default_Handler, . - Default_Handler
+
+    .macro  IRQ handler
+    .weak   \handler
+    .set    \handler, Default_Handler
+    .endm
+
+    IRQ  POWER_CLOCK_IRQHandler
+    IRQ  RADIO_IRQHandler
+    IRQ  UARTE0_UART0_IRQHandler
+    IRQ  SPIM0_SPIS0_TWIM0_TWIS0_SPI0_TWI0_IRQHandler
+    IRQ  SPIM1_SPIS1_TWIM1_TWIS1_SPI1_TWI1_IRQHandler
+    IRQ  NFCT_IRQHandler
+    IRQ  GPIOTE_IRQHandler
+    IRQ  SAADC_IRQHandler
+    IRQ  TIMER0_IRQHandler
+    IRQ  TIMER1_IRQHandler
+    IRQ  TIMER2_IRQHandler
+    IRQ  RTC0_IRQHandler
+    IRQ  TEMP_IRQHandler
+    IRQ  RNG_IRQHandler
+    IRQ  ECB_IRQHandler
+    IRQ  CCM_AAR_IRQHandler
+    IRQ  WDT_IRQHandler
+    IRQ  RTC1_IRQHandler
+    IRQ  QDEC_IRQHandler
+    IRQ  COMP_LPCOMP_IRQHandler
+    IRQ  SWI0_EGU0_IRQHandler
+    IRQ  SWI1_EGU1_IRQHandler
+    IRQ  SWI2_EGU2_IRQHandler
+    IRQ  SWI3_EGU3_IRQHandler
+    IRQ  SWI4_EGU4_IRQHandler
+    IRQ  SWI5_EGU5_IRQHandler
+    IRQ  TIMER3_IRQHandler
+    IRQ  TIMER4_IRQHandler
+    IRQ  PWM0_IRQHandler
+    IRQ  PDM_IRQHandler
+    IRQ  MWU_IRQHandler
+    IRQ  PWM1_IRQHandler
+    IRQ  PWM2_IRQHandler
+    IRQ  SPIM2_SPIS2_SPI2_IRQHandler
+    IRQ  RTC2_IRQHandler
+    IRQ  I2S_IRQHandler
+
+  .end
diff --git a/hw/bsp/pinetime/src/hal_bsp.c b/hw/bsp/pinetime/src/hal_bsp.c
new file mode 100644
index 0000000..19db06f
--- /dev/null
+++ b/hw/bsp/pinetime/src/hal_bsp.c
@@ -0,0 +1,99 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you 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.
+ */
+
+#include <inttypes.h>
+#include <assert.h>
+#include "syscfg/syscfg.h"
+#include "sysflash/sysflash.h"
+#include "hal/hal_system.h"
+#include "hal/hal_flash_int.h"
+#include "hal/hal_timer.h"
+#include "hal/hal_bsp.h"
+#include "os/os.h"
+#include "bsp/bsp.h"
+#include "mcu/nrf52_hal.h"
+#include "mcu/nrf52_periph.h"
+
+/** What memory to include in coredump. */
+static const struct hal_bsp_mem_dump dump_cfg[] = {
+    [0] = {
+        .hbmd_start = &_ram_start,
+        .hbmd_size = RAM_SIZE,
+    }
+};
+
+const struct hal_bsp_mem_dump *
+hal_bsp_core_dump(int *area_cnt)
+{
+    *area_cnt = sizeof(dump_cfg) / sizeof(dump_cfg[0]);
+    return dump_cfg;
+}
+
+/**
+ * Retrieves the flash device with the specified ID.  Returns NULL if no such
+ * device exists.
+ */
+const struct hal_flash *
+hal_bsp_flash_dev(uint8_t id)
+{
+    switch (id) {
+    case 0:
+        /* MCU internal flash. */
+        return &nrf52k_flash_dev;
+
+    default:
+        /* External flash.  Assume not present in this BSP. */
+        return NULL;
+    }
+}
+
+/**
+ * Retrieves the configured priority for the given interrupt. If no priority
+ * is configured, returns the priority passed in.
+ *
+ * @param irq_num               The IRQ being queried.
+ * @param pri                   The default priority if none is configured.
+ *
+ * @return uint32_t             The specified IRQ's priority.
+ */
+uint32_t
+hal_bsp_get_nvic_priority(int irq_num, uint32_t pri)
+{
+    uint32_t cfg_pri;
+
+    switch (irq_num) {
+    /* Radio gets highest priority */
+    case RADIO_IRQn:
+        cfg_pri = 0;
+        break;
+    default:
+        cfg_pri = pri;
+    }
+    return cfg_pri;
+}
+
+void
+hal_bsp_init(void)
+{
+    /* Make sure system clocks have started. */
+    hal_system_clock_start();
+
+    /* Create all available nRF52840 peripherals */
+    nrf52_periph_create();
+}
diff --git a/hw/bsp/pinetime/src/sbrk.c b/hw/bsp/pinetime/src/sbrk.c
new file mode 100644
index 0000000..6402c8a
--- /dev/null
+++ b/hw/bsp/pinetime/src/sbrk.c
@@ -0,0 +1,58 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you 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.
+ */
+
+/* put these in the data section so they are not cleared by _start */
+static char *sbrkBase __attribute__ ((section (".data")));
+static char *sbrkLimit __attribute__ ((section (".data")));
+static char *brk __attribute__ ((section (".data")));
+
+void
+_sbrkInit(char *base, char *limit)
+{
+    sbrkBase = base;
+    sbrkLimit = limit;
+    brk = base;
+}
+
+void *
+_sbrk(int incr)
+{
+    void *prev_brk;
+
+    if (incr < 0) {
+        /* Returning memory to the heap. */
+        incr = -incr;
+        if (brk - incr < sbrkBase) {
+            prev_brk = (void *)-1;
+        } else {
+            prev_brk = brk;
+            brk -= incr;
+        }
+    } else {
+        /* Allocating memory from the heap. */
+        if (sbrkLimit - brk >= incr) {
+            prev_brk = brk;
+            brk += incr;
+        } else {
+            prev_brk = (void *)-1;
+        }
+    }
+
+    return prev_brk;
+}
diff --git a/hw/bsp/pinetime/syscfg.yml b/hw/bsp/pinetime/syscfg.yml
new file mode 100644
index 0000000..38cfb47
--- /dev/null
+++ b/hw/bsp/pinetime/syscfg.yml
@@ -0,0 +1,69 @@
+#
+# Licensed to the Apache Software Foundation (ASF) under one
+# or more contributor license agreements.  See the NOTICE file
+# distributed with this work for additional information
+# regarding copyright ownership.  The ASF licenses this file
+# to you 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.
+#
+
+# Settings this BSP defines.
+syscfg.defs:
+    BSP_NRF52:
+        description: 'Set to indicate that BSP has NRF52'
+        value: 1
+
+# Settings this BSP overrides.
+syscfg.vals:
+    # Enable nRF52832 MCU
+    MCU_TARGET: nRF52832
+
+    # 32.768 kHz crystal oscillator
+    MCU_LFCLK_SOURCE: LFXO      
+
+    # Enable DC/DC regulator
+    MCU_DCDC_ENABLED: 1
+
+    ###########################################################################
+    # Default Pins for Peripherals
+
+    # SPI port 0 connected to ST7789 display
+    SPI_0_MASTER_PIN_SCK:  2  # P0.02: SPI-SCK, LCD_SCK
+    SPI_0_MASTER_PIN_MOSI: 3  # P0.03: SPI-MOSI, LCD_SDI
+    SPI_0_MASTER_PIN_MISO: 4  # P0.04: SPI-MISO
+
+    # I2C port 1 connected to CST816S touch controller, BMA421 accelerometer, HRS3300 heart rate sensor 
+    I2C_1_PIN_SCL: 7  # P0.07: BMA421-SCL, HRS3300-SCL, TP-SCLOUT
+    I2C_1_PIN_SDA: 6  # P0.06: BMA421-SDA, HRS3300-SDA, TP-SDAI/O
+
+    # UART port 0 is disabled
+    UART_0: 0
+
+    # Configure NFC pins as GPIO P0.09, P0.10
+    NFC_PINS_AS_GPIO: 1
+
+    # ADC needed for battery voltage
+    ADC_0: 1
+
+    # Define flash areas
+    CONFIG_FCB_FLASH_AREA: FLASH_AREA_NFFS
+    REBOOT_LOG_FLASH_AREA: FLASH_AREA_REBOOT_LOG
+    NFFS_FLASH_AREA: FLASH_AREA_NFFS
+    COREDUMP_FLASH_AREA: FLASH_AREA_IMAGE_1
+
+syscfg.vals.BLE_CONTROLLER:
+    TIMER_0: 0
+    TIMER_5: 1
+    OS_CPUTIME_FREQ: 32768
+    OS_CPUTIME_TIMER_NUM: 5
+    BLE_LL_RFMGMT_ENABLE_TIME: 1500