diff --git a/cross_arm.txt b/cross_arm.txt
index 67c05003..3b60e957 100644
--- a/cross_arm.txt
+++ b/cross_arm.txt
@@ -1,20 +1,41 @@
[binaries]
-c = 'arm-none-eabi-gcc'
-cpp = 'arm-none-eabi-g++'
-ld = 'arm-none-eabi-ld'
-ar = 'arm-none-eabi-ar'
-as = 'arm-none-eabi-as'
-size = 'arm-none-eabi-size'
-objdump = 'arm-none-eabi-objdump'
-objcopy = 'arm-none-eabi-objcopy'
-strip = 'arm-none-eabi-strip'
-gdb = 'arm-none-eabi-gdb'
+c = 'arm-miosix-eabi-gcc'
+cpp = 'arm-miosix-eabi-g++'
+ld = 'arm-miosix-eabi-ld'
+ar = 'arm-miosix-eabi-ar'
+as = 'arm-miosix-eabi-as'
+size = 'arm-miosix-eabi-size'
+objdump = 'arm-miosix-eabi-objdump'
+objcopy = 'arm-miosix-eabi-objcopy'
+strip = 'arm-miosix-eabi-strip'
+gdb = 'arm-miosix-eabi-gdb'
terminal= 'x-terminal-emulator'
openocd = '/usr/local/bin/openocd'
[properties]
c_args = [
- '-fcommon',
+ '-D_DEFAULT_SOURCE=1',
+ '-ffunction-sections',
+ '-Wall',
+ '-Werror=return-type',
+ '-g',
+ '-mcpu=cortex-m4', # Cortex-M4 CPU
+ '-mthumb', # ARM Thumb2 ISA
+ '-mfloat-abi=hard', # Hard floating point support
+ '-mfpu=fpv4-sp-d16',
+ '-Os'
+ ]
+
+cpp_args = [
+ '-D_DEFAULT_SOURCE=1',
+ '-ffunction-sections',
+ '-Wall',
+ '-Werror=return-type',
+ '-g',
+ '-fno-exceptions',
+ '-fno-rtti',
+ '-D__NO_EXCEPTIONS',
+ '-std=c++14',
'-mcpu=cortex-m4', # Cortex-M4 CPU
'-mthumb', # ARM Thumb2 ISA
'-mfloat-abi=hard', # Hard floating point support
@@ -27,17 +48,23 @@ c_link_args = [
'-mthumb',
'-mfloat-abi=hard',
'-mfpu=fpv4-sp-d16',
+ '-fno-exceptions',
+ '-fno-rtti',
+ '-Wl,-L../lib/miosix-kernel',
'-Wl,--gc-sections',
'-Wl,-Map,main.map',
'-Wl,--warn-common',
'-nostdlib',
- '-Wl,--start-group',
+ '-lmiosix',
+ '-lstdc++',
'-lc',
- '-lgcc',
'-lm',
- '-Wl,--end-group'
+ '-lgcc',
+ '-latomic'
]
+cpp_link_args = c_link_args
+
[host_machine]
system = 'none'
cpu_family = 'arm'
diff --git a/platform/mcu/STM32F4xx/boot/bsp.cpp b/platform/mcu/STM32F4xx/boot/bsp.cpp
new file mode 100644
index 00000000..25c59f2d
--- /dev/null
+++ b/platform/mcu/STM32F4xx/boot/bsp.cpp
@@ -0,0 +1,74 @@
+/***************************************************************************
+ * Copyright (C) 2021 by Federico Amedeo Izzo IU2NUO, *
+ * Niccolò Izzo IU2KIN *
+ * Frederik Saraci IU2NRO *
+ * Silvano Seva IU2KWO, *
+ * Federico Terraneo *
+ * *
+ * This program 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 3 of the License, or *
+ * (at your option) any later version. *
+ * *
+ * This program 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, see *
+ ***************************************************************************/
+
+/***********************************************************************
+* bsp.cpp Part of the Miosix Embedded OS.
+* Board support package, this file initializes hardware.
+************************************************************************/
+
+#include
+#include
+#include
+#include
+
+namespace miosix
+{
+
+//
+// Initialization
+//
+
+void IRQbspInit()
+{
+ RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN | RCC_AHB1ENR_GPIOBEN
+ | RCC_AHB1ENR_GPIOCEN | RCC_AHB1ENR_GPIODEN
+ | RCC_AHB1ENR_GPIOEEN | RCC_AHB1ENR_GPIOHEN;
+ RCC_SYNC();
+
+ GPIOA->OSPEEDR=0xaaaaaaaa; //Default to 50MHz speed for all GPIOS
+ GPIOB->OSPEEDR=0xaaaaaaaa;
+ GPIOC->OSPEEDR=0xaaaaaaaa;
+ GPIOD->OSPEEDR=0xaaaaaaaa;
+ GPIOE->OSPEEDR=0xaaaaaaaa;
+ GPIOH->OSPEEDR=0xaaaaaaaa;
+}
+
+void bspInit2()
+{
+
+}
+
+//
+// Shutdown and reboot
+//
+
+void shutdown()
+{
+ reboot();
+}
+
+void reboot()
+{
+ disableInterrupts();
+ miosix_private::IRQsystemReboot();
+}
+
+} //namespace miosix
diff --git a/platform/mcu/STM32F4xx/boot/libc_integration.c b/platform/mcu/STM32F4xx/boot/libc_integration.c
deleted file mode 100644
index 3b525ef9..00000000
--- a/platform/mcu/STM32F4xx/boot/libc_integration.c
+++ /dev/null
@@ -1,432 +0,0 @@
-/***************************************************************************
- * Copyright (C) 2020 by Silvano Seva IU2KWO *
- * *
- * This program 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 3 of the License, or *
- * (at your option) any later version. *
- * *
- * This program 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, see *
- ***************************************************************************/
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include "../drivers/usb_vcom.h"
-
-
-void pthread_mutex_unlock(){}
-void pthread_mutex_lock() {}
-void pthread_mutex_destroy() {}
-int pthread_setcancelstate(int state, int *oldstate)
-{
- (void) state;
- (void) oldstate;
- return 0;
-}
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-//
-// C atexit support, for thread safety and code size optimizations
-// ===============================================================
-
-/**
- * Function called by atexit(), on_exit() and __cxa_atexit() to register
- * C functions/C++ destructors to be run at program termintion.
- * It is called in this way:
- * atexit(): __register_exitproc(__et_atexit, fn, 0, 0)
- * on_exit(): __register_exitproc(__et_onexit, fn, arg, 0)
- * __cxa_atexit(): __register_exitproc(__et_cxa, fn, arg, d)
- * \param type to understand if the function was called by atexit, on_exit, ...
- * \param fn pointer to function to be called
- * \param arg 0 in case of atexit, function argument in case of on_exit,
- * "this" parameter for C++ destructors registered with __cxa_atexit
- * \param d __dso_handle used to selectively call C++ destructors of a shared
- * library loaded dynamically, unused since Miosix does not support shared libs
- * \return 0 on success
- */
-int __register_exitproc(int type, void (*fn)(void), void *arg, void *d)
-{
- (void) type;
- (void) fn;
- (void) arg;
- (void) d;
-
- return 0;
-}
-
-/**
- * Called by exit() to call functions registered through atexit()
- * \param code the exit code, for example with exit(1), code==1
- * \param d __dso_handle, see __register_exitproc
- */
-void __call_exitprocs(int code, void *d)
-{
- (void) code;
- (void) d;
-}
-
-/**
- * \internal
- * Required by C++ standard library.
- * See http://lists.debian.org/debian-gcc/2003/07/msg00057.html
- */
-void *__dso_handle=(void*) &__dso_handle;
-
-
-
-
-//
-// C/C++ system calls, to support malloc, printf, fopen, etc.
-// ==========================================================
-
-/**
- * \internal
- * _exit, lock system in infinite loop until reboot
- */
-void _exit(int status)
-{
- (void) status;
- for(;;) ;
-}
-
-/**
- * \internal
- * _sbrk_r, allocates memory dynamically
- */
-void *_sbrk_r(struct _reent *ptr, ptrdiff_t incr)
-{
- (void) ptr;
-
- //This is the absolute start of the heap
- extern char _end asm("_end"); //defined in the linker script
- //This is the absolute end of the heap
- extern char _heap_end asm("_heap_end"); //defined in the linker script
- //This holds the current end of the heap (static)
- static char *curHeapEnd=NULL;
- //This holds the previous end of the heap
- char *prevHeapEnd;
-
- //Check if it's first time called
- if(curHeapEnd==NULL) curHeapEnd=&_end;
-
- prevHeapEnd=curHeapEnd;
-
- if((curHeapEnd+incr)>&_heap_end)
- {
- return (void*)(-1);
- }
- curHeapEnd+=incr;
-
- return (void*)(prevHeapEnd);
-}
-
-/**
- * \internal
- * __malloc_lock, called by malloc to ensure no context switch happens during
- * memory allocation. Since this environment is not a multithreaded one, this
- * function is left empty. Allocating memory inside interrupts is anyway
- * forbidden.
- */
-void __malloc_lock() {}
-
-/**
- * \internal
- * __malloc_unlock, called by malloc after performing operations on the heap
- */
-void __malloc_unlock() {}
-
-/**
- * \internal
- * __getreent(), return the reentrancy structure of the current thread.
- * Used by newlib to make the C standard library thread safe.
- * Not a multithreaded environment, we return global reentrancy data.
- */
-struct _reent *__getreent()
-{
- return _GLOBAL_REENT;
-}
-
-
-
-
-/**
- * \internal
- * _open_r, open a file. Actually unimpemented
- */
-int _open_r(struct _reent *ptr, const char *name, int flags, int mode)
-{
- (void) ptr;
- (void) name;
- (void) flags;
- (void) mode;
-
- return -1;
-}
-
-/**
- * \internal
- * _close_r, close a file. Actually unimpemented
- */
-int _close_r(struct _reent *ptr, int fd)
-{
- (void) ptr;
- (void) fd;
-
- return -1;
-}
-
-/**
- * \internal
- * _write_r, write to a file.
- */
-int _write_r(struct _reent *ptr, int fd, const void *buf, size_t cnt)
-{
- if(fd == STDOUT_FILENO || fd == STDERR_FILENO)
- {
- vcom_writeBlock(buf, cnt);
- return cnt;
- }
-
- /* If fd is not stdout or stderr */
- ptr->_errno = EBADF;
- return -1;
-}
-
-/**
- * \internal
- * _read_r, read from a file.
- */
-int _read_r(struct _reent *ptr, int fd, void *buf, size_t cnt)
-{
- if(fd == STDIN_FILENO)
- {
- for(;;)
- {
- ssize_t r = vcom_readBlock(buf, cnt);
- if((r < 0) || (r == (ssize_t)(cnt))) return r;
- }
- }
- else
-
- /* If fd is not stdin */
- ptr->_errno = EBADF;
- return -1;
-}
-
-int _read(int fd, void *buf, size_t cnt)
-{
- return _read_r(__getreent(), fd, buf, cnt);
-}
-
-/**
- * \internal
- * _lseek_r, move file pointer. Actually unimpemented
- */
-off_t _lseek_r(struct _reent *ptr, int fd, off_t pos, int whence)
-{
- (void) ptr;
- (void) fd;
- (void) pos;
- (void) whence;
-
- return -1;
-}
-
-off_t _lseek(int fd, off_t pos, int whence)
-{
- (void) fd;
- (void) pos;
- (void) whence;
-
- return -1;
-}
-
-/**
- * \internal
- * _fstat_r, return file info. Actually unimpemented
- */
-int _fstat_r(struct _reent *ptr, int fd, struct stat *pstat)
-{
- (void) ptr;
- (void) fd;
- (void) pstat;
-
- return -1;
-}
-
-int _fstat(int fd, struct stat *pstat)
-{
- (void) fd;
- (void) pstat;
-
- return -1;
-}
-
-/**
- * \internal
- * _stat_r, collect data about a file. Actually unimpemented
- */
-int _stat_r(struct _reent *ptr, const char *file, struct stat *pstat)
-{
- (void) ptr;
- (void) file;
- (void) pstat;
-
- return -1;
-}
-
-/**
- * \internal
- * isatty, returns 1 if fd is associated with a terminal.
- * Always return 1 because read and write are implemented only in
- * terms of serial communication
- */
-int _isatty_r(struct _reent *ptr, int fd)
-{
- (void) ptr;
- (void) fd;
-
- return 1;
-}
-
-int isatty(int fd)
-{
- (void) fd;
-
- return 1;
-}
-
-int _isatty(int fd)
-{
- (void) fd;
-
- return 1;
-}
-
-/**
- * \internal
- * _mkdir, create a directory. Actually unimpemented
- */
-int mkdir(const char *path, mode_t mode)
-{
- (void) path;
- (void) mode;
-
- return -1;
-}
-
-/**
- * \internal
- * _link_r: create hardlinks. Actually unimpemented
- */
-int _link_r(struct _reent *ptr, const char *f_old, const char *f_new)
-{
- (void) ptr;
- (void) f_old;
- (void) f_new;
-
- return -1;
-}
-
-/**
- * \internal
- * _unlink_r, remove a file. Actually unimpemented
- */
-int _unlink_r(struct _reent *ptr, const char *file)
-{
- (void) ptr;
- (void) file;
-
- return -1;
-}
-
-/**
- * \internal
- * _times_r, return elapsed time. Actually unimpemented
- */
-clock_t _times_r(struct _reent *ptr, struct tms *tim)
-{
- (void) ptr;
- (void) tim;
-
- return -1;
-}
-
-
-
-
-
-/**
- * \internal
- * it looks like abort() calls _kill instead of exit, this implementation
- * calls _exit() so that calling abort() really terminates the program
- */
-int _kill_r(struct _reent* ptr, int pid, int sig)
-{
- (void) ptr;
- (void) sig;
-
- if(pid == 0)
- _exit(1);
- else
- return -1;
-}
-
-int _kill(int pid, int sig)
-{
- return _kill_r(0, pid, sig);
-}
-
-/**
- * \internal
- * _getpid_r. Not a multiprocess system, return always 0
- */
-int _getpid_r(struct _reent* ptr)
-{
- (void) ptr;
- return 0;
-}
-
-int _getpid()
-{
- return 0;
-}
-
-/**
- * \internal
- * _wait_r, unimpemented because processes are not supported.
- */
-int _wait_r(struct _reent *ptr, int *status)
-{
- (void) ptr;
- (void) status;
-
- return -1;
-}
-
-int _fork_r(struct _reent *ptr)
-{
- (void) ptr;
-
- return -1;
-}
-
-#ifdef __cplusplus
-}
-#endif
diff --git a/platform/mcu/STM32F4xx/boot/libc_integration.cpp b/platform/mcu/STM32F4xx/boot/libc_integration.cpp
new file mode 100644
index 00000000..dc9ab69f
--- /dev/null
+++ b/platform/mcu/STM32F4xx/boot/libc_integration.cpp
@@ -0,0 +1,68 @@
+/***************************************************************************
+ * Copyright (C) 2020, 2021 by Silvano Seva IU2KWO *
+ * *
+ * This program 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 3 of the License, or *
+ * (at your option) any later version. *
+ * *
+ * This program 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, see *
+ ***************************************************************************/
+
+#include
+#include
+#include "filesystem/file_access.h"
+
+using namespace std;
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * \internal
+ * _write_r, write to a file
+ */
+int _write_r(struct _reent *ptr, int fd, const void *buf, size_t cnt)
+{
+// if(fd == STDOUT_FILENO || fd == STDERR_FILENO)
+// {
+// vcom_writeBlock(buf, cnt);
+// return cnt;
+// }
+
+ /* If fd is not stdout or stderr */
+ ptr->_errno = EBADF;
+ return -1;
+}
+
+/**
+ * \internal
+ * _read_r, read from a file.
+ */
+int _read_r(struct _reent *ptr, int fd, void *buf, size_t cnt)
+{
+// if(fd == STDIN_FILENO)
+// {
+// for(;;)
+// {
+// ssize_t r = vcom_readBlock(buf, cnt);
+// if((r < 0) || (r == (ssize_t)(cnt))) return r;
+// }
+// }
+// else
+
+ /* If fd is not stdin */
+ ptr->_errno = EBADF;
+ return -1;
+}
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/platform/mcu/STM32F4xx/boot/startup.c b/platform/mcu/STM32F4xx/boot/startup.c
deleted file mode 100644
index f21599bc..00000000
--- a/platform/mcu/STM32F4xx/boot/startup.c
+++ /dev/null
@@ -1,395 +0,0 @@
-/***************************************************************************
- * Copyright (C) 2020 by Federico Izzo IU2NUO, Niccolò Izzo IU2KIN and *
- * Silvano Seva IU2KWO *
- * *
- * This program 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 3 of the License, or *
- * (at your option) any later version. *
- * *
- * This program 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, see *
- ***************************************************************************/
-
-
-#include
-#include
-#include "stm32f4xx.h"
-#include "../drivers/usb_vcom.h"
-
-///< Entry point for system bootstrap after initial configurations.
-void systemBootstrap();
-
-void Reset_Handler() __attribute__((__interrupt__, noreturn));
-void Reset_Handler()
-{
- // Disable interrupts at startup, as the RTOS requires this.
- __disable_irq();
-
- // Call CMSIS init function, it's safe to do it here.
- // This function initialises VTOR, clock-tree and flash memory wait states.
- // System clock frequency is 168MHz.
- SystemInit();
-
- //These are defined in the linker script
- extern unsigned char _etext asm("_etext");
- extern unsigned char _data asm("_data");
- extern unsigned char _edata asm("_edata");
- extern unsigned char _bss_start asm("_bss_start");
- extern unsigned char _bss_end asm("_bss_end");
-
- // Initialize .data section, clear .bss section
- unsigned char *etext=&_etext;
- unsigned char *data=&_data;
- unsigned char *edata=&_edata;
- unsigned char *bss_start=&_bss_start;
- unsigned char *bss_end=&_bss_end;
-
- memcpy(data, etext, edata-data);
- memset(bss_start, 0, bss_end-bss_start);
-
- // General system configurations: enabling all GPIO ports.
- RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN
- | RCC_AHB1ENR_GPIOBEN
- | RCC_AHB1ENR_GPIOCEN
- | RCC_AHB1ENR_GPIODEN
- | RCC_AHB1ENR_GPIOEEN;
- __DSB();
-
- // Configure all GPIO pins to fast speed mode (50MHz)
- GPIOA->OSPEEDR = 0xAAAAAAAA;
- GPIOB->OSPEEDR = 0xAAAAAAAA;
- GPIOC->OSPEEDR = 0xAAAAAAAA;
- GPIOD->OSPEEDR = 0xAAAAAAAA;
- GPIOE->OSPEEDR = 0xAAAAAAAA;
-
- // Enable SWD interface on PA13 and PA14 (Tytera's bootloader disables this
- // functionality).
- // NOTE: these pins are used also for other functions (MIC power and wide/
- // narrow FM reception), thus they cannot be always used for debugging!
- #ifdef ENABLE_SWD
- GPIOA->MODER &= ~0x3C000000; // Clear current setting
- GPIOA->MODER |= 0x28000000; // Put back to alternate function
- GPIOA->AFR[1] &= ~0x0FF00000; // SWD is AF0
- #endif
-
- // Enable virtual com port (for stdin, stdout and stderr redirection)
- vcom_init();
-
- // Set no buffer for stdin, required to make scanf, getchar, ... working
- // correctly
- setvbuf(stdin, NULL, _IONBF, 0);
-
- // Jump to application code
- systemBootstrap();
-
- // Execution flow should never reach this point but, in any case, loop
- // indefinitely it this happens
- for(;;) ;
-}
-
-void Default_Handler()
-{
- // default handler does nothing
-}
-
-void __attribute__((weak)) NMI_Handler();
-void __attribute__((weak)) HardFault_Handler();
-void __attribute__((weak)) MemManage_Handler();
-void __attribute__((weak)) BusFault_Handler();
-void __attribute__((weak)) UsageFault_Handler();
-void __attribute__((weak)) SVC_Handler();
-void __attribute__((weak)) DebugMon_Handler();
-
-void __attribute__((weak)) OS_CPU_PendSVHandler(); // uC/OS-III naming convention
-void __attribute__((weak)) OS_CPU_SysTickHandler();
-
-void __attribute__((weak)) WWDG_IRQHandler();
-void __attribute__((weak)) PVD_IRQHandler();
-void __attribute__((weak)) TAMP_STAMP_IRQHandler();
-void __attribute__((weak)) RTC_WKUP_IRQHandler();
-void __attribute__((weak)) FLASH_IRQHandler();
-void __attribute__((weak)) RCC_IRQHandler();
-void __attribute__((weak)) EXTI0_IRQHandler();
-void __attribute__((weak)) EXTI1_IRQHandler();
-void __attribute__((weak)) EXTI2_IRQHandler();
-void __attribute__((weak)) EXTI3_IRQHandler();
-void __attribute__((weak)) EXTI4_IRQHandler();
-void __attribute__((weak)) DMA1_Stream0_IRQHandler();
-void __attribute__((weak)) DMA1_Stream1_IRQHandler();
-void __attribute__((weak)) DMA1_Stream2_IRQHandler();
-void __attribute__((weak)) DMA1_Stream3_IRQHandler();
-void __attribute__((weak)) DMA1_Stream4_IRQHandler();
-void __attribute__((weak)) DMA1_Stream5_IRQHandler();
-void __attribute__((weak)) DMA1_Stream6_IRQHandler();
-void __attribute__((weak)) ADC_IRQHandler();
-void __attribute__((weak)) CAN1_TX_IRQHandler();
-void __attribute__((weak)) CAN1_RX0_IRQHandler();
-void __attribute__((weak)) CAN1_RX1_IRQHandler();
-void __attribute__((weak)) CAN1_SCE_IRQHandler();
-void __attribute__((weak)) EXTI9_5_IRQHandler();
-void __attribute__((weak)) TIM1_BRK_TIM9_IRQHandler();
-void __attribute__((weak)) TIM1_UP_TIM10_IRQHandler();
-void __attribute__((weak)) TIM1_TRG_COM_TIM11_IRQHandler();
-void __attribute__((weak)) TIM1_CC_IRQHandler();
-void __attribute__((weak)) TIM2_IRQHandler();
-void __attribute__((weak)) TIM3_IRQHandler();
-void __attribute__((weak)) TIM4_IRQHandler();
-void __attribute__((weak)) I2C1_EV_IRQHandler();
-void __attribute__((weak)) I2C1_ER_IRQHandler();
-void __attribute__((weak)) I2C2_EV_IRQHandler();
-void __attribute__((weak)) I2C2_ER_IRQHandler();
-void __attribute__((weak)) SPI1_IRQHandler();
-void __attribute__((weak)) SPI2_IRQHandler();
-void __attribute__((weak)) USART1_IRQHandler();
-void __attribute__((weak)) USART2_IRQHandler();
-void __attribute__((weak)) USART3_IRQHandler();
-void __attribute__((weak)) EXTI15_10_IRQHandler();
-void __attribute__((weak)) RTC_Alarm_IRQHandler();
-void __attribute__((weak)) OTG_FS_WKUP_IRQHandler();
-void __attribute__((weak)) TIM8_BRK_TIM12_IRQHandler();
-void __attribute__((weak)) TIM8_UP_TIM13_IRQHandler();
-void __attribute__((weak)) TIM8_TRG_COM_TIM14_IRQHandler();
-void __attribute__((weak)) TIM8_CC_IRQHandler();
-void __attribute__((weak)) DMA1_Stream7_IRQHandler();
-void __attribute__((weak)) FSMC_IRQHandler();
-void __attribute__((weak)) SDIO_IRQHandler();
-void __attribute__((weak)) TIM5_IRQHandler();
-void __attribute__((weak)) SPI3_IRQHandler();
-void __attribute__((weak)) UART4_IRQHandler();
-void __attribute__((weak)) UART5_IRQHandler();
-void __attribute__((weak)) TIM6_DAC_IRQHandler();
-void __attribute__((weak)) TIM7_IRQHandler();
-void __attribute__((weak)) DMA2_Stream0_IRQHandler();
-void __attribute__((weak)) DMA2_Stream1_IRQHandler();
-void __attribute__((weak)) DMA2_Stream2_IRQHandler();
-void __attribute__((weak)) DMA2_Stream3_IRQHandler();
-void __attribute__((weak)) DMA2_Stream4_IRQHandler();
-void __attribute__((weak)) ETH_IRQHandler();
-void __attribute__((weak)) ETH_WKUP_IRQHandler();
-void __attribute__((weak)) CAN2_TX_IRQHandler();
-void __attribute__((weak)) CAN2_RX0_IRQHandler();
-void __attribute__((weak)) CAN2_RX1_IRQHandler();
-void __attribute__((weak)) CAN2_SCE_IRQHandler();
-void __attribute__((weak)) OTG_FS_IRQHandler();
-void __attribute__((weak)) DMA2_Stream5_IRQHandler();
-void __attribute__((weak)) DMA2_Stream6_IRQHandler();
-void __attribute__((weak)) DMA2_Stream7_IRQHandler();
-void __attribute__((weak)) USART6_IRQHandler();
-void __attribute__((weak)) I2C3_EV_IRQHandler();
-void __attribute__((weak)) I2C3_ER_IRQHandler();
-void __attribute__((weak)) OTG_HS_EP1_OUT_IRQHandler();
-void __attribute__((weak)) OTG_HS_EP1_IN_IRQHandler();
-void __attribute__((weak)) OTG_HS_WKUP_IRQHandler();
-void __attribute__((weak)) OTG_HS_IRQHandler();
-void __attribute__((weak)) DCMI_IRQHandler();
-void __attribute__((weak)) CRYP_IRQHandler();
-void __attribute__((weak)) HASH_RNG_IRQHandler();
-void __attribute__((weak)) FPU_IRQHandler();
-
-//Stack top, defined in the linker script
-extern char _stack_top asm("_stack_top");
-
-//Interrupt vectors, must be placed @ address 0x00000000
-//The extern declaration is required otherwise g++ optimizes it out
-extern void (* const __Vectors[])();
-void (* const __Vectors[])() __attribute__ ((section(".isr_vector"))) =
-{
- (void (*)())(&_stack_top),
- Reset_Handler,
- NMI_Handler,
- HardFault_Handler,
- MemManage_Handler,
- BusFault_Handler,
- UsageFault_Handler,
- 0,
- 0,
- 0,
- 0,
- SVC_Handler,
- DebugMon_Handler,
- 0,
- OS_CPU_PendSVHandler,
- OS_CPU_SysTickHandler,
-
- WWDG_IRQHandler,
- PVD_IRQHandler,
- TAMP_STAMP_IRQHandler,
- RTC_WKUP_IRQHandler,
- FLASH_IRQHandler,
- RCC_IRQHandler,
- EXTI0_IRQHandler,
- EXTI1_IRQHandler,
- EXTI2_IRQHandler,
- EXTI3_IRQHandler,
- EXTI4_IRQHandler,
- DMA1_Stream0_IRQHandler,
- DMA1_Stream1_IRQHandler,
- DMA1_Stream2_IRQHandler,
- DMA1_Stream3_IRQHandler,
- DMA1_Stream4_IRQHandler,
- DMA1_Stream5_IRQHandler,
- DMA1_Stream6_IRQHandler,
- ADC_IRQHandler,
- CAN1_TX_IRQHandler,
- CAN1_RX0_IRQHandler,
- CAN1_RX1_IRQHandler,
- CAN1_SCE_IRQHandler,
- EXTI9_5_IRQHandler,
- TIM1_BRK_TIM9_IRQHandler,
- TIM1_UP_TIM10_IRQHandler,
- TIM1_TRG_COM_TIM11_IRQHandler,
- TIM1_CC_IRQHandler,
- TIM2_IRQHandler,
- TIM3_IRQHandler,
- TIM4_IRQHandler,
- I2C1_EV_IRQHandler,
- I2C1_ER_IRQHandler,
- I2C2_EV_IRQHandler,
- I2C2_ER_IRQHandler,
- SPI1_IRQHandler,
- SPI2_IRQHandler,
- USART1_IRQHandler,
- USART2_IRQHandler,
- USART3_IRQHandler,
- EXTI15_10_IRQHandler,
- RTC_Alarm_IRQHandler,
- OTG_FS_WKUP_IRQHandler,
- TIM8_BRK_TIM12_IRQHandler,
- TIM8_UP_TIM13_IRQHandler,
- TIM8_TRG_COM_TIM14_IRQHandler,
- TIM8_CC_IRQHandler,
- DMA1_Stream7_IRQHandler,
- FSMC_IRQHandler,
- SDIO_IRQHandler,
- TIM5_IRQHandler,
- SPI3_IRQHandler,
- UART4_IRQHandler,
- UART5_IRQHandler,
- TIM6_DAC_IRQHandler,
- TIM7_IRQHandler,
- DMA2_Stream0_IRQHandler,
- DMA2_Stream1_IRQHandler,
- DMA2_Stream2_IRQHandler,
- DMA2_Stream3_IRQHandler,
- DMA2_Stream4_IRQHandler,
- ETH_IRQHandler,
- ETH_WKUP_IRQHandler,
- CAN2_TX_IRQHandler,
- CAN2_RX0_IRQHandler,
- CAN2_RX1_IRQHandler,
- CAN2_SCE_IRQHandler,
- OTG_FS_IRQHandler,
- DMA2_Stream5_IRQHandler,
- DMA2_Stream6_IRQHandler,
- DMA2_Stream7_IRQHandler,
- USART6_IRQHandler,
- I2C3_EV_IRQHandler,
- I2C3_ER_IRQHandler,
- OTG_HS_EP1_OUT_IRQHandler,
- OTG_HS_EP1_IN_IRQHandler,
- OTG_HS_WKUP_IRQHandler,
- OTG_HS_IRQHandler,
- DCMI_IRQHandler,
- CRYP_IRQHandler,
- HASH_RNG_IRQHandler,
- FPU_IRQHandler
-};
-
-#pragma weak NMI_Handler= Default_Handler
-#pragma weak HardFault_Handler= Default_Handler
-#pragma weak MemManage_Handler= Default_Handler
-#pragma weak BusFault_Handler= Default_Handler
-#pragma weak UsageFault_Handler= Default_Handler
-#pragma weak SVC_Handler= Default_Handler
-#pragma weak DebugMon_Handler= Default_Handler
-#pragma weak PendSV_Handler= Default_Handler
-#pragma weak SysTick_Handler= Default_Handler
-#pragma weak WWDG_IRQHandler= Default_Handler
-
-#pragma weak PVD_IRQHandler= Default_Handler
-#pragma weak TAMP_STAMP_IRQHandler= Default_Handler
-#pragma weak RTC_WKUP_IRQHandler= Default_Handler
-#pragma weak FLASH_IRQHandler= Default_Handler
-#pragma weak RCC_IRQHandler= Default_Handler
-#pragma weak EXTI0_IRQHandler= Default_Handler
-#pragma weak EXTI1_IRQHandler= Default_Handler
-#pragma weak EXTI2_IRQHandler= Default_Handler
-#pragma weak EXTI3_IRQHandler= Default_Handler
-#pragma weak EXTI4_IRQHandler= Default_Handler
-#pragma weak DMA1_Stream0_IRQHandler= Default_Handler
-#pragma weak DMA1_Stream1_IRQHandler= Default_Handler
-#pragma weak DMA1_Stream2_IRQHandler= Default_Handler
-#pragma weak DMA1_Stream3_IRQHandler= Default_Handler
-#pragma weak DMA1_Stream4_IRQHandler= Default_Handler
-#pragma weak DMA1_Stream5_IRQHandler= Default_Handler
-#pragma weak DMA1_Stream6_IRQHandler= Default_Handler
-#pragma weak ADC_IRQHandler= Default_Handler
-#pragma weak CAN1_TX_IRQHandler= Default_Handler
-#pragma weak CAN1_RX0_IRQHandler= Default_Handler
-#pragma weak CAN1_RX1_IRQHandler= Default_Handler
-#pragma weak CAN1_SCE_IRQHandler= Default_Handler
-#pragma weak EXTI9_5_IRQHandler= Default_Handler
-#pragma weak TIM1_BRK_TIM9_IRQHandler= Default_Handler
-#pragma weak TIM1_UP_TIM10_IRQHandler= Default_Handler
-#pragma weak TIM1_TRG_COM_TIM11_IRQHandler= Default_Handler
-#pragma weak TIM1_CC_IRQHandler= Default_Handler
-#pragma weak TIM2_IRQHandler= Default_Handler
-#pragma weak TIM3_IRQHandler= Default_Handler
-#pragma weak TIM4_IRQHandler= Default_Handler
-#pragma weak I2C1_EV_IRQHandler= Default_Handler
-#pragma weak I2C1_ER_IRQHandler= Default_Handler
-#pragma weak I2C2_EV_IRQHandler= Default_Handler
-#pragma weak I2C2_ER_IRQHandler= Default_Handler
-#pragma weak SPI1_IRQHandler= Default_Handler
-#pragma weak SPI2_IRQHandler= Default_Handler
-#pragma weak USART1_IRQHandler= Default_Handler
-#pragma weak USART2_IRQHandler= Default_Handler
-#pragma weak USART3_IRQHandler= Default_Handler
-#pragma weak EXTI15_10_IRQHandler= Default_Handler
-#pragma weak RTC_Alarm_IRQHandler= Default_Handler
-#pragma weak OTG_FS_WKUP_IRQHandler= Default_Handler
-#pragma weak TIM8_BRK_TIM12_IRQHandler= Default_Handler
-#pragma weak TIM8_UP_TIM13_IRQHandler= Default_Handler
-#pragma weak TIM8_TRG_COM_TIM14_IRQHandler= Default_Handler
-#pragma weak TIM8_CC_IRQHandler= Default_Handler
-#pragma weak DMA1_Stream7_IRQHandler= Default_Handler
-#pragma weak FSMC_IRQHandler= Default_Handler
-#pragma weak SDIO_IRQHandler= Default_Handler
-#pragma weak TIM5_IRQHandler= Default_Handler
-#pragma weak SPI3_IRQHandler= Default_Handler
-#pragma weak UART4_IRQHandler= Default_Handler
-#pragma weak UART5_IRQHandler= Default_Handler
-#pragma weak TIM6_DAC_IRQHandler= Default_Handler
-#pragma weak TIM7_IRQHandler= Default_Handler
-#pragma weak DMA2_Stream0_IRQHandler= Default_Handler
-#pragma weak DMA2_Stream1_IRQHandler= Default_Handler
-#pragma weak DMA2_Stream2_IRQHandler= Default_Handler
-#pragma weak DMA2_Stream3_IRQHandler= Default_Handler
-#pragma weak DMA2_Stream4_IRQHandler= Default_Handler
-#pragma weak ETH_IRQHandler= Default_Handler
-#pragma weak ETH_WKUP_IRQHandler= Default_Handler
-#pragma weak CAN2_TX_IRQHandler= Default_Handler
-#pragma weak CAN2_RX0_IRQHandler= Default_Handler
-#pragma weak CAN2_RX1_IRQHandler= Default_Handler
-#pragma weak CAN2_SCE_IRQHandler= Default_Handler
-#pragma weak OTG_FS_IRQHandler= Default_Handler
-#pragma weak DMA2_Stream5_IRQHandler= Default_Handler
-#pragma weak DMA2_Stream6_IRQHandler= Default_Handler
-#pragma weak DMA2_Stream7_IRQHandler= Default_Handler
-#pragma weak USART6_IRQHandler= Default_Handler
-#pragma weak I2C3_EV_IRQHandler= Default_Handler
-#pragma weak I2C3_ER_IRQHandler= Default_Handler
-#pragma weak OTG_HS_EP1_OUT_IRQHandler= Default_Handler
-#pragma weak OTG_HS_EP1_IN_IRQHandler= Default_Handler
-#pragma weak OTG_HS_WKUP_IRQHandler= Default_Handler
-#pragma weak OTG_HS_IRQHandler= Default_Handler
-#pragma weak DCMI_IRQHandler= Default_Handler
-#pragma weak CRYP_IRQHandler= Default_Handler
-#pragma weak HASH_RNG_IRQHandler= Default_Handler
-#pragma weak FPU_IRQHandler= Default_Handler
diff --git a/platform/mcu/STM32F4xx/boot/startup.cpp b/platform/mcu/STM32F4xx/boot/startup.cpp
new file mode 100644
index 00000000..fe64d8b5
--- /dev/null
+++ b/platform/mcu/STM32F4xx/boot/startup.cpp
@@ -0,0 +1,399 @@
+/***************************************************************************
+ * Copyright (C) 2021 by Federico Amedeo Izzo IU2NUO, *
+ * Niccolò Izzo IU2KIN *
+ * Frederik Saraci IU2NRO *
+ * Silvano Seva IU2KWO, *
+ * Federico Terraneo *
+ * *
+ * This program 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 3 of the License, or *
+ * (at your option) any later version. *
+ * *
+ * This program 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, see *
+ ***************************************************************************/
+
+/*
+ * startup.cpp
+ * STM32 C++ startup.
+ * NOTE: for stm32f4 devices ONLY.
+ * Supports interrupt handlers in C++ without extern "C"
+ * Developed by Terraneo Federico, based on ST startup code.
+ * Additionally modified to boot Miosix.
+ */
+
+#include "interfaces/arch_registers.h"
+#include "kernel/stage_2_boot.h"
+#include "core/interrupts.h" //For the unexpected interrupt call
+#include
+
+/**
+ * Called by Reset_Handler, performs initialization and calls main.
+ * Never returns.
+ */
+void program_startup() __attribute__((noreturn));
+void program_startup()
+{
+ //Cortex M3 core appears to get out of reset with interrupts already enabled
+ __disable_irq();
+
+ //SystemInit() is called *before* initializing .data and zeroing .bss
+ //Despite all startup files provided by ST do the opposite, there are three
+ //good reasons to do so:
+ //First, the CMSIS specifications say that SystemInit() must not access
+ //global variables, so it is actually possible to call it before
+ //Second, when running Miosix with the xram linker scripts .data and .bss
+ //are placed in the external RAM, so we *must* call SystemInit(), which
+ //enables xram, before touching .data and .bss
+ //Third, this is a performance improvement since the loops that initialize
+ //.data and zeros .bss now run with the CPU at full speed instead of 8MHz
+ SystemInit();
+
+ //These are defined in the linker script
+ extern unsigned char _etext asm("_etext");
+ extern unsigned char _data asm("_data");
+ extern unsigned char _edata asm("_edata");
+ extern unsigned char _bss_start asm("_bss_start");
+ extern unsigned char _bss_end asm("_bss_end");
+
+ //Initialize .data section, clear .bss section
+ unsigned char *etext=&_etext;
+ unsigned char *data=&_data;
+ unsigned char *edata=&_edata;
+ unsigned char *bss_start=&_bss_start;
+ unsigned char *bss_end=&_bss_end;
+ memcpy(data, etext, edata-data);
+ memset(bss_start, 0, bss_end-bss_start);
+
+ //Move on to stage 2
+ _init();
+
+ //If main returns, reboot
+ NVIC_SystemReset();
+ for(;;) ;
+}
+
+/**
+ * Reset handler, called by hardware immediately after reset
+ */
+void Reset_Handler() __attribute__((__interrupt__, noreturn));
+void Reset_Handler()
+{
+ /*
+ * Initialize process stack and switch to it.
+ * This is required for booting Miosix, a small portion of the top of the
+ * heap area will be used as stack until the first thread starts. After,
+ * this stack will be abandoned and the process stack will point to the
+ * current thread's stack.
+ */
+ asm volatile("ldr r0, =_heap_end \n\t"
+ "msr psp, r0 \n\t"
+ "movw r0, #2 \n\n" //Privileged, process stack
+ "msr control, r0 \n\t"
+ "isb \n\t":::"r0");
+
+ program_startup();
+}
+
+/**
+ * All unused interrupts call this function.
+ */
+extern "C" void Default_Handler()
+{
+ unexpectedInterrupt();
+}
+
+//System handlers
+void /*__attribute__((weak))*/ Reset_Handler(); //These interrupts are not
+void /*__attribute__((weak))*/ NMI_Handler(); //weak because they are
+void /*__attribute__((weak))*/ HardFault_Handler(); //surely defined by Miosix
+void /*__attribute__((weak))*/ MemManage_Handler();
+void /*__attribute__((weak))*/ BusFault_Handler();
+void /*__attribute__((weak))*/ UsageFault_Handler();
+void /*__attribute__((weak))*/ SVC_Handler();
+void /*__attribute__((weak))*/ DebugMon_Handler();
+void /*__attribute__((weak))*/ PendSV_Handler();
+void /*__attribute__((weak))*/ SysTick_Handler();
+
+//Interrupt handlers
+void __attribute__((weak)) WWDG_IRQHandler();
+void __attribute__((weak)) PVD_IRQHandler();
+void __attribute__((weak)) TAMP_STAMP_IRQHandler();
+void __attribute__((weak)) RTC_WKUP_IRQHandler();
+void __attribute__((weak)) FLASH_IRQHandler();
+void __attribute__((weak)) RCC_IRQHandler();
+void __attribute__((weak)) EXTI0_IRQHandler();
+void __attribute__((weak)) EXTI1_IRQHandler();
+void __attribute__((weak)) EXTI2_IRQHandler();
+void __attribute__((weak)) EXTI3_IRQHandler();
+void __attribute__((weak)) EXTI4_IRQHandler();
+void __attribute__((weak)) DMA1_Stream0_IRQHandler();
+void __attribute__((weak)) DMA1_Stream1_IRQHandler();
+void __attribute__((weak)) DMA1_Stream2_IRQHandler();
+void __attribute__((weak)) DMA1_Stream3_IRQHandler();
+void __attribute__((weak)) DMA1_Stream4_IRQHandler();
+void __attribute__((weak)) DMA1_Stream5_IRQHandler();
+void __attribute__((weak)) DMA1_Stream6_IRQHandler();
+void __attribute__((weak)) ADC_IRQHandler();
+void __attribute__((weak)) CAN1_TX_IRQHandler();
+void __attribute__((weak)) CAN1_RX0_IRQHandler();
+void __attribute__((weak)) CAN1_RX1_IRQHandler();
+void __attribute__((weak)) CAN1_SCE_IRQHandler();
+void __attribute__((weak)) EXTI9_5_IRQHandler();
+void __attribute__((weak)) TIM1_BRK_TIM9_IRQHandler();
+void __attribute__((weak)) TIM1_UP_TIM10_IRQHandler();
+void __attribute__((weak)) TIM1_TRG_COM_TIM11_IRQHandler();
+void __attribute__((weak)) TIM1_CC_IRQHandler();
+void __attribute__((weak)) TIM2_IRQHandler();
+void __attribute__((weak)) TIM3_IRQHandler();
+void __attribute__((weak)) TIM4_IRQHandler();
+void __attribute__((weak)) I2C1_EV_IRQHandler();
+void __attribute__((weak)) I2C1_ER_IRQHandler();
+void __attribute__((weak)) I2C2_EV_IRQHandler();
+void __attribute__((weak)) I2C2_ER_IRQHandler();
+void __attribute__((weak)) SPI1_IRQHandler();
+void __attribute__((weak)) SPI2_IRQHandler();
+void __attribute__((weak)) USART1_IRQHandler();
+void __attribute__((weak)) USART2_IRQHandler();
+void __attribute__((weak)) USART3_IRQHandler();
+void __attribute__((weak)) EXTI15_10_IRQHandler();
+void __attribute__((weak)) RTC_Alarm_IRQHandler();
+void __attribute__((weak)) OTG_FS_WKUP_IRQHandler();
+void __attribute__((weak)) TIM8_BRK_TIM12_IRQHandler();
+void __attribute__((weak)) TIM8_UP_TIM13_IRQHandler();
+void __attribute__((weak)) TIM8_TRG_COM_TIM14_IRQHandler();
+void __attribute__((weak)) TIM8_CC_IRQHandler();
+void __attribute__((weak)) DMA1_Stream7_IRQHandler();
+void __attribute__((weak)) FSMC_IRQHandler();
+void __attribute__((weak)) SDIO_IRQHandler();
+void __attribute__((weak)) TIM5_IRQHandler();
+void __attribute__((weak)) SPI3_IRQHandler();
+void __attribute__((weak)) UART4_IRQHandler();
+void __attribute__((weak)) UART5_IRQHandler();
+void __attribute__((weak)) TIM6_DAC_IRQHandler();
+void __attribute__((weak)) TIM7_IRQHandler();
+void __attribute__((weak)) DMA2_Stream0_IRQHandler();
+void __attribute__((weak)) DMA2_Stream1_IRQHandler();
+void __attribute__((weak)) DMA2_Stream2_IRQHandler();
+void __attribute__((weak)) DMA2_Stream3_IRQHandler();
+void __attribute__((weak)) DMA2_Stream4_IRQHandler();
+void __attribute__((weak)) ETH_IRQHandler();
+void __attribute__((weak)) ETH_WKUP_IRQHandler();
+void __attribute__((weak)) CAN2_TX_IRQHandler();
+void __attribute__((weak)) CAN2_RX0_IRQHandler();
+void __attribute__((weak)) CAN2_RX1_IRQHandler();
+void __attribute__((weak)) CAN2_SCE_IRQHandler();
+void __attribute__((weak)) OTG_FS_IRQHandler();
+void __attribute__((weak)) DMA2_Stream5_IRQHandler();
+void __attribute__((weak)) DMA2_Stream6_IRQHandler();
+void __attribute__((weak)) DMA2_Stream7_IRQHandler();
+void __attribute__((weak)) USART6_IRQHandler();
+void __attribute__((weak)) I2C3_EV_IRQHandler();
+void __attribute__((weak)) I2C3_ER_IRQHandler();
+void __attribute__((weak)) OTG_HS_EP1_OUT_IRQHandler();
+void __attribute__((weak)) OTG_HS_EP1_IN_IRQHandler();
+void __attribute__((weak)) OTG_HS_WKUP_IRQHandler();
+void __attribute__((weak)) OTG_HS_IRQHandler();
+void __attribute__((weak)) DCMI_IRQHandler();
+void __attribute__((weak)) CRYP_IRQHandler();
+void __attribute__((weak)) HASH_RNG_IRQHandler();
+void __attribute__((weak)) FPU_IRQHandler();
+
+//Stack top, defined in the linker script
+extern char _main_stack_top asm("_main_stack_top");
+
+//Interrupt vectors, must be placed @ address 0x00000000
+//The extern declaration is required otherwise g++ optimizes it out
+extern void (* const __Vectors[])();
+void (* const __Vectors[])() __attribute__ ((section(".isr_vector"))) =
+{
+ reinterpret_cast(&_main_stack_top),/* Stack pointer*/
+ Reset_Handler, /* Reset Handler */
+ NMI_Handler, /* NMI Handler */
+ HardFault_Handler, /* Hard Fault Handler */
+ MemManage_Handler, /* MPU Fault Handler */
+ BusFault_Handler, /* Bus Fault Handler */
+ UsageFault_Handler, /* Usage Fault Handler */
+ 0, /* Reserved */
+ 0, /* Reserved */
+ 0, /* Reserved */
+ 0, /* Reserved */
+ SVC_Handler, /* SVCall Handler */
+ DebugMon_Handler, /* Debug Monitor Handler */
+ 0, /* Reserved */
+ PendSV_Handler, /* PendSV Handler */
+ SysTick_Handler, /* SysTick Handler */
+
+ /* External Interrupts */
+ WWDG_IRQHandler,
+ PVD_IRQHandler,
+ TAMP_STAMP_IRQHandler,
+ RTC_WKUP_IRQHandler,
+ FLASH_IRQHandler,
+ RCC_IRQHandler,
+ EXTI0_IRQHandler,
+ EXTI1_IRQHandler,
+ EXTI2_IRQHandler,
+ EXTI3_IRQHandler,
+ EXTI4_IRQHandler,
+ DMA1_Stream0_IRQHandler,
+ DMA1_Stream1_IRQHandler,
+ DMA1_Stream2_IRQHandler,
+ DMA1_Stream3_IRQHandler,
+ DMA1_Stream4_IRQHandler,
+ DMA1_Stream5_IRQHandler,
+ DMA1_Stream6_IRQHandler,
+ ADC_IRQHandler,
+ CAN1_TX_IRQHandler,
+ CAN1_RX0_IRQHandler,
+ CAN1_RX1_IRQHandler,
+ CAN1_SCE_IRQHandler,
+ EXTI9_5_IRQHandler,
+ TIM1_BRK_TIM9_IRQHandler,
+ TIM1_UP_TIM10_IRQHandler,
+ TIM1_TRG_COM_TIM11_IRQHandler,
+ TIM1_CC_IRQHandler,
+ TIM2_IRQHandler,
+ TIM3_IRQHandler,
+ TIM4_IRQHandler,
+ I2C1_EV_IRQHandler,
+ I2C1_ER_IRQHandler,
+ I2C2_EV_IRQHandler,
+ I2C2_ER_IRQHandler,
+ SPI1_IRQHandler,
+ SPI2_IRQHandler,
+ USART1_IRQHandler,
+ USART2_IRQHandler,
+ USART3_IRQHandler,
+ EXTI15_10_IRQHandler,
+ RTC_Alarm_IRQHandler,
+ OTG_FS_WKUP_IRQHandler,
+ TIM8_BRK_TIM12_IRQHandler,
+ TIM8_UP_TIM13_IRQHandler,
+ TIM8_TRG_COM_TIM14_IRQHandler,
+ TIM8_CC_IRQHandler,
+ DMA1_Stream7_IRQHandler,
+ FSMC_IRQHandler,
+ SDIO_IRQHandler,
+ TIM5_IRQHandler,
+ SPI3_IRQHandler,
+ UART4_IRQHandler,
+ UART5_IRQHandler,
+ TIM6_DAC_IRQHandler,
+ TIM7_IRQHandler,
+ DMA2_Stream0_IRQHandler,
+ DMA2_Stream1_IRQHandler,
+ DMA2_Stream2_IRQHandler,
+ DMA2_Stream3_IRQHandler,
+ DMA2_Stream4_IRQHandler,
+ ETH_IRQHandler,
+ ETH_WKUP_IRQHandler,
+ CAN2_TX_IRQHandler,
+ CAN2_RX0_IRQHandler,
+ CAN2_RX1_IRQHandler,
+ CAN2_SCE_IRQHandler,
+ OTG_FS_IRQHandler,
+ DMA2_Stream5_IRQHandler,
+ DMA2_Stream6_IRQHandler,
+ DMA2_Stream7_IRQHandler,
+ USART6_IRQHandler,
+ I2C3_EV_IRQHandler,
+ I2C3_ER_IRQHandler,
+ OTG_HS_EP1_OUT_IRQHandler,
+ OTG_HS_EP1_IN_IRQHandler,
+ OTG_HS_WKUP_IRQHandler,
+ OTG_HS_IRQHandler,
+ DCMI_IRQHandler,
+ CRYP_IRQHandler,
+ HASH_RNG_IRQHandler,
+ FPU_IRQHandler,
+};
+
+#pragma weak WWDG_IRQHandler = Default_Handler
+#pragma weak PVD_IRQHandler = Default_Handler
+#pragma weak TAMP_STAMP_IRQHandler = Default_Handler
+#pragma weak RTC_WKUP_IRQHandler = Default_Handler
+#pragma weak FLASH_IRQHandler = Default_Handler
+#pragma weak RCC_IRQHandler = Default_Handler
+#pragma weak EXTI0_IRQHandler = Default_Handler
+#pragma weak EXTI1_IRQHandler = Default_Handler
+#pragma weak EXTI2_IRQHandler = Default_Handler
+#pragma weak EXTI3_IRQHandler = Default_Handler
+#pragma weak EXTI4_IRQHandler = Default_Handler
+#pragma weak DMA1_Stream0_IRQHandler = Default_Handler
+#pragma weak DMA1_Stream1_IRQHandler = Default_Handler
+#pragma weak DMA1_Stream2_IRQHandler = Default_Handler
+#pragma weak DMA1_Stream3_IRQHandler = Default_Handler
+#pragma weak DMA1_Stream4_IRQHandler = Default_Handler
+#pragma weak DMA1_Stream5_IRQHandler = Default_Handler
+#pragma weak DMA1_Stream6_IRQHandler = Default_Handler
+#pragma weak ADC_IRQHandler = Default_Handler
+#pragma weak CAN1_TX_IRQHandler = Default_Handler
+#pragma weak CAN1_RX0_IRQHandler = Default_Handler
+#pragma weak CAN1_RX1_IRQHandler = Default_Handler
+#pragma weak CAN1_SCE_IRQHandler = Default_Handler
+#pragma weak EXTI9_5_IRQHandler = Default_Handler
+#pragma weak TIM1_BRK_TIM9_IRQHandler = Default_Handler
+#pragma weak TIM1_UP_TIM10_IRQHandler = Default_Handler
+#pragma weak TIM1_TRG_COM_TIM11_IRQHandler = Default_Handler
+#pragma weak TIM1_CC_IRQHandler = Default_Handler
+#pragma weak TIM2_IRQHandler = Default_Handler
+#pragma weak TIM3_IRQHandler = Default_Handler
+#pragma weak TIM4_IRQHandler = Default_Handler
+#pragma weak I2C1_EV_IRQHandler = Default_Handler
+#pragma weak I2C1_ER_IRQHandler = Default_Handler
+#pragma weak I2C2_EV_IRQHandler = Default_Handler
+#pragma weak I2C2_ER_IRQHandler = Default_Handler
+#pragma weak SPI1_IRQHandler = Default_Handler
+#pragma weak SPI2_IRQHandler = Default_Handler
+#pragma weak USART1_IRQHandler = Default_Handler
+#pragma weak USART2_IRQHandler = Default_Handler
+#pragma weak USART3_IRQHandler = Default_Handler
+#pragma weak EXTI15_10_IRQHandler = Default_Handler
+#pragma weak RTC_Alarm_IRQHandler = Default_Handler
+#pragma weak OTG_FS_WKUP_IRQHandler = Default_Handler
+#pragma weak TIM8_BRK_TIM12_IRQHandler = Default_Handler
+#pragma weak TIM8_UP_TIM13_IRQHandler = Default_Handler
+#pragma weak TIM8_TRG_COM_TIM14_IRQHandler = Default_Handler
+#pragma weak TIM8_CC_IRQHandler = Default_Handler
+#pragma weak DMA1_Stream7_IRQHandler = Default_Handler
+#pragma weak FSMC_IRQHandler = Default_Handler
+#pragma weak SDIO_IRQHandler = Default_Handler
+#pragma weak TIM5_IRQHandler = Default_Handler
+#pragma weak SPI3_IRQHandler = Default_Handler
+#pragma weak UART4_IRQHandler = Default_Handler
+#pragma weak UART5_IRQHandler = Default_Handler
+#pragma weak TIM6_DAC_IRQHandler = Default_Handler
+#pragma weak TIM7_IRQHandler = Default_Handler
+#pragma weak DMA2_Stream0_IRQHandler = Default_Handler
+#pragma weak DMA2_Stream1_IRQHandler = Default_Handler
+#pragma weak DMA2_Stream2_IRQHandler = Default_Handler
+#pragma weak DMA2_Stream3_IRQHandler = Default_Handler
+#pragma weak DMA2_Stream4_IRQHandler = Default_Handler
+#pragma weak ETH_IRQHandler = Default_Handler
+#pragma weak ETH_WKUP_IRQHandler = Default_Handler
+#pragma weak CAN2_TX_IRQHandler = Default_Handler
+#pragma weak CAN2_RX0_IRQHandler = Default_Handler
+#pragma weak CAN2_RX1_IRQHandler = Default_Handler
+#pragma weak CAN2_SCE_IRQHandler = Default_Handler
+#pragma weak OTG_FS_IRQHandler = Default_Handler
+#pragma weak DMA2_Stream5_IRQHandler = Default_Handler
+#pragma weak DMA2_Stream6_IRQHandler = Default_Handler
+#pragma weak DMA2_Stream7_IRQHandler = Default_Handler
+#pragma weak USART6_IRQHandler = Default_Handler
+#pragma weak I2C3_EV_IRQHandler = Default_Handler
+#pragma weak I2C3_ER_IRQHandler = Default_Handler
+#pragma weak OTG_HS_EP1_OUT_IRQHandler = Default_Handler
+#pragma weak OTG_HS_EP1_IN_IRQHandler = Default_Handler
+#pragma weak OTG_HS_WKUP_IRQHandler = Default_Handler
+#pragma weak OTG_HS_IRQHandler = Default_Handler
+#pragma weak DCMI_IRQHandler = Default_Handler
+#pragma weak CRYP_IRQHandler = Default_Handler
+#pragma weak HASH_RNG_IRQHandler = Default_Handler
+#pragma weak FPU_IRQHandler = Default_Handler
diff --git a/platform/mcu/STM32F4xx/linker_script.ld b/platform/mcu/STM32F4xx/linker_script.ld
index 7aacbc27..5520da0a 100644
--- a/platform/mcu/STM32F4xx/linker_script.ld
+++ b/platform/mcu/STM32F4xx/linker_script.ld
@@ -1,32 +1,71 @@
/*
- RAM space is organized in this way: the stack begins at the end of
- the RAM space and grows down towards the base, while the heap begins
- at the end of the bss space (symbol _end) and grows up towards the
- end of the RAM.
-
- WARNING: with this configuration we have an high risk of collision
- between stack and heap, since none of them is limited. One thing to
- do in the future is to put this limit to the stack.
+ * C++ enabled linker script for stm32 (1M FLASH, 192K RAM)
+ * Developed by TFT: Terraneo Federico Technologies
+ * Optimized for use with the Miosix kernel
*/
-/* stack top in large ram, at an address which, masked with 0x2FFE0000,
- gives 0x20000000
-*/
-_stack_top = 0x2001FFFC;
+/*
+ * This chip has an unusual quirk that the RAM is divided in two block mapped
+ * at two non contiguous memory addresses. I don't know why they've done that,
+ * probably doing the obvious thing would have made writing code too easy...
+ * Anyway, since hardware can't be changed, we've got to live with that and
+ * try to make use of both RAMs.
+ *
+ * Given the constraints above, this linker script puts:
+ * - read only data and code (.text, .rodata, .eh_*) in FLASH
+ * - .data and .bss in the "small" 64KB RAM
+ * - the 512Byte main (IRQ) stack, stacks and heap in the "large" 128KB RAM.
+ *
+ * Unfortunately thread stacks can't be put in the small RAM as Miosix
+ * allocates them inside the heap.
+ */
-/* temporary set heap end equal to stack top */
-_heap_end = _stack_top;
+/*
+ * The main stack is used for interrupt handling by the kernel.
+ *
+ * *** Readme ***
+ * This linker script places the main stack (used by the kernel for interrupts)
+ * at the bottom of the ram, instead of the top. This is done for two reasons:
+ *
+ * - as an optimization for microcontrollers with little ram memory. In fact
+ * the implementation of malloc from newlib requests memory to the OS in 4KB
+ * block (except the first block that can be smaller). This is probably done
+ * for compatibility with OSes with an MMU and paged memory. To see why this
+ * is bad, consider a microcontroller with 8KB of ram: when malloc finishes
+ * up the first 4KB it will call _sbrk_r asking for a 4KB block, but this will
+ * fail because the top part of the ram is used by the main stack. As a
+ * result, the top part of the memory will not be used by malloc, even if
+ * available (and it is nearly *half* the ram on an 8KB mcu). By placing the
+ * main stack at the bottom of the ram, the upper 4KB block will be entirely
+ * free and available as heap space.
+ *
+ * - In case of main stack overflow the cpu will fault because access to memory
+ * before the beginning of the ram faults. Instead with the default stack
+ * placement the main stack will silently collide with the heap.
+ * Note: if increasing the main stack size also increase the ORIGIN value in
+ * the MEMORY definitions below accordingly.
+ */
+_main_stack_size = 0x00000200; /* main stack = 512Bytes */
+_main_stack_top = 0x20000000 + _main_stack_size;
+ASSERT(_main_stack_size % 8 == 0, "MAIN stack size error");
+/* Mapping the heap into the large 128KB RAM */
+_end = _main_stack_top;
+_heap_end = 0x20020000; /* end of available ram */
/* identify the Entry Point */
-ENTRY(Reset_Handler)
+ENTRY(_Z13Reset_Handlerv)
/* specify the memory areas */
MEMORY
{
- flash(rx) : ORIGIN = 0x0800C000, LENGTH = 1M - 48K
- smallram(wx) : ORIGIN = 0x10000200, LENGTH = 64K
- largeram(wx) : ORIGIN = 0x20000000, LENGTH = 128K
+ flash(rx) : ORIGIN = 0x0800C000, LENGTH = 1M - 48K
+ /*
+ * Note, the small ram starts at 0x10000000 but it is necessary to add the
+ * size of the main stack, so it is 0x10000200.
+ */
+ smallram(wx) : ORIGIN = 0x10000000, LENGTH = 64K
+ largeram(wx) : ORIGIN = 0x20000200, LENGTH = 128K-0x200
}
/* now define the output sections */
@@ -62,6 +101,12 @@ SECTIONS
. = ALIGN(4);
KEEP(*(.init))
+ . = ALIGN(4);
+ __miosix_init_array_start = .;
+ KEEP (*(SORT(.miosix_init_array.*)))
+ KEEP (*(.miosix_init_array))
+ __miosix_init_array_end = .;
+
. = ALIGN(4);
__preinit_array_start = .;
KEEP (*(.preinit_array))
@@ -106,7 +151,7 @@ SECTIONS
} > flash
__exidx_end = .;
- /* .data section: global variables go to ram, but also store a copy to
+ /* .data section: global variables go to ram, but also store a copy to
flash to initialize them */
.data : ALIGN(8)
{
@@ -120,16 +165,16 @@ SECTIONS
_etext = LOADADDR(.data);
/* .bss section: uninitialized global variables go to ram */
+ _bss_start = .;
.bss :
{
- _bss_start = .;
*(.bss)
*(.bss.*)
*(.gnu.linkonce.b.*)
. = ALIGN(8);
- } > largeram
+ } > smallram
_bss_end = .;
- _end = .;
- PROVIDE(end = .);
+ /*_end = .;*/
+ /*PROVIDE(end = .);*/
}