From fbd2e0b98cb5470ef42f8245a343cfb3affa607c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C5=A0t=C4=9Bp=C3=A1n=20Daleck=C3=BD?= Date: Tue, 21 Jun 2022 17:50:18 +0200 Subject: [PATCH] Remove unused F1 and F3 files --- src/main/drivers/adc_stm32f10x.c | 174 ------ src/main/drivers/adc_stm32f30x.c | 272 ---------- src/main/startup/startup_stm32f10x_hd_gcc.S | 513 ------------------ src/main/startup/startup_stm32f10x_md_gcc.S | 408 -------------- src/main/startup/startup_stm32f30x_md_gcc.S | 483 ----------------- .../startup_stm32f3_debug_hardfault_handler.S | 501 ----------------- src/main/vcp/hw_config.h | 3 - 7 files changed, 2354 deletions(-) delete mode 100644 src/main/drivers/adc_stm32f10x.c delete mode 100644 src/main/drivers/adc_stm32f30x.c delete mode 100644 src/main/startup/startup_stm32f10x_hd_gcc.S delete mode 100644 src/main/startup/startup_stm32f10x_md_gcc.S delete mode 100644 src/main/startup/startup_stm32f30x_md_gcc.S delete mode 100644 src/main/startup/startup_stm32f3_debug_hardfault_handler.S diff --git a/src/main/drivers/adc_stm32f10x.c b/src/main/drivers/adc_stm32f10x.c deleted file mode 100644 index ff3b5341e3..0000000000 --- a/src/main/drivers/adc_stm32f10x.c +++ /dev/null @@ -1,174 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software 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. - * - * Cleanflight and Betaflight are distributed in the hope that they - * 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 software. - * - * If not, see . - */ - -#include -#include -#include - -#include "platform.h" - -#ifdef USE_ADC - -#include "build/build_config.h" - -#include "drivers/sensor.h" -#include "adc.h" -#include "adc_impl.h" -#include "drivers/io.h" -#include "rcc.h" -#include "dma.h" - -#include "pg/adc.h" - - -const adcDevice_t adcHardware[] = { - { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .dmaResource = (dmaResource_t *)DMA1_Channel1 } -}; - -const adcTagMap_t adcTagMap[] = { - { DEFIO_TAG_E__PA0, ADC_Channel_0 }, // ADC12 - { DEFIO_TAG_E__PA1, ADC_Channel_1 }, // ADC12 - { DEFIO_TAG_E__PA2, ADC_Channel_2 }, // ADC12 - { DEFIO_TAG_E__PA3, ADC_Channel_3 }, // ADC12 - { DEFIO_TAG_E__PA4, ADC_Channel_4 }, // ADC12 - { DEFIO_TAG_E__PA5, ADC_Channel_5 }, // ADC12 - { DEFIO_TAG_E__PA6, ADC_Channel_6 }, // ADC12 - { DEFIO_TAG_E__PA7, ADC_Channel_7 }, // ADC12 - { DEFIO_TAG_E__PB0, ADC_Channel_8 }, // ADC12 - { DEFIO_TAG_E__PB1, ADC_Channel_9 }, // ADC12 -}; - -// Driver for STM32F103CB onboard ADC -// -// Naze32 -// Battery Voltage (VBAT) is connected to PA4 (ADC1_IN4) with 10k:1k divider -// RSSI ADC uses CH2 (PA1, ADC1_IN1) -// Current ADC uses CH8 (PB1, ADC1_IN9) -// -// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board -// - -void adcInit(const adcConfig_t *config) -{ - uint8_t configuredAdcChannels = 0; - - memset(&adcOperatingConfig, 0, sizeof(adcOperatingConfig)); - - if (config->vbat.enabled) { - adcOperatingConfig[ADC_BATTERY].tag = config->vbat.ioTag; - } - - if (config->rssi.enabled) { - adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL; - } - - if (config->external1.enabled) { - adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL; - } - - if (config->current.enabled) { - adcOperatingConfig[ADC_CURRENT].tag = config->current.ioTag; //CURRENT_METER_ADC_CHANNEL; - } - - ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); - if (device == ADCINVALID) { - return; - } - - const adcDevice_t adc = adcHardware[device]; - - if (!dmaAllocate(dmaGetIdentifier(adc.dmaResource), OWNER_ADC, 0)) { - return; - } - - bool adcActive = false; - for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { - if (!adcOperatingConfig[i].tag) - continue; - - adcActive = true; - IOInit(IOGetByTag(adcOperatingConfig[i].tag), OWNER_ADC_BATT + i, 0); - IOConfigGPIO(IOGetByTag(adcOperatingConfig[i].tag), IO_CONFIG(GPIO_Mode_AIN, 0)); - adcOperatingConfig[i].adcChannel = adcChannelByTag(adcOperatingConfig[i].tag); - adcOperatingConfig[i].dmaIndex = configuredAdcChannels++; - adcOperatingConfig[i].sampleTime = ADC_SampleTime_239Cycles5; - adcOperatingConfig[i].enabled = true; - } - - if (!adcActive) { - return; - } - - RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI) - RCC_ClockCmd(adc.rccADC, ENABLE); - - dmaEnable(dmaGetIdentifier(adc.dmaResource)); - - xDMA_DeInit(adc.dmaResource); - DMA_InitTypeDef DMA_InitStructure; - DMA_StructInit(&DMA_InitStructure); - DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR; - DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues; - DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; - DMA_InitStructure.DMA_BufferSize = configuredAdcChannels; - DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; - DMA_InitStructure.DMA_MemoryInc = configuredAdcChannels > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable; - DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; - DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord; - DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; - DMA_InitStructure.DMA_Priority = DMA_Priority_High; - DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; - xDMA_Init(adc.dmaResource, &DMA_InitStructure); - xDMA_Cmd(adc.dmaResource, ENABLE); - - ADC_InitTypeDef ADC_InitStructure; - ADC_StructInit(&ADC_InitStructure); - ADC_InitStructure.ADC_Mode = ADC_Mode_Independent; - ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; - ADC_InitStructure.ADC_ContinuousConvMode = ENABLE; - ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None; - ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; - ADC_InitStructure.ADC_NbrOfChannel = configuredAdcChannels; - ADC_Init(adc.ADCx, &ADC_InitStructure); - - uint8_t rank = 1; - for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { - if (!adcOperatingConfig[i].enabled) { - continue; - } - ADC_RegularChannelConfig(adc.ADCx, adcOperatingConfig[i].adcChannel, rank++, adcOperatingConfig[i].sampleTime); - } - - ADC_DMACmd(adc.ADCx, ENABLE); - ADC_Cmd(adc.ADCx, ENABLE); - - ADC_ResetCalibration(adc.ADCx); - while (ADC_GetResetCalibrationStatus(adc.ADCx)); - ADC_StartCalibration(adc.ADCx); - while (ADC_GetCalibrationStatus(adc.ADCx)); - - ADC_SoftwareStartConvCmd(adc.ADCx, ENABLE); -} - -void adcGetChannelValues(void) -{ - // Nothing to do -} -#endif diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c deleted file mode 100644 index 59a5254c18..0000000000 --- a/src/main/drivers/adc_stm32f30x.c +++ /dev/null @@ -1,272 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software 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. - * - * Cleanflight and Betaflight are distributed in the hope that they - * 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 software. - * - * If not, see . - */ - -#include -#include -#include - -#include "platform.h" - -#ifdef USE_ADC - -#include "common/utils.h" - -#include "drivers/adc_impl.h" -#include "drivers/dma.h" -#include "drivers/dma_reqmap.h" -#include "drivers/io.h" -#include "drivers/rcc.h" -#include "drivers/sensor.h" -#include "drivers/time.h" - -#include "pg/adc.h" - -#include "adc.h" - -const adcDevice_t adcHardware[] = { - { .ADCx = ADC1, .rccADC = RCC_AHB(ADC12), -#if !defined(USE_DMA_SPEC) - .dmaResource = (dmaResource_t *)DMA1_Channel1, -#endif - }, -#ifdef ADC24_DMA_REMAP - { .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), -#if !defined(USE_DMA_SPEC) - .dmaResource = (dmaResource_t *)DMA2_Channel3, -#endif - }, -#else - { .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), -#if !defined(USE_DMA_SPEC) - .dmaResource = (dmaResource_t *)DMA2_Channel1, -#endif - }, -#endif - { .ADCx = ADC3, .rccADC = RCC_AHB(ADC34), -#if !defined(USE_DMA_SPEC) - .dmaResource = (dmaResource_t *)DMA2_Channel5, -#endif - } -}; - -const adcTagMap_t adcTagMap[] = { - { DEFIO_TAG_E__PA0, ADC_DEVICES_1, ADC_Channel_1 }, // ADC1 - { DEFIO_TAG_E__PA1, ADC_DEVICES_1, ADC_Channel_2 }, // ADC1 - { DEFIO_TAG_E__PA2, ADC_DEVICES_1, ADC_Channel_3 }, // ADC1 - { DEFIO_TAG_E__PA3, ADC_DEVICES_1, ADC_Channel_4 }, // ADC1 - { DEFIO_TAG_E__PA4, ADC_DEVICES_2, ADC_Channel_1 }, // ADC2 - { DEFIO_TAG_E__PA5, ADC_DEVICES_2, ADC_Channel_2 }, // ADC2 - { DEFIO_TAG_E__PA6, ADC_DEVICES_2, ADC_Channel_3 }, // ADC2 - { DEFIO_TAG_E__PA7, ADC_DEVICES_4, ADC_Channel_4 }, // ADC2 - { DEFIO_TAG_E__PB0, ADC_DEVICES_3, ADC_Channel_12 }, // ADC3 - { DEFIO_TAG_E__PB1, ADC_DEVICES_3, ADC_Channel_1 }, // ADC3 - { DEFIO_TAG_E__PB2, ADC_DEVICES_2, ADC_Channel_12 }, // ADC2 - { DEFIO_TAG_E__PB12, ADC_DEVICES_4, ADC_Channel_3 }, // ADC4 - { DEFIO_TAG_E__PB13, ADC_DEVICES_3, ADC_Channel_5 }, // ADC3 - { DEFIO_TAG_E__PB14, ADC_DEVICES_4, ADC_Channel_4 }, // ADC4 - { DEFIO_TAG_E__PB15, ADC_DEVICES_4, ADC_Channel_5 }, // ADC4 - { DEFIO_TAG_E__PC0, ADC_DEVICES_12, ADC_Channel_6 }, // ADC12 - { DEFIO_TAG_E__PC1, ADC_DEVICES_12, ADC_Channel_7 }, // ADC12 - { DEFIO_TAG_E__PC2, ADC_DEVICES_12, ADC_Channel_8 }, // ADC12 - { DEFIO_TAG_E__PC3, ADC_DEVICES_12, ADC_Channel_9 }, // ADC12 - { DEFIO_TAG_E__PC4, ADC_DEVICES_2, ADC_Channel_5 }, // ADC2 - { DEFIO_TAG_E__PC5, ADC_DEVICES_2, ADC_Channel_11 }, // ADC2 - { DEFIO_TAG_E__PD8, ADC_DEVICES_4, ADC_Channel_12 }, // ADC4 - { DEFIO_TAG_E__PD9, ADC_DEVICES_4, ADC_Channel_13 }, // ADC4 - { DEFIO_TAG_E__PD10, ADC_DEVICES_34, ADC_Channel_7 }, // ADC34 - { DEFIO_TAG_E__PD11, ADC_DEVICES_34, ADC_Channel_8 }, // ADC34 - { DEFIO_TAG_E__PD12, ADC_DEVICES_34, ADC_Channel_9 }, // ADC34 - { DEFIO_TAG_E__PD13, ADC_DEVICES_34, ADC_Channel_10 }, // ADC34 - { DEFIO_TAG_E__PD14, ADC_DEVICES_34, ADC_Channel_11 }, // ADC34 - { DEFIO_TAG_E__PE7, ADC_DEVICES_3, ADC_Channel_13 }, // ADC3 - { DEFIO_TAG_E__PE8, ADC_DEVICES_34, ADC_Channel_6 }, // ADC34 - { DEFIO_TAG_E__PE9, ADC_DEVICES_3, ADC_Channel_2 }, // ADC3 - { DEFIO_TAG_E__PE10, ADC_DEVICES_3, ADC_Channel_14 }, // ADC3 - { DEFIO_TAG_E__PE11, ADC_DEVICES_3, ADC_Channel_15 }, // ADC3 - { DEFIO_TAG_E__PE12, ADC_DEVICES_3, ADC_Channel_16 }, // ADC3 - { DEFIO_TAG_E__PE13, ADC_DEVICES_3, ADC_Channel_3 }, // ADC3 - { DEFIO_TAG_E__PE14, ADC_DEVICES_4, ADC_Channel_1 }, // ADC4 - { DEFIO_TAG_E__PE15, ADC_DEVICES_4, ADC_Channel_2 }, // ADC4 - { DEFIO_TAG_E__PF2, ADC_DEVICES_12, ADC_Channel_10 }, // ADC12 - { DEFIO_TAG_E__PF4, ADC_DEVICES_1, ADC_Channel_5 }, // ADC1 -}; - -void adcInit(const adcConfig_t *config) -{ - ADC_InitTypeDef ADC_InitStructure; - DMA_InitTypeDef DMA_InitStructure; - - uint8_t adcChannelCount = 0; - - memset(&adcOperatingConfig, 0, sizeof(adcOperatingConfig)); - - if (config->vbat.enabled) { - adcOperatingConfig[ADC_BATTERY].tag = config->vbat.ioTag; - } - - if (config->rssi.enabled) { - adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL; - } - - if (config->external1.enabled) { - adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL; - } - - if (config->current.enabled) { - adcOperatingConfig[ADC_CURRENT].tag = config->current.ioTag; //CURRENT_METER_ADC_CHANNEL; - } - - ADCDevice device = ADC_CFG_TO_DEV(config->device); - - if (device == ADCINVALID) { - return; - } - -#ifdef ADC24_DMA_REMAP - SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_ADC2ADC4, ENABLE); -#endif - adcDevice_t adc = adcHardware[device]; - - bool adcActive = false; - for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { - if (!adcVerifyPin(adcOperatingConfig[i].tag, device)) { - continue; - } - - adcActive = true; - IOInit(IOGetByTag(adcOperatingConfig[i].tag), OWNER_ADC_BATT + i, 0); - IOConfigGPIO(IOGetByTag(adcOperatingConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcOperatingConfig[i].adcChannel = adcChannelByTag(adcOperatingConfig[i].tag); - adcOperatingConfig[i].dmaIndex = adcChannelCount++; - adcOperatingConfig[i].sampleTime = ADC_SampleTime_601Cycles5; - adcOperatingConfig[i].enabled = true; - } - - if (!adcActive) { - return; - } - - if ((device == ADCDEV_1) || (device == ADCDEV_2)) { - // enable clock for ADC1+2 - RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz - } else { - // enable clock for ADC3+4 - RCC_ADCCLKConfig(RCC_ADC34PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz - } - - RCC_ClockCmd(adc.rccADC, ENABLE); - -#if defined(USE_DMA_SPEC) - const dmaChannelSpec_t *dmaSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_ADC, device, config->dmaopt[device]); - - if (!dmaSpec || !dmaAllocate(dmaGetIdentifier(dmaSpec->ref), OWNER_ADC, RESOURCE_INDEX(device))) { - return; - } - - dmaEnable(dmaGetIdentifier(dmaSpec->ref)); - - DMA_DeInit((DMA_ARCH_TYPE *)dmaSpec->ref); -#else - if (!dmaAllocate(dmaGetIdentifier(adc.dmaResource), OWNER_ADC, 0)) { - return; - } - - dmaEnable(dmaGetIdentifier(adc.dmaResource)); - - xDMA_DeInit(adc.dmaResource); -#endif - - DMA_StructInit(&DMA_InitStructure); - DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR; - DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues; - DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; - DMA_InitStructure.DMA_BufferSize = adcChannelCount; - DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; - DMA_InitStructure.DMA_MemoryInc = adcChannelCount > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable; - DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; - DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord; - DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; - DMA_InitStructure.DMA_Priority = DMA_Priority_High; - DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; - -#if defined(USE_DMA_SPEC) - xDMA_Init(dmaSpec->ref, &DMA_InitStructure); - xDMA_Cmd(dmaSpec->ref, ENABLE); -#else - xDMA_Init(adc.dmaResource, &DMA_InitStructure); - xDMA_Cmd(adc.dmaResource, ENABLE); -#endif - - // calibrate - - ADC_VoltageRegulatorCmd(adc.ADCx, ENABLE); - delay(10); - ADC_SelectCalibrationMode(adc.ADCx, ADC_CalibrationMode_Single); - ADC_StartCalibration(adc.ADCx); - while (ADC_GetCalibrationStatus(adc.ADCx) != RESET); - ADC_VoltageRegulatorCmd(adc.ADCx, DISABLE); - - ADC_CommonInitTypeDef ADC_CommonInitStructure; - - ADC_CommonStructInit(&ADC_CommonInitStructure); - ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent; - ADC_CommonInitStructure.ADC_Clock = ADC_Clock_SynClkModeDiv4; - ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_1; - ADC_CommonInitStructure.ADC_DMAMode = ADC_DMAMode_Circular; - ADC_CommonInitStructure.ADC_TwoSamplingDelay = 0; - ADC_CommonInit(adc.ADCx, &ADC_CommonInitStructure); - - ADC_StructInit(&ADC_InitStructure); - - ADC_InitStructure.ADC_ContinuousConvMode = ADC_ContinuousConvMode_Enable; - ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b; - ADC_InitStructure.ADC_ExternalTrigConvEvent = ADC_ExternalTrigConvEvent_0; - ADC_InitStructure.ADC_ExternalTrigEventEdge = ADC_ExternalTrigEventEdge_None; - ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; - ADC_InitStructure.ADC_OverrunMode = ADC_OverrunMode_Disable; - ADC_InitStructure.ADC_AutoInjMode = ADC_AutoInjec_Disable; - ADC_InitStructure.ADC_NbrOfRegChannel = adcChannelCount; - - ADC_Init(adc.ADCx, &ADC_InitStructure); - - uint8_t rank = 1; - for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { - if (!adcOperatingConfig[i].enabled) { - continue; - } - ADC_RegularChannelConfig(adc.ADCx, adcOperatingConfig[i].adcChannel, rank++, adcOperatingConfig[i].sampleTime); - } - - ADC_Cmd(adc.ADCx, ENABLE); - - while (!ADC_GetFlagStatus(adc.ADCx, ADC_FLAG_RDY)); - - ADC_DMAConfig(adc.ADCx, ADC_DMAMode_Circular); - - ADC_DMACmd(adc.ADCx, ENABLE); - - ADC_StartConversion(adc.ADCx); -} - -void adcGetChannelValues(void) -{ - // Nothing to do -} -#endif diff --git a/src/main/startup/startup_stm32f10x_hd_gcc.S b/src/main/startup/startup_stm32f10x_hd_gcc.S deleted file mode 100644 index a828691b64..0000000000 --- a/src/main/startup/startup_stm32f10x_hd_gcc.S +++ /dev/null @@ -1,513 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f10x_hd.s - * @author MCD Application Team - * @version V3.5.0 - * @date 11-March-2011 - * @brief STM32F10x High Density Devices vector table for Atollic toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Configure the clock system - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m3 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -.equ BootRAM, 0xF1E0F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr r0, =0x2000CFF0 // HJI - TC bootloader entry on reset mod - ldr r1, =0xDEADBEEF // HJI - TC bootloader entry on reset mod - ldr r2, [r0, #0] // HJI - TC bootloader entry on reset mod - str r0, [r0, #0] // HJI - TC bootloader entry on reset mod - cmp r2, r1 // HJI - TC bootloader entry on reset mod - beq Reboot_Loader // HJI - TC bootloader entry on reset mod - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call the application's entry point.*/ - bl main -/* Atollic update, branch LoopForever */ -LoopForever: - b LoopForever - -.equ RCC_APB2ENR, 0x40021018 // HJI - TC bootloader entry on reset mod -.equ GPIO_AFIO_MASK, 0x00000009 // HJI - TC bootloader entry on reset mod -.equ GPIOB_CRL, 0x40010C00 // HJI - TC bootloader entry on reset mod -.equ GPIOB_BRR, 0x40010C14 // HJI - TC bootloader entry on reset mod -.equ AFIO_MAPR, 0x40010004 // HJI - TC bootloader entry on reset mod - -Reboot_Loader: // HJI - TC bootloader entry on reset mod - // RCC Enable GPIOB+AFIO // HJI - TC bootloader entry on reset mod - ldr r6, =RCC_APB2ENR // HJI - TC bootloader entry on reset mod - ldr r0, =GPIO_AFIO_MASK // HJI - TC bootloader entry on reset mod - str R0, [r6]; // HJI - TC bootloader entry on reset mod - - // MAPR pt1 // HJI - TC bootloader entry on reset mod - ldr r0, =AFIO_MAPR // HJI - TC bootloader entry on reset mod - ldr r1, [r0] // HJI - TC bootloader entry on reset mod - bic r1, r1, #0x0F000000 // HJI - TC bootloader entry on reset mod - str r1, [r0] // HJI - TC bootloader entry on reset mod - - // MAPR pt2 // HJI - TC bootloader entry on reset mod - lsls r1, r0, #9 // HJI - TC bootloader entry on reset mod - str r1, [r0] // HJI - TC bootloader entry on reset mod - - // BRR // HJI - TC bootloader entry on reset mod - ldr r4, =GPIOB_BRR // HJI - TC bootloader entry on reset mod - movs r0, #0x18 // HJI - TC bootloader entry on reset mod - str r0, [r4] // HJI - TC bootloader entry on reset mod - - // CRL // HJI - TC bootloader entry on reset mod - ldr r1, =GPIOB_CRL // HJI - TC bootloader entry on reset mod - ldr r0, =0x44433444 // HJI - TC bootloader entry on reset mod - str r0, [r1] // HJI - TC bootloader entry on reset mod - - // Reboot to ROM // HJI - TC bootloader entry on reset mod - ldr r0, =0x1FFFF000 // HJI - TC bootloader entry on reset mod - ldr sp,[r0, #0] // HJI - TC bootloader entry on reset mod - ldr r0,[r0, #4] // HJI - TC bootloader entry on reset mod - bx r0 // HJI - TC bootloader entry on reset mod - -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * - * @param None - * @retval : None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_IRQHandler - .word RTC_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_IRQHandler - .word TIM1_UP_IRQHandler - .word TIM1_TRG_COM_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTCAlarm_IRQHandler - .word USBWakeUp_IRQHandler - .word TIM8_BRK_IRQHandler - .word TIM8_UP_IRQHandler - .word TIM8_TRG_COM_IRQHandler - .word TIM8_CC_IRQHandler - .word ADC3_IRQHandler - .word FSMC_IRQHandler - .word SDIO_IRQHandler - .word TIM5_IRQHandler - .word SPI3_IRQHandler - .word UART4_IRQHandler - .word UART5_IRQHandler - .word TIM6_IRQHandler - .word TIM7_IRQHandler - .word DMA2_Channel1_IRQHandler - .word DMA2_Channel2_IRQHandler - .word DMA2_Channel3_IRQHandler - .word DMA2_Channel4_5_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x1E0. This is for boot in RAM mode for - STM32F10x High Density devices. */ -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_IRQHandler - .thumb_set TIM1_BRK_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTCAlarm_IRQHandler - .thumb_set RTCAlarm_IRQHandler,Default_Handler - - .weak USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - - .weak TIM8_BRK_IRQHandler - .thumb_set TIM8_BRK_IRQHandler,Default_Handler - - .weak TIM8_UP_IRQHandler - .thumb_set TIM8_UP_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_IRQHandler - .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak ADC3_IRQHandler - .thumb_set ADC3_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_IRQHandler - .thumb_set TIM6_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Channel1_IRQHandler - .thumb_set DMA2_Channel1_IRQHandler,Default_Handler - - .weak DMA2_Channel2_IRQHandler - .thumb_set DMA2_Channel2_IRQHandler,Default_Handler - - .weak DMA2_Channel3_IRQHandler - .thumb_set DMA2_Channel3_IRQHandler,Default_Handler - - .weak DMA2_Channel4_5_IRQHandler - .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ - diff --git a/src/main/startup/startup_stm32f10x_md_gcc.S b/src/main/startup/startup_stm32f10x_md_gcc.S deleted file mode 100644 index 4bd8b2b731..0000000000 --- a/src/main/startup/startup_stm32f10x_md_gcc.S +++ /dev/null @@ -1,408 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f10x_md.s - * @author MCD Application Team - * @version V3.5.0 - * @date 11-March-2011 - * @brief STM32F10x Medium Density Devices vector table for Atollic toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Configure the clock system - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m3 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss - -.equ BootRAM, 0xF108F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr r0, =0x20004FF0 // HJI - TC bootloader entry on reset mod - ldr r1, =0xDEADBEEF // HJI - TC bootloader entry on reset mod - ldr r2, [r0, #0] // HJI - TC bootloader entry on reset mod - str r0, [r0, #0] // HJI - TC bootloader entry on reset mod - cmp r2, r1 // HJI - TC bootloader entry on reset mod - beq Reboot_Loader // HJI - TC bootloader entry on reset mod - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call the application's entry point.*/ - bl main -/* Atollic update, branch LoopForever */ -LoopForever: - b LoopForever - -.equ RCC_APB2ENR, 0x40021018 // HJI - TC bootloader entry on reset mod -.equ GPIO_AFIO_MASK, 0x00000009 // HJI - TC bootloader entry on reset mod -.equ GPIOB_CRL, 0x40010C00 // HJI - TC bootloader entry on reset mod -.equ GPIOB_BRR, 0x40010C14 // HJI - TC bootloader entry on reset mod -.equ AFIO_MAPR, 0x40010004 // HJI - TC bootloader entry on reset mod - -Reboot_Loader: // HJI - TC bootloader entry on reset mod - // RCC Enable GPIOB+AFIO // HJI - TC bootloader entry on reset mod - ldr r6, =RCC_APB2ENR // HJI - TC bootloader entry on reset mod - ldr r0, =GPIO_AFIO_MASK // HJI - TC bootloader entry on reset mod - str R0, [r6]; // HJI - TC bootloader entry on reset mod - - // MAPR pt1 // HJI - TC bootloader entry on reset mod - ldr r0, =AFIO_MAPR // HJI - TC bootloader entry on reset mod - ldr r1, [r0] // HJI - TC bootloader entry on reset mod - bic r1, r1, #0x0F000000 // HJI - TC bootloader entry on reset mod - str r1, [r0] // HJI - TC bootloader entry on reset mod - - // MAPR pt2 // HJI - TC bootloader entry on reset mod - lsls r1, r0, #9 // HJI - TC bootloader entry on reset mod - str r1, [r0] // HJI - TC bootloader entry on reset mod - - // BRR // HJI - TC bootloader entry on reset mod - ldr r4, =GPIOB_BRR // HJI - TC bootloader entry on reset mod - movs r0, #0x18 // HJI - TC bootloader entry on reset mod - str r0, [r4] // HJI - TC bootloader entry on reset mod - - // CRL // HJI - TC bootloader entry on reset mod - ldr r1, =GPIOB_CRL // HJI - TC bootloader entry on reset mod - ldr r0, =0x44433444 // HJI - TC bootloader entry on reset mod - str r0, [r1] // HJI - TC bootloader entry on reset mod - - // Reboot to ROM // HJI - TC bootloader entry on reset mod - ldr r0, =0x1FFFF000 // HJI - TC bootloader entry on reset mod - ldr sp,[r0, #0] // HJI - TC bootloader entry on reset mod - ldr r0,[r0, #4] // HJI - TC bootloader entry on reset mod - bx r0 // HJI - TC bootloader entry on reset mod - -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * - * @param None - * @retval : None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_IRQHandler - .word RTC_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_IRQHandler - .word TIM1_UP_IRQHandler - .word TIM1_TRG_COM_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTCAlarm_IRQHandler - .word USBWakeUp_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x108. This is for boot in RAM mode for - STM32F10x Medium Density devices. */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_IRQHandler - .thumb_set TIM1_BRK_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTCAlarm_IRQHandler - .thumb_set RTCAlarm_IRQHandler,Default_Handler - - .weak USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ - diff --git a/src/main/startup/startup_stm32f30x_md_gcc.S b/src/main/startup/startup_stm32f30x_md_gcc.S deleted file mode 100644 index e1387cbc0e..0000000000 --- a/src/main/startup/startup_stm32f30x_md_gcc.S +++ /dev/null @@ -1,483 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f30x.s - * @author MCD Application Team - * @version V1.0.0 - * @date 04-Spetember-2012 - * @brief STM32F30x Devices vector table for RIDE7 toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Configure the clock system and the external SRAM mounted on - * STM3230C-EVAL board to be used as data memory (optional, - * to be enabled by user) - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2012 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2 - * - * 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. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m4 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr r0, =0x20009FFC // HJI 11/9/2012 - ldr r1, =0xDEADBEEF // HJI 11/9/2012 - ldr r2, [r0, #0] // HJI 11/9/2012 - str r0, [r0, #0] // HJI 11/9/2012 - cmp r2, r1 // HJI 11/9/2012 - beq Reboot_Loader // HJI 11/9/2012 - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call the application's entry point.*/ - bl main - bx lr - -LoopForever: - b LoopForever - -Reboot_Loader: // HJI 11/9/2012 - - // Reboot to ROM // HJI 11/9/2012 - ldr r0, =0x1FFFD800 // HJI 4/26/2013 - ldr sp,[r0, #0] // HJI 11/9/2012 - ldr r0,[r0, #4] // HJI 11/9/2012 - bx r0 // HJI 11/9/2012 - -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M4. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_STAMP_IRQHandler - .word RTC_WKUP_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_TS_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_TIM15_IRQHandler - .word TIM1_UP_TIM16_IRQHandler - .word TIM1_TRG_COM_TIM17_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTC_Alarm_IRQHandler - .word USBWakeUp_IRQHandler - .word TIM8_BRK_IRQHandler - .word TIM8_UP_IRQHandler - .word TIM8_TRG_COM_IRQHandler - .word TIM8_CC_IRQHandler - .word ADC3_IRQHandler - .word 0 - .word 0 - .word 0 - .word SPI3_IRQHandler - .word UART4_IRQHandler - .word UART5_IRQHandler - .word TIM6_DAC_IRQHandler - .word TIM7_IRQHandler - .word DMA2_Channel1_IRQHandler - .word DMA2_Channel2_IRQHandler - .word DMA2_Channel3_IRQHandler - .word DMA2_Channel4_IRQHandler - .word DMA2_Channel5_IRQHandler - .word ADC4_IRQHandler - .word 0 - .word 0 - .word COMP1_2_3_IRQHandler - .word COMP4_5_6_IRQHandler - .word COMP7_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word USB_HP_IRQHandler - .word USB_LP_IRQHandler - .word USBWakeUp_RMP_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word FPU_IRQHandler - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_STAMP_IRQHandler - .thumb_set TAMPER_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_TS_IRQHandler - .thumb_set EXTI2_TS_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM15_IRQHandler - .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM16_IRQHandler - .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM17_IRQHandler - .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - - .weak TIM8_BRK_IRQHandler - .thumb_set TIM8_BRK_IRQHandler,Default_Handler - - .weak TIM8_UP_IRQHandler - .thumb_set TIM8_UP_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_IRQHandler - .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak ADC3_IRQHandler - .thumb_set ADC3_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Channel1_IRQHandler - .thumb_set DMA2_Channel1_IRQHandler,Default_Handler - - .weak DMA2_Channel2_IRQHandler - .thumb_set DMA2_Channel2_IRQHandler,Default_Handler - - .weak DMA2_Channel3_IRQHandler - .thumb_set DMA2_Channel3_IRQHandler,Default_Handler - - .weak DMA2_Channel4_IRQHandler - .thumb_set DMA2_Channel4_IRQHandler,Default_Handler - - .weak DMA2_Channel5_IRQHandler - .thumb_set DMA2_Channel5_IRQHandler,Default_Handler - - .weak ADC4_IRQHandler - .thumb_set ADC4_IRQHandler,Default_Handler - - .weak COMP1_2_3_IRQHandler - .thumb_set COMP1_2_3_IRQHandler,Default_Handler - - .weak COMP4_5_6_IRQHandler - .thumb_set COMP4_5_6_IRQHandler,Default_Handler - - .weak COMP7_IRQHandler - .thumb_set COMP7_IRQHandler,Default_Handler - - .weak USB_HP_IRQHandler - .thumb_set USB_HP_IRQHandler,Default_Handler - - .weak USB_LP_IRQHandler - .thumb_set USB_LP_IRQHandler,Default_Handler - - .weak USBWakeUp_RMP_IRQHandler - .thumb_set USBWakeUp_RMP_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/startup/startup_stm32f3_debug_hardfault_handler.S b/src/main/startup/startup_stm32f3_debug_hardfault_handler.S deleted file mode 100644 index 65ee39a670..0000000000 --- a/src/main/startup/startup_stm32f3_debug_hardfault_handler.S +++ /dev/null @@ -1,501 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f30x.s - * @author MCD Application Team - * @version V1.0.0 - * @date 04-Spetember-2012 - * @brief STM32F30x Devices vector table for RIDE7 toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Configure the clock system and the external SRAM mounted on - * STM3230C-EVAL board to be used as data memory (optional, - * to be enabled by user) - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2012 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2 - * - * 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. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m4 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -.global HardFault_Handler -.extern hard_fault_handler_c - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr r0, =0x20009FFC // HJI 11/9/2012 - ldr r1, =0xDEADBEEF // HJI 11/9/2012 - ldr r2, [r0, #0] // HJI 11/9/2012 - str r0, [r0, #0] // HJI 11/9/2012 - cmp r2, r1 // HJI 11/9/2012 - beq Reboot_Loader // HJI 11/9/2012 - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call the application's entry point.*/ - bl main - bx lr - -LoopForever: - b LoopForever - -Reboot_Loader: // HJI 11/9/2012 - - // Reboot to ROM // HJI 11/9/2012 - ldr r0, =0x1FFFD800 // HJI 4/26/2013 - ldr sp,[r0, #0] // HJI 11/9/2012 - ldr r0,[r0, #4] // HJI 11/9/2012 - bx r0 // HJI 11/9/2012 - -.size Reset_Handler, .-Reset_Handler - -.section .text.Reset_Handler -.weak HardFault_Handler -.type HardFault_Handler, %function -HardFault_Handler: - movs r0,#4 - movs r1, lr - tst r0, r1 - beq _MSP - mrs r0, psp - b _HALT -_MSP: - mrs r0, msp -_HALT: - ldr r1,[r0,#20] - b hard_fault_handler_c - bkpt #0 - -.size HardFault_Handler, .-HardFault_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M4. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_STAMP_IRQHandler - .word RTC_WKUP_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_TS_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_TIM15_IRQHandler - .word TIM1_UP_TIM16_IRQHandler - .word TIM1_TRG_COM_TIM17_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTC_Alarm_IRQHandler - .word USBWakeUp_IRQHandler - .word TIM8_BRK_IRQHandler - .word TIM8_UP_IRQHandler - .word TIM8_TRG_COM_IRQHandler - .word TIM8_CC_IRQHandler - .word ADC3_IRQHandler - .word 0 - .word 0 - .word 0 - .word SPI3_IRQHandler - .word UART4_IRQHandler - .word UART5_IRQHandler - .word TIM6_DAC_IRQHandler - .word TIM7_IRQHandler - .word DMA2_Channel1_IRQHandler - .word DMA2_Channel2_IRQHandler - .word DMA2_Channel3_IRQHandler - .word DMA2_Channel4_IRQHandler - .word DMA2_Channel5_IRQHandler - .word ADC4_IRQHandler - .word 0 - .word 0 - .word COMP1_2_3_IRQHandler - .word COMP4_5_6_IRQHandler - .word COMP7_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word USB_HP_IRQHandler - .word USB_LP_IRQHandler - .word USBWakeUp_RMP_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word FPU_IRQHandler - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_STAMP_IRQHandler - .thumb_set TAMPER_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_TS_IRQHandler - .thumb_set EXTI2_TS_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM15_IRQHandler - .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM16_IRQHandler - .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM17_IRQHandler - .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - - .weak TIM8_BRK_IRQHandler - .thumb_set TIM8_BRK_IRQHandler,Default_Handler - - .weak TIM8_UP_IRQHandler - .thumb_set TIM8_UP_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_IRQHandler - .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak ADC3_IRQHandler - .thumb_set ADC3_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Channel1_IRQHandler - .thumb_set DMA2_Channel1_IRQHandler,Default_Handler - - .weak DMA2_Channel2_IRQHandler - .thumb_set DMA2_Channel2_IRQHandler,Default_Handler - - .weak DMA2_Channel3_IRQHandler - .thumb_set DMA2_Channel3_IRQHandler,Default_Handler - - .weak DMA2_Channel4_IRQHandler - .thumb_set DMA2_Channel4_IRQHandler,Default_Handler - - .weak DMA2_Channel5_IRQHandler - .thumb_set DMA2_Channel5_IRQHandler,Default_Handler - - .weak ADC4_IRQHandler - .thumb_set ADC4_IRQHandler,Default_Handler - - .weak COMP1_2_3_IRQHandler - .thumb_set COMP1_2_3_IRQHandler,Default_Handler - - .weak COMP4_5_6_IRQHandler - .thumb_set COMP4_5_6_IRQHandler,Default_Handler - - .weak COMP7_IRQHandler - .thumb_set COMP7_IRQHandler,Default_Handler - - .weak USB_HP_IRQHandler - .thumb_set USB_HP_IRQHandler,Default_Handler - - .weak USB_LP_IRQHandler - .thumb_set USB_LP_IRQHandler,Default_Handler - - .weak USBWakeUp_RMP_IRQHandler - .thumb_set USBWakeUp_RMP_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/vcp/hw_config.h b/src/main/vcp/hw_config.h index 1692bec113..0008206399 100644 --- a/src/main/vcp/hw_config.h +++ b/src/main/vcp/hw_config.h @@ -32,9 +32,6 @@ /* Includes ------------------------------------------------------------------*/ //#include "platform_config.h" #include "usb_type.h" -#ifdef STM32F303 -#include "stm32f30x.h" -#endif /* Exported types ------------------------------------------------------------*/ /* Exported constants --------------------------------------------------------*/