From cdf0f4ffc9e4f39885b5a212a68a3b6a0d4565cb Mon Sep 17 00:00:00 2001 From: Max Regan Date: Wed, 3 Jun 2020 04:51:19 +0000 Subject: [PATCH] Update such that tests pass for v1.2 This includes minor updates for the th different MCU variant, and bugfixes. Resolves #7 --- .dir-locals.el | 9 +- .gitlab-ci.yml | 4 +- firmware/Bsp/Drivers/GpioDriver.cpp | 2 +- firmware/Bsp/Drivers/LptimPwm.cpp | 6 +- firmware/Bsp/Drivers/RtcDriver.cpp | 6 +- firmware/Bsp/Drivers/RtcDriver.h | 5 +- firmware/Bsp/Drivers/UsartDriver.cpp | 13 +- firmware/Bsp/Mcu/Mcu.h | 4 +- firmware/Bsp/Mcu/stm32l010c6.S | 317 +++++++++++++++++++++++++++ firmware/Bsp/Mcu/stm32l010c6.ld | 223 +++++++++++++++++++ firmware/Bsp/macros.h | 6 +- firmware/Makefile | 4 +- firmware/Test/clock.cpp | 10 +- firmware/Test/fail.cpp | 8 +- firmware/Test/lptim.cpp | 18 +- firmware/Test/pass.cpp | 8 +- firmware/Test/periodic_alarms.cpp | 11 +- firmware/Test/set_time.cpp | 10 +- firmware/Test/stop.cpp | 8 +- firmware/Test/timeout.cpp | 8 +- firmware/Test/wakeup_irq.cpp | 15 +- test/src/tr_test/test.py | 11 +- 22 files changed, 649 insertions(+), 57 deletions(-) create mode 100644 firmware/Bsp/Mcu/stm32l010c6.S create mode 100644 firmware/Bsp/Mcu/stm32l010c6.ld diff --git a/.dir-locals.el b/.dir-locals.el index 6e1184b..e383bb9 100644 --- a/.dir-locals.el +++ b/.dir-locals.el @@ -1,7 +1,12 @@ (;; Tell projectile about how to compile this project - (nil . ((projectile-project-compilation-cmd . "make -C firmware/ BOARD=devboard") + (nil . ((projectile-project-compilation-cmd . "make -C firmware/ TOOL_PREFIX=/opt/arm/gcc-arm-none-eabi-8-2019-q3-update/bin/arm-none-eabi-") (projectile-project-test-cmd . "test/src/tr_test/test.py") (python-shell-interpreter . "python3") - (gud-gdb-command-name . "arm-none-eabi-gdb -i=mi"))) + (gud-gdb-command-name . "/opt/arm/gcc-arm-none-eabi-8-2019-q3-update/bin/arm-none-eabi-gdb -i=mi") + (eval . (defun tr-serial() + (interactive) + (make-serial-process :port "/dev/ttyUSB0" :speed 115200 + :name "tr-watch terminal" :stopbits 1 :bytesize 8) + (switch-to-buffer "tr-watch terminal"))))) ;; Automatically run python-black on python buffers when they are saved (python-mode . ((eval . (python-black-on-save-mode))))) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 4d6a9fa..a724a2d 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -23,10 +23,10 @@ build-watch: variables: BOARD: watch -test-devboard: +test-watch: stage: test dependencies: - - build-devboard + - build-watch tags: - tr-hw - privileged diff --git a/firmware/Bsp/Drivers/GpioDriver.cpp b/firmware/Bsp/Drivers/GpioDriver.cpp index a71695e..44a3671 100644 --- a/firmware/Bsp/Drivers/GpioDriver.cpp +++ b/firmware/Bsp/Drivers/GpioDriver.cpp @@ -107,7 +107,7 @@ namespace BSP { if (mode == output_mode_t::OPEN_DRAIN) { SET(m_gpio->OTYPER, mask); } else { - SET(m_gpio->OTYPER, mask); + CLR(m_gpio->OTYPER, mask); } } diff --git a/firmware/Bsp/Drivers/LptimPwm.cpp b/firmware/Bsp/Drivers/LptimPwm.cpp index 50bbf49..be223bf 100644 --- a/firmware/Bsp/Drivers/LptimPwm.cpp +++ b/firmware/Bsp/Drivers/LptimPwm.cpp @@ -50,7 +50,7 @@ void LptimPwm::init_lptim() /*!< Set the LSE clock to be the source of the LPTIM */ SET_TO(RCC->CCIPR, RCC_CCIPR_LPTIM1SEL, - RCC_CCIPR_LPTIM1SEL_0); + RCC_CCIPR_LPTIM1SEL_0 | RCC_CCIPR_LPTIM1SEL_1); /** Write CR CFGR and IER while LPTIM is disabled (LPTIM_CR_ENABLE not yet set) */ /*!< Disable Interrupts (not needed, this is the default */ @@ -82,8 +82,8 @@ void LptimPwm::init_lptim() /*!< Produce a 60Hz, signal with minimal "high" time. The display only needs 2us of "high" time on EXTCOMM, and it draws a fair amount of power. */ - LPTIM1->ARR = 0x27F; - LPTIM1->CMP = 0x27E; + LPTIM1->ARR = (32768 / 50) + 1; + LPTIM1->CMP = (32768 / 50); while(!(LPTIM1->ISR & LPTIM_ISR_ARROK)) {} while(!(LPTIM1->ISR & LPTIM_ISR_CMPOK)) {} diff --git a/firmware/Bsp/Drivers/RtcDriver.cpp b/firmware/Bsp/Drivers/RtcDriver.cpp index e2ef30e..47343ea 100644 --- a/firmware/Bsp/Drivers/RtcDriver.cpp +++ b/firmware/Bsp/Drivers/RtcDriver.cpp @@ -253,11 +253,11 @@ ReturnCode RtcDriver::set_time(const BSP::WallClockTime &wall_time) #if defined(STM32L0XX) CLR(RTC->ISR, RTC_ISR_INIT); - while (!(RTC->ISR & RTC_ISR_INITF)) {} // FIXME: this is probably inverted + while (RTC->ISR & RTC_ISR_INITF) {} while (!(RTC->ISR & RTC_ISR_RSF)) {} #elif defined(STM32L4XX) CLR(RTC->ICSR, RTC_ICSR_INIT); - while ((RTC->ICSR & RTC_ICSR_INITF)) {} + while (RTC->ICSR & RTC_ICSR_INITF) {} while (!(RTC->ICSR & RTC_ICSR_RSF)) {} #else #error "Unsupported device type" @@ -415,7 +415,9 @@ extern "C" void RTC_IRQHandler() CLR(RTC->ISR, RTC_ISR_WUTF); // Disable the Wakeup timer (its periodic, but we use it as a // one-shot timer + RtcDriver::enable_rtc_write(); CLR(RTC->CR, RTC_CR_WUTE); + RtcDriver::disable_rtc_write(); } } diff --git a/firmware/Bsp/Drivers/RtcDriver.h b/firmware/Bsp/Drivers/RtcDriver.h index 9ffead4..935e2b5 100644 --- a/firmware/Bsp/Drivers/RtcDriver.h +++ b/firmware/Bsp/Drivers/RtcDriver.h @@ -52,11 +52,12 @@ public: static void increment_wakeup_count(); static void increment_alarm_count(); + static void enable_rtc_write(); + static void disable_rtc_write(); + private: static BSP::ReturnCode init_hw(); - static void enable_rtc_write(); - static void disable_rtc_write(); static void enable_rtc_wakeup_interrupt(); static void enable_periodic_alarm(); diff --git a/firmware/Bsp/Drivers/UsartDriver.cpp b/firmware/Bsp/Drivers/UsartDriver.cpp index 30bdaf1..570bd2a 100644 --- a/firmware/Bsp/Drivers/UsartDriver.cpp +++ b/firmware/Bsp/Drivers/UsartDriver.cpp @@ -36,8 +36,6 @@ UsartDriver::UsartDriver(USART_TypeDef *usart, TaskScheduler &scheduler) void UsartDriver::init() { - // TODO: This is all hardcoded for USART1 (doesn't exist on STM32L031) - #if defined(STM32L0XX) if (m_usart == USART2) { RCC->APB1ENR |= RCC_APB1ENR_USART2EN; @@ -54,14 +52,9 @@ void UsartDriver::init() #error "Unknown device family" #endif - // Set TX (PA9) to output, push/pull - SET_TO(GPIOA->AFR[1], GPIO_AFRH_AFSEL9, 7u << GPIO_AFRH_AFSEL9_Pos); //AF7 (USART1_TX) - SET_TO(GPIOA->MODER, GPIO_MODER_MODE9, 2u << GPIO_MODER_MODE9_Pos); // Alternate Function - GPIOA->OTYPER &= ~GPIO_OTYPER_OT_9; // push/pull - GPIOA->PUPDR &= ~GPIO_PUPDR_PUPD9; // no pullup, no pulldown - - m_usart->BRR = (4100000) /115200L; // set baudrate (APBCLK / baud) - m_usart->CR1 |= (USART_CR1_RE | USART_CR1_TE); // RX, TX enable + // TODO: Don't hardcode the main clock value here + m_usart->BRR = (4100000) / 115200L; // set baudrate (APBCLK / baud) + m_usart->CR1 |= (USART_CR1_TE); // TX enable m_usart->CR1 |= USART_CR1_UE; // USART enable } diff --git a/firmware/Bsp/Mcu/Mcu.h b/firmware/Bsp/Mcu/Mcu.h index fc57c27..4695e24 100644 --- a/firmware/Bsp/Mcu/Mcu.h +++ b/firmware/Bsp/Mcu/Mcu.h @@ -21,7 +21,9 @@ #pragma once -#if defined(STM32L031xx) +#if defined(STM32L010C6) +#include "stm32l010x6.h" +#elif defined(STM32L031xx) #include "stm32l031xx.h" #elif defined(STM32L412xx) #include "stm32l412xx.h" diff --git a/firmware/Bsp/Mcu/stm32l010c6.S b/firmware/Bsp/Mcu/stm32l010c6.S new file mode 100644 index 0000000..6c5a6d2 --- /dev/null +++ b/firmware/Bsp/Mcu/stm32l010c6.S @@ -0,0 +1,317 @@ +/* File: startup_ARMCM0.S + * Purpose: startup file for Cortex-M0 devices. Should use with + * GCC for ARM Embedded Processors + * Version: V2.01 + * Date: 12 June 2014 + * + */ +/* Copyright (c) 2011 - 2014 ARM LIMITED + + 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 ARM 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 COPYRIGHT HOLDERS AND 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. + ---------------------------------------------------------------------------*/ + + + .syntax unified + .arch armv6-m + + .section .stack + .align 3 + .equ Stack_Size, __STACK_SIZE + .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, 0x00000C00 +#endif + .globl __HeapBase + .globl __HeapLimit +__HeapBase: + .if Heap_Size + .space Heap_Size + .endif + .size __HeapBase, . - __HeapBase +__HeapLimit: + .size __HeapLimit, . - __HeapLimit + + .section .vectors + .align 2 + .globl __Vectors +__Vectors: + .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 WWDG_IRQHandler /* 0: Watchdog Timer */ + .long PVD_IRQHandler /* 1: Real Time Clock */ + .long RTC_IRQHandler /* 2: Timer0 / Timer1 */ + .long FLASH_IRQHandler /* 3: Timer2 / Timer3 */ + .long RCC_CRS_IRQHandler /* 4: MCIa */ + .long EXTI_1_0_IRQHandler /* 5: MCIb */ + .long EXTI_3_2_IRQHandler /* 6: UART0 - DUT FPGA */ + .long EXTI_15_4_IRQHandler /* 7: UART1 - DUT FPGA */ + .long 0 /* 8: UART2 - reserved */ + .long DMA1_CHANNEL1_IRQHandler /* 8: UART2 - DUT FPGA */ + .long DMA1_CHANNEL3_2_IRQHandler /* 9: UART4 - not connected */ + .long DMA_CHANNEL_7_4_IRQHandler /* 10: AACI / AC97 */ + .long ADC_COMP_IRQHandler /* 11: CLCD Combined Interrupt */ + .long LPTIM1_IRQHandler /* 12: Ethernet */ + .long USART4_USART5_IRQHandler /* 13: USB Device */ + .long TIM2_IRQHandler /* 14: USB Host Controller */ + .long TIM3_IRQHandler /* 15: Character LCD */ + .long TIM6_IRQHandler /* 16: Flexray */ + .long TIM7_IRQHandler /* 17: CAN */ + .long 0 /* 18: LIN */ + .long TIM21_IRQHandler /* 19: I2C ADC/DAC */ + .long I2C3_IRQHandler /* 20: Reserved */ + .long TIM22_IRQHandler /* 21: Reserved */ + + /* TODO: There are more but I'm lazy */ + .long 0 + .long 0 + .long 0 + .long 0 + .long 0 + .long 0 + .long 0 + .long 0 + .long 0 + .size __Vectors, . - __Vectors + + .text + .thumb + .thumb_func + .align 1 + .globl Reset_Handler + .type Reset_Handler, %function +Reset_Handler: +/* Firstly it copies data from read only memory to RAM. There are two schemes + * to copy. One can copy more than one sections. Another can only copy + * one section. The former scheme needs more instructions and read-only + * data to implement than the latter. + * Macro __STARTUP_COPY_MULTIPLE is used to choose between two schemes. */ + +#ifdef __STARTUP_COPY_MULTIPLE +/* Multiple sections scheme. + * + * Between symbol address __copy_table_start__ and __copy_table_end__, + * there are array of triplets, each of which specify: + * offset 0: LMA of start of a section to copy from + * offset 4: VMA of start of a section to copy to + * offset 8: size of the section to copy. Must be multiply of 4 + * + * All addresses must be aligned to 4 bytes boundary. + */ + ldr r4, =__copy_table_start__ + ldr r5, =__copy_table_end__ + +.L_loop0: + cmp r4, r5 + bge .L_loop0_done + ldr r1, [r4] + ldr r2, [r4, #4] + ldr r3, [r4, #8] + +.L_loop0_0: + subs r3, #4 + blt .L_loop0_0_done + ldr r0, [r1, r3] + str r0, [r2, r3] + b .L_loop0_0 + +.L_loop0_0_done: + adds r4, #12 + b .L_loop0 + +.L_loop0_done: +#else +/* Single section scheme. + * + * The ranges of copy from/to are specified by following symbols + * __etext: LMA of start of the section to copy from. Usually end of text + * __data_start__: VMA of start of the section to copy to + * __data_end__: VMA of end of the section to copy to + * + * All addresses must be aligned to 4 bytes boundary. + */ + ldr r1, =__etext + ldr r2, =__data_start__ + ldr r3, =__data_end__ + + subs r3, r2 + ble .L_loop1_done + +.L_loop1: + subs r3, #4 + ldr r0, [r1,r3] + str r0, [r2,r3] + bgt .L_loop1 + +.L_loop1_done: +#endif /*__STARTUP_COPY_MULTIPLE */ + +/* This part of work usually is done in C library startup code. Otherwise, + * define this macro to enable it in this startup. + * + * There are two schemes too. One can clear multiple BSS sections. Another + * can only clear one section. The former is more size expensive than the + * latter. + * + * Define macro __STARTUP_CLEAR_BSS_MULTIPLE to choose the former. + * Otherwise efine macro __STARTUP_CLEAR_BSS to choose the later. + */ +#ifdef __STARTUP_CLEAR_BSS_MULTIPLE +/* Multiple sections scheme. + * + * Between symbol address __copy_table_start__ and __copy_table_end__, + * there are array of tuples specifying: + * offset 0: Start of a BSS section + * offset 4: Size of this BSS section. Must be multiply of 4 + */ + ldr r3, =__zero_table_start__ + ldr r4, =__zero_table_end__ + +.L_loop2: + cmp r3, r4 + bge .L_loop2_done + ldr r1, [r3] + ldr r2, [r3, #4] + movs r0, 0 + +.L_loop2_0: + subs r2, #4 + blt .L_loop2_0_done + str r0, [r1, r2] + b .L_loop2_0 +.L_loop2_0_done: + + adds r3, #8 + b .L_loop2 +.L_loop2_done: +#elif defined (__STARTUP_CLEAR_BSS) +/* Single BSS section scheme. + * + * The BSS section is specified by following symbols + * __bss_start__: start of the BSS section. + * __bss_end__: end of the BSS section. + * + * Both addresses must be aligned to 4 bytes boundary. + */ + ldr r1, =__bss_start__ + ldr r2, =__bss_end__ + + movs r0, 0 + + subs r2, r1 + ble .L_loop3_done + +.L_loop3: + subs r2, #4 + str r0, [r1, r2] + bgt .L_loop3 +.L_loop3_done: +#endif /* __STARTUP_CLEAR_BSS_MULTIPLE || __STARTUP_CLEAR_BSS */ + +#ifndef __NO_SYSTEM_INIT + bl SystemInit +#endif + + bl __init_array + +#ifndef __START +#define __START _start +#endif +// bl __START + bl main + .pool + .size Reset_Handler, . - Reset_Handler + + .align 1 + .thumb_func + .weak Default_Handler + .type Default_Handler, %function +Default_Handler: + b . + .size Default_Handler, . - Default_Handler + +/* Macro to define default handlers. Default handler + * will be weak symbol and just dead loops. They can be + * overwritten by other handlers */ + .macro def_irq_handler handler_name + .weak \handler_name + .set \handler_name, Default_Handler + .endm + + def_irq_handler NMI_Handler + def_irq_handler HardFault_Handler + def_irq_handler SVC_Handler + def_irq_handler PendSV_Handler + def_irq_handler SysTick_Handler + + def_irq_handler WWDG_IRQHandler + def_irq_handler PVD_IRQHandler + def_irq_handler WDT_IRQHandler + def_irq_handler RTC_IRQHandler + def_irq_handler FLASH_IRQHandler + def_irq_handler RCC_CRS_IRQHandler + def_irq_handler EXTI_1_0_IRQHandler + def_irq_handler EXTI_3_2_IRQHandler + def_irq_handler EXTI_15_4_IRQHandler + def_irq_handler DMA1_CHANNEL1_IRQHandler + def_irq_handler DMA1_CHANNEL3_2_IRQHandler + def_irq_handler DMA_CHANNEL_7_4_IRQHandler + def_irq_handler ADC_COMP_IRQHandler + def_irq_handler LPTIM1_IRQHandler + def_irq_handler USART4_USART5_IRQHandler + def_irq_handler TIM2_IRQHandler + def_irq_handler TIM3_IRQHandler + def_irq_handler TIM6_IRQHandler + def_irq_handler TIM7_IRQHandler + def_irq_handler TIM21_IRQHandler + def_irq_handler I2C3_IRQHandler + def_irq_handler TIM22_IRQHandler + + .end diff --git a/firmware/Bsp/Mcu/stm32l010c6.ld b/firmware/Bsp/Mcu/stm32l010c6.ld new file mode 100644 index 0000000..d344c29 --- /dev/null +++ b/firmware/Bsp/Mcu/stm32l010c6.ld @@ -0,0 +1,223 @@ +/** +Copyright (C) 2009-2015 ARM Limited. All rights reserved. +Copyright 2019, Max Regan + +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 ARM 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 COPYRIGHT HOLDERS AND 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. +*/ + +/* Linker script to configure memory regions. */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 8K +} + +/* Library configurations */ +/* GROUP(libgcc.a libc.a libm.a libnosys.a) */ + +/* 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 + * __copy_table_start__ + * __copy_table_end__ + * __zero_table_start__ + * __zero_table_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 + * __Vectors_End + * __Vectors_Size + */ +ENTRY(Reset_Handler) + +SECTIONS +{ + .text : + { + KEEP(*(.vectors)) + __Vectors_End = .; + __Vectors_Size = __Vectors_End - __Vectors; + __end__ = .; + + *(.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 = .; + + /* To copy multiple ROM to RAM sections, + * uncomment .copy.table section and, + * define __STARTUP_COPY_MULTIPLE in startup_ARMCMx.S */ + /* + .copy.table : + { + . = ALIGN(4); + __copy_table_start__ = .; + LONG (__etext) + LONG (__data_start__) + LONG (__data_end__ - __data_start__) + LONG (__etext2) + LONG (__data2_start__) + LONG (__data2_end__ - __data2_start__) + __copy_table_end__ = .; + } > FLASH + */ + + /* To clear multiple BSS sections, + * uncomment .zero.table section and, + * define __STARTUP_CLEAR_BSS_MULTIPLE in startup_ARMCMx.S */ + /* + .zero.table : + { + . = ALIGN(4); + __zero_table_start__ = .; + LONG (__bss_start__) + LONG (__bss_end__ - __bss_start__) + LONG (__bss2_start__) + LONG (__bss2_end__ - __bss2_start__) + __zero_table_end__ = .; + } > FLASH + */ + + __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 = .); + + KEEP(*(.jcr*)) + . = ALIGN(4); + /* All data end */ + __data_end__ = .; + + } > RAM + + .bss : + { + . = ALIGN(4); + __bss_start__ = .; + *(.bss*) + *(COMMON) + . = ALIGN(4); + __bss_end__ = .; + } > RAM + + .heap (COPY): + { + __HeapBase = .; + __end__ = .; + end = __end__; + KEEP(*(.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): + { + KEEP(*(.stack*)) /* changed MG 30.05.14 */ + } > 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") +} diff --git a/firmware/Bsp/macros.h b/firmware/Bsp/macros.h index e2ca70e..dfd62de 100644 --- a/firmware/Bsp/macros.h +++ b/firmware/Bsp/macros.h @@ -85,9 +85,9 @@ #define SET_STRIDE_TO(var, stride_width, index, val) \ do { \ - uint32_t mask = (1 << stride_width) - 1; \ - CLR(var, mask << (index * stride_width)); \ - SET(var, val << (index * stride_width)); \ + uint32_t mask = (1 << (stride_width)) - 1; \ + CLR(var, mask << ((index) * (stride_width))); \ + SET(var, (val) << ((index) * (stride_width))); \ } while (0) #endif diff --git a/firmware/Makefile b/firmware/Makefile index a9b99ea..d04eb12 100644 --- a/firmware/Makefile +++ b/firmware/Makefile @@ -41,8 +41,8 @@ BOARD ?= watch ifeq ($(BOARD), watch) -DEVICE_TYPE ?= stm32l031k6 -DEVICE_FAMILY = stm32l031xx +DEVICE_TYPE ?= stm32l010c6 +DEVICE_FAMILY = stm32l010xx DEVICE_LINE = stm32l0xx STACK_SIZE ?= 512 diff --git a/firmware/Test/clock.cpp b/firmware/Test/clock.cpp index 00c9df3..b8fa2da 100644 --- a/firmware/Test/clock.cpp +++ b/firmware/Test/clock.cpp @@ -36,12 +36,13 @@ using BSP::ReturnCode; using BSP::SystemTimer; static BSP::Schedule::LowPowerTaskScheduler<1> g_sched; +static BSP::GpioDriver g_gpioa(GPIOA); #if defined(BOARD_WATCH) static BSP::UsartDriver g_test_uart(USART2, g_sched); +static BSP::GpioPin g_tx_pin(g_gpioa, 9); #elif defined(BOARD_DEVBOARD) static BSP::UsartDriver g_test_uart(USART1, g_sched); #endif -static BSP::GpioDriver g_gpioa(GPIOA); static BSP::time_t get_time() { BSP::time_t time; @@ -54,10 +55,14 @@ static BSP::time_t get_time() { return time; } - [[noreturn]] void main() { g_gpioa.enable(); + +#if defined(BOARD_WATCH) + g_tx_pin.configure_alternate_function(4); +#endif + g_test_uart.init(); g_test_uart.tx_blocking(test_start_text); @@ -77,7 +82,6 @@ static BSP::time_t get_time() { g_test_uart.tx_blocking(buffer); now = get_time(); } - g_test_uart.tx_blocking("STOP\r\n"); g_test_uart.tx_blocking(test_pass_text); diff --git a/firmware/Test/fail.cpp b/firmware/Test/fail.cpp index d1b6e42..ec80d93 100644 --- a/firmware/Test/fail.cpp +++ b/firmware/Test/fail.cpp @@ -33,16 +33,22 @@ using BSP::Time; static BSP::Schedule::LowPowerTaskScheduler<1> g_sched; +static BSP::GpioDriver g_gpioa(GPIOA); #if defined(BOARD_WATCH) static BSP::UsartDriver g_test_uart(USART2, g_sched); +static BSP::GpioPin g_tx_pin(g_gpioa, 9); #elif defined(BOARD_DEVBOARD) static BSP::UsartDriver g_test_uart(USART1, g_sched); #endif -static BSP::GpioDriver g_gpioa(GPIOA); [[noreturn]] void main() { g_gpioa.enable(); + +#if defined(BOARD_WATCH) + g_tx_pin.configure_alternate_function(4); +#endif + g_test_uart.init(); g_test_uart.tx_blocking(test_start_text); diff --git a/firmware/Test/lptim.cpp b/firmware/Test/lptim.cpp index af88f5b..d16832e 100644 --- a/firmware/Test/lptim.cpp +++ b/firmware/Test/lptim.cpp @@ -37,16 +37,19 @@ using BSP::ReturnCode; using BSP::SystemTimer; static BSP::Schedule::LowPowerTaskScheduler<1> g_sched; +static BSP::GpioDriver g_gpioa(GPIOA); +static BSP::GpioDriver g_gpiob(GPIOB); + #if defined(BOARD_WATCH) static BSP::UsartDriver g_test_uart(USART2, g_sched); +static BSP::GpioPin g_tx_pin(g_gpioa, 9); static BSP::LptimPwm g_test_lptim(LPTIM1); +static BSP::GpioPin g_lptim_pin(g_gpioa, 7); #elif defined(BOARD_DEVBOARD) static BSP::UsartDriver g_test_uart(USART1, g_sched); static BSP::LptimPwm g_test_lptim(LPTIM2); -#endif -static BSP::GpioDriver g_gpioa(GPIOA); -static BSP::GpioDriver g_gpiob(GPIOB); static BSP::GpioPin g_lptim_pin(g_gpiob, 2); +#endif static BSP::time_t get_time() { BSP::time_t time; @@ -63,6 +66,15 @@ static BSP::time_t get_time() { g_gpioa.enable(); g_gpiob.enable(); + +#if defined(BOARD_WATCH) + g_tx_pin.configure_alternate_function(4); + g_lptim_pin.configure_alternate_function(1); +#elif defined(BOARD_DEVBOARD) + g_lptim_pin.configure_alternate_function(1); +#endif + + // TODO: Fix LPTIM pin init for the L030 model g_lptim_pin.configure_alternate_function(1); g_test_uart.init(); diff --git a/firmware/Test/pass.cpp b/firmware/Test/pass.cpp index 6debd7d..6b715b4 100644 --- a/firmware/Test/pass.cpp +++ b/firmware/Test/pass.cpp @@ -33,16 +33,22 @@ using BSP::Time; static BSP::Schedule::LowPowerTaskScheduler<1> g_sched; +static BSP::GpioDriver g_gpioa(GPIOA); #if defined(BOARD_WATCH) static BSP::UsartDriver g_test_uart(USART2, g_sched); +static BSP::GpioPin g_tx_pin(g_gpioa, 9); #elif defined(BOARD_DEVBOARD) static BSP::UsartDriver g_test_uart(USART1, g_sched); #endif -static BSP::GpioDriver g_gpioa(GPIOA); [[noreturn]] void main() { g_gpioa.enable(); + +#if defined(BOARD_WATCH) + g_tx_pin.configure_alternate_function(4); +#endif + g_test_uart.init(); g_test_uart.tx_blocking(test_start_text); diff --git a/firmware/Test/periodic_alarms.cpp b/firmware/Test/periodic_alarms.cpp index bb8d551..8440870 100644 --- a/firmware/Test/periodic_alarms.cpp +++ b/firmware/Test/periodic_alarms.cpp @@ -39,13 +39,13 @@ using BSP::SystemTimer; using BSP::time_t; static BSP::Schedule::LowPowerTaskScheduler<1> g_sched; +static BSP::GpioDriver g_gpioa(GPIOA); #if defined(BOARD_WATCH) static BSP::UsartDriver g_test_uart(USART2, g_sched); +static BSP::GpioPin g_tx_pin(g_gpioa, 9); #elif defined(BOARD_DEVBOARD) static BSP::UsartDriver g_test_uart(USART1, g_sched); #endif -static BSP::GpioDriver g_gpioa(GPIOA); -static BSP::GpioPin g_test_pin(g_gpioa, 6); static time_t get_time() { time_t time; @@ -66,9 +66,12 @@ static time_t get_time() { BSP::LowPower::init(); g_gpioa.enable(); - g_test_pin.configure_alternate_function(1); - g_test_uart.init(); +#if defined(BOARD_WATCH) + g_tx_pin.configure_alternate_function(4); +#endif + + g_test_uart.init(); g_test_uart.tx_blocking(test_start_text); const time_t end = get_time() + Time::millis(5100); diff --git a/firmware/Test/set_time.cpp b/firmware/Test/set_time.cpp index 65fc0f3..d00535a 100644 --- a/firmware/Test/set_time.cpp +++ b/firmware/Test/set_time.cpp @@ -39,13 +39,13 @@ using BSP::WallClockTime; using BSP::RtcDriver; static BSP::Schedule::LowPowerTaskScheduler<1> g_sched; +static BSP::GpioDriver g_gpioa(GPIOA); #if defined(BOARD_WATCH) static BSP::UsartDriver g_test_uart(USART2, g_sched); +static BSP::GpioPin g_tx_pin(g_gpioa, 9); #elif defined(BOARD_DEVBOARD) static BSP::UsartDriver g_test_uart(USART1, g_sched); #endif -static BSP::GpioDriver g_gpioa(GPIOA); -static BSP::GpioPin g_test_pin(g_gpioa, 6); static char buffer[128] = {0}; void run_case(unsigned int hours, unsigned int minutes, unsigned int seconds) { @@ -90,7 +90,11 @@ void run_case(unsigned int hours, unsigned int minutes, unsigned int seconds) { BSP::LowPower::init(); g_gpioa.enable(); - g_test_pin.configure_alternate_function(1); + +#if defined(BOARD_WATCH) + g_tx_pin.configure_alternate_function(4); +#endif + g_test_uart.init(); g_test_uart.tx_blocking(test_start_text); diff --git a/firmware/Test/stop.cpp b/firmware/Test/stop.cpp index dfefaa6..c151bc8 100644 --- a/firmware/Test/stop.cpp +++ b/firmware/Test/stop.cpp @@ -39,13 +39,13 @@ using BSP::SystemTimer; using BSP::time_t; static BSP::Schedule::LowPowerTaskScheduler<1> g_sched; +static BSP::GpioDriver g_gpioa(GPIOA); #if defined(BOARD_WATCH) static BSP::UsartDriver g_test_uart(USART2, g_sched); +static BSP::GpioPin g_tx_pin(g_gpioa, 9); #elif defined(BOARD_DEVBOARD) static BSP::UsartDriver g_test_uart(USART1, g_sched); #endif -static BSP::GpioDriver g_gpioa(GPIOA); -static BSP::GpioPin g_test_pin(g_gpioa, 6); static time_t get_time() { time_t time; @@ -99,7 +99,9 @@ static void stop_for(time_t delay) { BSP::LowPower::init(); g_gpioa.enable(); - g_test_pin.configure_alternate_function(1); +#if defined(BOARD_WATCH) + g_tx_pin.configure_alternate_function(4); +#endif g_test_uart.init(); g_test_uart.tx_blocking(test_start_text); diff --git a/firmware/Test/timeout.cpp b/firmware/Test/timeout.cpp index 38ed712..e527c5e 100644 --- a/firmware/Test/timeout.cpp +++ b/firmware/Test/timeout.cpp @@ -33,16 +33,22 @@ using BSP::Time; static BSP::Schedule::LowPowerTaskScheduler<1> g_sched; +static BSP::GpioDriver g_gpioa(GPIOA); #if defined(BOARD_WATCH) static BSP::UsartDriver g_test_uart(USART2, g_sched); +static BSP::GpioPin g_tx_pin(g_gpioa, 9); #elif defined(BOARD_DEVBOARD) static BSP::UsartDriver g_test_uart(USART1, g_sched); #endif -static BSP::GpioDriver g_gpioa(GPIOA); [[noreturn]] void main() { g_gpioa.enable(); + +#if defined(BOARD_WATCH) + g_tx_pin.configure_alternate_function(4); +#endif + g_test_uart.init(); g_test_uart.tx_blocking(test_start_text); diff --git a/firmware/Test/wakeup_irq.cpp b/firmware/Test/wakeup_irq.cpp index 56d5491..b39687c 100644 --- a/firmware/Test/wakeup_irq.cpp +++ b/firmware/Test/wakeup_irq.cpp @@ -38,13 +38,13 @@ using BSP::SystemTimer; using BSP::time_t; static BSP::Schedule::LowPowerTaskScheduler<1> g_sched; +static BSP::GpioDriver g_gpioa(GPIOA); #if defined(BOARD_WATCH) static BSP::UsartDriver g_test_uart(USART2, g_sched); +static BSP::GpioPin g_tx_pin(g_gpioa, 9); #elif defined(BOARD_DEVBOARD) static BSP::UsartDriver g_test_uart(USART1, g_sched); #endif -static BSP::GpioDriver g_gpioa(GPIOA); -static BSP::GpioPin g_test_pin(g_gpioa, 6); static time_t get_time() { time_t time; @@ -87,10 +87,10 @@ static void stop_for(time_t delay) { static void fail_if_wakeup(time_t delay) { uint32_t pre_wakeups = BSP::RtcDriver::get_wakeup_count(); time_t before = get_time(); - while (before + delay > get_time() || BSP::RtcDriver::get_wakeup_count() != pre_wakeups) {} + while (before + delay > get_time() && BSP::RtcDriver::get_wakeup_count() == pre_wakeups) {} if (BSP::RtcDriver::get_wakeup_count() != pre_wakeups) { - g_test_uart.tx_blocking("Got unexpected wakeup IRQ"); + g_test_uart.tx_blocking("Got unexpected wakeup IRQ\r\n"); g_test_uart.tx_blocking(test_fail_text); TEST_SPIN(); } @@ -102,9 +102,12 @@ static void fail_if_wakeup(time_t delay) { SystemTimer::set_timer(BSP::RtcDriver::get_system_timer()); g_gpioa.enable(); - g_test_pin.configure_alternate_function(1); - g_test_uart.init(); +#if defined(BOARD_WATCH) + g_tx_pin.configure_alternate_function(4); +#endif + + g_test_uart.init(); g_test_uart.tx_blocking(test_start_text); for (uint32_t i = 0; i <= 100; i++) { diff --git a/test/src/tr_test/test.py b/test/src/tr_test/test.py index 5f0204c..774f1e9 100755 --- a/test/src/tr_test/test.py +++ b/test/src/tr_test/test.py @@ -51,7 +51,7 @@ def logger(): def context_factory(): def create_context( fw_rel_path: str, - mcu: str = "STM32L412RB", + mcu: str = "STM32L010C6", addr: int = 0x8000000, leave_halted: bool = False, ): @@ -138,6 +138,7 @@ def test_set_time(context_factory, logger): print("Text:", text.decode()) assert text.endswith(TEST_PASS_TEXT) + def test_periodic_alarms(context_factory, logger): serial_dev, jlink = context_factory("Test/periodic_alarms.bin") serial_dev.timeout = 6 @@ -175,7 +176,7 @@ def test_clock(context_factory, logger): # TODO: Using a single pin, instead of UART, would make this more # accurate. Add support via sigrok. - assert (delta - EXPECTED_RUNTIME) < TOLERANCE + assert abs(delta - EXPECTED_RUNTIME) < TOLERANCE def test_wakeup_irq(context_factory, logger): @@ -207,7 +208,7 @@ def test_wakeup_irq(context_factory, logger): def test_stop(context_factory, logger): serial_dev, jlink = context_factory("Test/stop.bin") - serial_dev.timeout = 65 + serial_dev.timeout = 70 pattern = re.compile("Requested=(\\d*) Actual=(\\d*)") while True: @@ -229,6 +230,7 @@ def test_stop(context_factory, logger): # Delays > 32sec have reduced resolution (1 sec) assert abs(delta) < 1000 + "sigrok-cli -C D3 -d fx2lafw -c samplerate=1M --time 1s -P timing:data=D3" @@ -275,9 +277,10 @@ def measure_frequency( return periods[::2], periods[1:][::2] + def test_lptim(context_factory, logger): serial_dev, jlink = context_factory("Test/lptim.bin") - state0_periods, state1_periods = measure_frequency(1, "D1") + state0_periods, state1_periods = measure_frequency(1, "D0") num_periods = min(len(state0_periods), len(state1_periods)) periods = [state0_periods[i] + state1_periods[i] for i in range(num_periods)] freqs = list(map(lambda x: 1 / x, periods))