add common files
parent
4ddf21bcdc
commit
4592359e98
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,87 @@
|
||||
/**************************************************************************//**
|
||||
* @file core_cmFunc.h
|
||||
* @brief CMSIS Cortex-M Core Function Access Header File
|
||||
* @version V4.30
|
||||
* @date 20. October 2015
|
||||
******************************************************************************/
|
||||
/* Copyright (c) 2009 - 2015 ARM LIMITED
|
||||
|
||||
All rights reserved.
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
- Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
- Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
- Neither the name of ARM nor the names of its contributors may be used
|
||||
to endorse or promote products derived from this software without
|
||||
specific prior written permission.
|
||||
*
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
|
||||
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
POSSIBILITY OF SUCH DAMAGE.
|
||||
---------------------------------------------------------------------------*/
|
||||
|
||||
|
||||
#if defined ( __ICCARM__ )
|
||||
#pragma system_include /* treat file as system include file for MISRA check */
|
||||
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
|
||||
#pragma clang system_header /* treat file as system include file */
|
||||
#endif
|
||||
|
||||
#ifndef __CORE_CMFUNC_H
|
||||
#define __CORE_CMFUNC_H
|
||||
|
||||
|
||||
/* ########################### Core Function Access ########################### */
|
||||
/** \ingroup CMSIS_Core_FunctionInterface
|
||||
\defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
|
||||
@{
|
||||
*/
|
||||
|
||||
/*------------------ RealView Compiler -----------------*/
|
||||
#if defined ( __CC_ARM )
|
||||
#include "cmsis_armcc.h"
|
||||
|
||||
/*------------------ ARM Compiler V6 -------------------*/
|
||||
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
|
||||
#include "cmsis_armcc_V6.h"
|
||||
|
||||
/*------------------ GNU Compiler ----------------------*/
|
||||
#elif defined ( __GNUC__ )
|
||||
#include "cmsis_gcc.h"
|
||||
|
||||
/*------------------ ICC Compiler ----------------------*/
|
||||
#elif defined ( __ICCARM__ )
|
||||
#include <cmsis_iar.h>
|
||||
|
||||
/*------------------ TI CCS Compiler -------------------*/
|
||||
#elif defined ( __TMS470__ )
|
||||
#include <cmsis_ccs.h>
|
||||
|
||||
/*------------------ TASKING Compiler ------------------*/
|
||||
#elif defined ( __TASKING__ )
|
||||
/*
|
||||
* The CMSIS functions have been implemented as intrinsics in the compiler.
|
||||
* Please use "carm -?i" to get an up to date list of all intrinsics,
|
||||
* Including the CMSIS ones.
|
||||
*/
|
||||
|
||||
/*------------------ COSMIC Compiler -------------------*/
|
||||
#elif defined ( __CSMC__ )
|
||||
#include <cmsis_csm.h>
|
||||
|
||||
#endif
|
||||
|
||||
/*@} end of CMSIS_Core_RegAccFunctions */
|
||||
|
||||
#endif /* __CORE_CMFUNC_H */
|
@ -0,0 +1,92 @@
|
||||
/**************************************************************************//**
|
||||
* @file core_cmInstr.h
|
||||
* @brief CMSIS Cortex-M Core Instruction Access Header File
|
||||
* @version V4.30
|
||||
* @date 20. October 2015
|
||||
******************************************************************************/
|
||||
/* Copyright (c) 2009 - 2015 ARM LIMITED
|
||||
|
||||
All rights reserved.
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
- Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
- Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
- Neither the name of ARM nor the names of its contributors may be used
|
||||
to endorse or promote products derived from this software without
|
||||
specific prior written permission.
|
||||
*
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
|
||||
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
POSSIBILITY OF SUCH DAMAGE.
|
||||
---------------------------------------------------------------------------*/
|
||||
|
||||
|
||||
#if defined ( __ICCARM__ )
|
||||
#pragma system_include /* treat file as system include file for MISRA check */
|
||||
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
|
||||
#pragma clang system_header /* treat file as system include file */
|
||||
#endif
|
||||
|
||||
#ifndef __CORE_CMINSTR_H
|
||||
#define __CORE_CMINSTR_H
|
||||
|
||||
|
||||
/* ########################## Core Instruction Access ######################### */
|
||||
/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
|
||||
Access to dedicated instructions
|
||||
@{
|
||||
*/
|
||||
|
||||
/* CHIBIOS FIX */
|
||||
#if !defined(__CORTEX_SC)
|
||||
#define __CORTEX_SC 0
|
||||
#endif
|
||||
|
||||
/*------------------ RealView Compiler -----------------*/
|
||||
#if defined ( __CC_ARM )
|
||||
#include "cmsis_armcc.h"
|
||||
|
||||
/*------------------ ARM Compiler V6 -------------------*/
|
||||
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
|
||||
#include "cmsis_armcc_V6.h"
|
||||
|
||||
/*------------------ GNU Compiler ----------------------*/
|
||||
#elif defined ( __GNUC__ )
|
||||
#include "cmsis_gcc.h"
|
||||
|
||||
/*------------------ ICC Compiler ----------------------*/
|
||||
#elif defined ( __ICCARM__ )
|
||||
#include <cmsis_iar.h>
|
||||
|
||||
/*------------------ TI CCS Compiler -------------------*/
|
||||
#elif defined ( __TMS470__ )
|
||||
#include <cmsis_ccs.h>
|
||||
|
||||
/*------------------ TASKING Compiler ------------------*/
|
||||
#elif defined ( __TASKING__ )
|
||||
/*
|
||||
* The CMSIS functions have been implemented as intrinsics in the compiler.
|
||||
* Please use "carm -?i" to get an up to date list of all intrinsics,
|
||||
* Including the CMSIS ones.
|
||||
*/
|
||||
|
||||
/*------------------ COSMIC Compiler -------------------*/
|
||||
#elif defined ( __CSMC__ )
|
||||
#include <cmsis_csm.h>
|
||||
|
||||
#endif
|
||||
|
||||
/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
|
||||
|
||||
#endif /* __CORE_CMINSTR_H */
|
@ -0,0 +1,96 @@
|
||||
/**************************************************************************//**
|
||||
* @file core_cmSimd.h
|
||||
* @brief CMSIS Cortex-M SIMD Header File
|
||||
* @version V4.30
|
||||
* @date 20. October 2015
|
||||
******************************************************************************/
|
||||
/* Copyright (c) 2009 - 2015 ARM LIMITED
|
||||
|
||||
All rights reserved.
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
- Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
- Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
- Neither the name of ARM nor the names of its contributors may be used
|
||||
to endorse or promote products derived from this software without
|
||||
specific prior written permission.
|
||||
*
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
|
||||
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
POSSIBILITY OF SUCH DAMAGE.
|
||||
---------------------------------------------------------------------------*/
|
||||
|
||||
|
||||
#if defined ( __ICCARM__ )
|
||||
#pragma system_include /* treat file as system include file for MISRA check */
|
||||
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
|
||||
#pragma clang system_header /* treat file as system include file */
|
||||
#endif
|
||||
|
||||
#ifndef __CORE_CMSIMD_H
|
||||
#define __CORE_CMSIMD_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
|
||||
/* ################### Compiler specific Intrinsics ########################### */
|
||||
/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics
|
||||
Access to dedicated SIMD instructions
|
||||
@{
|
||||
*/
|
||||
|
||||
/*------------------ RealView Compiler -----------------*/
|
||||
#if defined ( __CC_ARM )
|
||||
#include "cmsis_armcc.h"
|
||||
|
||||
/*------------------ ARM Compiler V6 -------------------*/
|
||||
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
|
||||
#include "cmsis_armcc_V6.h"
|
||||
|
||||
/*------------------ GNU Compiler ----------------------*/
|
||||
#elif defined ( __GNUC__ )
|
||||
#include "cmsis_gcc.h"
|
||||
|
||||
/*------------------ ICC Compiler ----------------------*/
|
||||
#elif defined ( __ICCARM__ )
|
||||
#include <cmsis_iar.h>
|
||||
|
||||
/*------------------ TI CCS Compiler -------------------*/
|
||||
#elif defined ( __TMS470__ )
|
||||
#include <cmsis_ccs.h>
|
||||
|
||||
/*------------------ TASKING Compiler ------------------*/
|
||||
#elif defined ( __TASKING__ )
|
||||
/*
|
||||
* The CMSIS functions have been implemented as intrinsics in the compiler.
|
||||
* Please use "carm -?i" to get an up to date list of all intrinsics,
|
||||
* Including the CMSIS ones.
|
||||
*/
|
||||
|
||||
/*------------------ COSMIC Compiler -------------------*/
|
||||
#elif defined ( __CSMC__ )
|
||||
#include <cmsis_csm.h>
|
||||
|
||||
#endif
|
||||
|
||||
/*@} end of group CMSIS_SIMD_intrinsics */
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __CORE_CMSIMD_H */
|
@ -0,0 +1,97 @@
|
||||
/**
|
||||
* @file linker.ld
|
||||
*
|
||||
* Copyright (C) 2018 Clyne Sullivan
|
||||
*
|
||||
* 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 <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
/* enter at the reset handler */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* description of memory regions */
|
||||
MEMORY {
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
|
||||
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 96K
|
||||
}
|
||||
|
||||
/* description of ELF sections */
|
||||
SECTIONS {
|
||||
/* keep startup code at beginning */
|
||||
.isr_vector : {
|
||||
. = ALIGN(8);
|
||||
KEEP(*(.isr_vector))
|
||||
. = ALIGN(8);
|
||||
} > FLASH
|
||||
|
||||
/* other code sections */
|
||||
.text : {
|
||||
. = ALIGN(8);
|
||||
*(.text)
|
||||
*(.text*)
|
||||
|
||||
KEEP(*(.init))
|
||||
KEEP(*(.fini))
|
||||
. = ALIGN(8);
|
||||
} > FLASH
|
||||
|
||||
/* read-only data sections */
|
||||
.rodata : {
|
||||
. = ALIGN(8);
|
||||
*(.rodata)
|
||||
*(.rodata*)
|
||||
|
||||
*(.eh_frame)
|
||||
. = ALIGN(8);
|
||||
} > FLASH
|
||||
|
||||
/* ARM stuff */
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx)
|
||||
} > FLASH
|
||||
|
||||
/* init_array/fini_array (TODO understand this) */
|
||||
.init_array : {
|
||||
__init_array_start = .;
|
||||
KEEP(*(.init_array.*))
|
||||
KEEP(*(.init_array*))
|
||||
__init_array_end = .;
|
||||
} > FLASH
|
||||
|
||||
.fini_array : {
|
||||
__fini_array_start = .;
|
||||
KEEP(*(.fini_array.*))
|
||||
KEEP(*(.fini_array*))
|
||||
__fini_array_end = .;
|
||||
} > FLASH
|
||||
|
||||
/* initialized data */
|
||||
_sidata = LOADADDR(.data);
|
||||
.data : {
|
||||
. = ALIGN(8);
|
||||
_sdata = .;
|
||||
*(.data)
|
||||
. = ALIGN(8);
|
||||
_edata = .;
|
||||
} > RAM AT > FLASH
|
||||
|
||||
/* uninitialized data */
|
||||
.bss : {
|
||||
. = ALIGN(8);
|
||||
__bss_start__ = .;
|
||||
*(.bss)
|
||||
. = ALIGN(8);
|
||||
__bss_end__ = .;
|
||||
} > RAM
|
||||
}
|
@ -0,0 +1,37 @@
|
||||
CC := arm-none-eabi-gcc
|
||||
AS := arm-none-eabi-as
|
||||
|
||||
OUTFILE := main.out
|
||||
|
||||
MCUFLAGS := -mthumb -mcpu=cortex-m4 #-mfloat-abi=hard -mfpu=fpv4-sp-d16
|
||||
AFLAGS = $(MCUFLAGS)
|
||||
CFLAGS += $(MCUFLAGS) -ggdb -g3 -O0 \
|
||||
-I$(COMMON_DIR) -I$(COMMON_DIR)/cmsis \
|
||||
-fno-builtin -fsigned-char -ffreestanding \
|
||||
-Wall -Werror -Wextra -pedantic
|
||||
LDFLAGS := -T $(COMMON_DIR)/link.ld -nostartfiles
|
||||
|
||||
CFILES += $(wildcard $(COMMON_DIR)/*.c) \
|
||||
$(wildcard $(COMMON_DIR)/*.s)
|
||||
|
||||
OFILES := $(patsubst %.c, %.o, $(patsubst %.s, %.o, $(CFILES)))
|
||||
|
||||
.PHONY: all clean
|
||||
|
||||
all: $(OUTFILE)
|
||||
|
||||
clean:
|
||||
@echo " CLEAN"
|
||||
rm -f $(OUTFILE) $(OFILES)
|
||||
|
||||
$(OUTFILE): $(OFILES)
|
||||
@$(CC) $(CFLAGS) $(LDFLAGS) $(OFILES) -o $@
|
||||
|
||||
%.o: %.c
|
||||
@echo " CC " $<
|
||||
@$(CC) $(CFLAGS) -c $< -o $@
|
||||
|
||||
%.o: %.s
|
||||
@echo " AS " $<
|
||||
@$(AS) $(AFLAGS) -c $< -o $@
|
||||
|
@ -0,0 +1,490 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file startup_stm32l476xx.s
|
||||
* @author MCD Application Team
|
||||
* @brief STM32L476xx devices vector table GCC 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-M4 processor is in Thread mode,
|
||||
* priority is Privileged, and the Stack is set to Main.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of STMicroelectronics nor the names of its contributors
|
||||
* may be used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
.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
|
||||
|
||||
.equ _estack, 0x20018000
|
||||
|
||||
.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 sp, =_estack /* Atollic update: set stack pointer */
|
||||
|
||||
/* Call the application's entry point.*/
|
||||
bl main
|
||||
|
||||
LoopForever:
|
||||
b LoopForever
|
||||
|
||||
.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_PVM_IRQHandler
|
||||
.word TAMP_STAMP_IRQHandler
|
||||
.word RTC_WKUP_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 CAN1_TX_IRQHandler
|
||||
.word 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 DFSDM1_FLT3_IRQHandler
|
||||
.word TIM8_BRK_IRQHandler
|
||||
.word TIM8_UP_IRQHandler
|
||||
.word TIM8_TRG_COM_IRQHandler
|
||||
.word TIM8_CC_IRQHandler
|
||||
.word ADC3_IRQHandler
|
||||
.word FMC_IRQHandler
|
||||
.word SDMMC1_IRQHandler
|
||||
.word TIM5_IRQHandler
|
||||
.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 DFSDM1_FLT0_IRQHandler
|
||||
.word DFSDM1_FLT1_IRQHandler
|
||||
.word DFSDM1_FLT2_IRQHandler
|
||||
.word COMP_IRQHandler
|
||||
.word LPTIM1_IRQHandler
|
||||
.word LPTIM2_IRQHandler
|
||||
.word OTG_FS_IRQHandler
|
||||
.word DMA2_Channel6_IRQHandler
|
||||
.word DMA2_Channel7_IRQHandler
|
||||
.word LPUART1_IRQHandler
|
||||
.word QUADSPI_IRQHandler
|
||||
.word I2C3_EV_IRQHandler
|
||||
.word I2C3_ER_IRQHandler
|
||||
.word SAI1_IRQHandler
|
||||
.word SAI2_IRQHandler
|
||||
.word SWPMI1_IRQHandler
|
||||
.word TSC_IRQHandler
|
||||
.word LCD_IRQHandler
|
||||
.word 0
|
||||
.word RNG_IRQHandler
|
||||
.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_PVM_IRQHandler
|
||||
.thumb_set PVD_PVM_IRQHandler,Default_Handler
|
||||
|
||||
.weak TAMP_STAMP_IRQHandler
|
||||
.thumb_set TAMP_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_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 CAN1_TX_IRQHandler
|
||||
.thumb_set CAN1_TX_IRQHandler,Default_Handler
|
||||
|
||||
.weak CAN1_RX0_IRQHandler
|
||||
.thumb_set 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 DFSDM1_FLT3_IRQHandler
|
||||
.thumb_set DFSDM1_FLT3_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 FMC_IRQHandler
|
||||
.thumb_set FMC_IRQHandler,Default_Handler
|
||||
|
||||
.weak SDMMC1_IRQHandler
|
||||
.thumb_set SDMMC1_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_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 DFSDM1_FLT0_IRQHandler
|
||||
.thumb_set DFSDM1_FLT0_IRQHandler,Default_Handler
|
||||
|
||||
.weak DFSDM1_FLT1_IRQHandler
|
||||
.thumb_set DFSDM1_FLT1_IRQHandler,Default_Handler
|
||||
|
||||
.weak DFSDM1_FLT2_IRQHandler
|
||||
.thumb_set DFSDM1_FLT2_IRQHandler,Default_Handler
|
||||
|
||||
.weak COMP_IRQHandler
|
||||
.thumb_set COMP_IRQHandler,Default_Handler
|
||||
|
||||
.weak LPTIM1_IRQHandler
|
||||
.thumb_set LPTIM1_IRQHandler,Default_Handler
|
||||
|
||||
.weak LPTIM2_IRQHandler
|
||||
.thumb_set LPTIM2_IRQHandler,Default_Handler
|
||||
|
||||
.weak OTG_FS_IRQHandler
|
||||
.thumb_set OTG_FS_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel6_IRQHandler
|
||||
.thumb_set DMA2_Channel6_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel7_IRQHandler
|
||||
.thumb_set DMA2_Channel7_IRQHandler,Default_Handler
|
||||
|
||||
.weak LPUART1_IRQHandler
|
||||
.thumb_set LPUART1_IRQHandler,Default_Handler
|
||||
|
||||
.weak QUADSPI_IRQHandler
|
||||
.thumb_set QUADSPI_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C3_EV_IRQHandler
|
||||
.thumb_set I2C3_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C3_ER_IRQHandler
|
||||
.thumb_set I2C3_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak SAI1_IRQHandler
|
||||
.thumb_set SAI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak SAI2_IRQHandler
|
||||
.thumb_set SAI2_IRQHandler,Default_Handler
|
||||
|
||||
.weak SWPMI1_IRQHandler
|
||||
.thumb_set SWPMI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak TSC_IRQHandler
|
||||
.thumb_set TSC_IRQHandler,Default_Handler
|
||||
|
||||
.weak LCD_IRQHandler
|
||||
.thumb_set LCD_IRQHandler,Default_Handler
|
||||
|
||||
.weak RNG_IRQHandler
|
||||
.thumb_set RNG_IRQHandler,Default_Handler
|
||||
|
||||
.weak FPU_IRQHandler
|
||||
.thumb_set FPU_IRQHandler,Default_Handler
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,38 @@
|
||||
#include <stm32l476xx.h>
|
||||
|
||||
__attribute__ ((naked))
|
||||
void NMI_Handler(void)
|
||||
{
|
||||
while (1);
|
||||
}
|
||||
|
||||
__attribute__ ((naked))
|
||||
void HardFault_Handler(void)
|
||||
{
|
||||
while (1);
|
||||
}
|
||||
|
||||
__attribute__ ((naked))
|
||||
void MemManage_Handler(void)
|
||||
{
|
||||
while (1);
|
||||
}
|
||||
|
||||
__attribute__ ((naked))
|
||||
void BusFault_Handler(void)
|
||||
{
|
||||
while (1);
|
||||
}
|
||||
|
||||
__attribute__ ((naked))
|
||||
void UsageFault_Handler(void)
|
||||
{
|
||||
while (1);
|
||||
}
|
||||
|
||||
__attribute__ ((naked))
|
||||
void DebugMon_Handler(void)
|
||||
{
|
||||
while (1);
|
||||
}
|
||||
|
Loading…
Reference in New Issue