git-svn-id: svn://svn.code.sf.net/p/chibios/svn/branches/kernel_3_dev@6096 35acf78f-673a-0410-8e92-d51de3d6d3f4
This commit is contained in:
parent
f9cfe6b9bb
commit
e0e31ea715
|
@ -69,8 +69,8 @@ include $(CHIBIOS)/boards/ST_STM32F3_DISCOVERY/board.mk
|
|||
include $(CHIBIOS)/os/halnew/hal.mk
|
||||
include $(CHIBIOS)/os/halnew/osal/chibios/osal.mk
|
||||
include $(CHIBIOS)/os/halnew/platforms/STM32F30x/platform.mk
|
||||
include $(CHIBIOS)/os/ports/GCC/ARMCMx/STM32F3xx/port.mk
|
||||
include $(CHIBIOS)/os/kernel/kernel.mk
|
||||
include $(CHIBIOS)/os/kernel/ports/ARMCMx/devices/STM32F30x/port.mk
|
||||
include $(CHIBIOS)/test/test.mk
|
||||
|
||||
# Define linker script file here
|
||||
|
@ -209,8 +209,10 @@ ULIBS =
|
|||
ifeq ($(USE_FPU),yes)
|
||||
USE_OPT += -mfloat-abi=softfp -mfpu=fpv4-sp-d16 -fsingle-precision-constant
|
||||
DDEFS += -DCORTEX_USE_FPU=TRUE
|
||||
DADEFS += -DCORTEX_USE_FPU=TRUE
|
||||
else
|
||||
DDEFS += -DCORTEX_USE_FPU=FALSE
|
||||
DADEFS += -DCORTEX_USE_FPU=FALSE
|
||||
endif
|
||||
|
||||
ifeq ($(USE_FWLIB),yes)
|
||||
|
@ -220,4 +222,4 @@ ifeq ($(USE_FWLIB),yes)
|
|||
USE_OPT += -DUSE_STDPERIPH_DRIVER
|
||||
endif
|
||||
|
||||
include $(CHIBIOS)/os/ports/GCC/ARMCMx/rules.mk
|
||||
include $(CHIBIOS)/os/kernel/ports/ARMCMx/compilers/GCC/rules.mk
|
||||
|
|
|
@ -57,7 +57,7 @@
|
|||
*
|
||||
* @isr
|
||||
*/
|
||||
OSAL_IRQ_HANDLER(SysTickVector) {
|
||||
OSAL_IRQ_HANDLER(SysTick_Handler) {
|
||||
|
||||
OSAL_IRQ_PROLOGUE();
|
||||
|
||||
|
|
|
@ -613,6 +613,9 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FPSCR(uint32_t fps
|
|||
__ASM volatile ("");
|
||||
__ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc");
|
||||
__ASM volatile ("");
|
||||
#else
|
||||
/* CHIBIOS FIX */
|
||||
(void)fpscr;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -70,6 +70,8 @@
|
|||
/* Derived constants and error checks. */
|
||||
/*===========================================================================*/
|
||||
|
||||
/* The following code is not processed when the file is included from an
|
||||
asm module.*/
|
||||
#if !defined(_FROM_ASM_)
|
||||
|
||||
/*
|
||||
|
@ -93,6 +95,8 @@
|
|||
/* Module data structures and types. */
|
||||
/*===========================================================================*/
|
||||
|
||||
/* The following code is not processed when the file is included from an
|
||||
asm module.*/
|
||||
#if !defined(_FROM_ASM_)
|
||||
|
||||
/* The following declarations are there just for Doxygen documentation, the
|
||||
|
|
|
@ -0,0 +1,174 @@
|
|||
/*
|
||||
ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
|
||||
2011,2012,2013 Giovanni Di Sirio.
|
||||
|
||||
This file is part of ChibiOS/RT.
|
||||
|
||||
ChibiOS/RT 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.
|
||||
|
||||
ChibiOS/RT 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file ARMCMx/chcore_v7m.c
|
||||
* @brief ARMv7-M architecture port code.
|
||||
*
|
||||
* @addtogroup ARMCMx_V7M_CORE
|
||||
* @{
|
||||
*/
|
||||
|
||||
#include "ch.h"
|
||||
|
||||
/*===========================================================================*/
|
||||
/* Module local definitions. */
|
||||
/*===========================================================================*/
|
||||
|
||||
/*===========================================================================*/
|
||||
/* Module exported variables. */
|
||||
/*===========================================================================*/
|
||||
|
||||
/*===========================================================================*/
|
||||
/* Module local types. */
|
||||
/*===========================================================================*/
|
||||
|
||||
/*===========================================================================*/
|
||||
/* Module local variables. */
|
||||
/*===========================================================================*/
|
||||
|
||||
/*===========================================================================*/
|
||||
/* Module local functions. */
|
||||
/*===========================================================================*/
|
||||
|
||||
/*===========================================================================*/
|
||||
/* Module interrupt handlers. */
|
||||
/*===========================================================================*/
|
||||
|
||||
#if !CORTEX_SIMPLIFIED_PRIORITY || defined(__DOXYGEN__)
|
||||
/**
|
||||
* @brief SVC vector.
|
||||
* @details The SVC vector is used for exception mode re-entering after a
|
||||
* context switch.
|
||||
* @note The PendSV vector is only used in advanced kernel mode.
|
||||
*/
|
||||
void SVC_Handler(void) {
|
||||
|
||||
/* The extctx structure is pointed by the PSP register.*/
|
||||
struct extctx *ctxp = (struct extctx *)__get_PSP();
|
||||
|
||||
/* Discarding the current exception context and positioning the stack to
|
||||
point to the real one.*/
|
||||
ctxp++;
|
||||
|
||||
#if CORTEX_USE_FPU
|
||||
/* Restoring the special register SCB_FPCCR.*/
|
||||
SCB_FPCCR = (uint32_t)ctxp->fpccr;
|
||||
SCB_FPCAR = SCB_FPCAR + sizeof (struct extctx);
|
||||
#endif
|
||||
|
||||
/* Writing back the modified PSP value.*/
|
||||
__set_PSP((uint32_t)ctxp);
|
||||
|
||||
/* Restoring the normal interrupts status.*/
|
||||
port_unlock_from_isr();
|
||||
}
|
||||
#endif /* !CORTEX_SIMPLIFIED_PRIORITY */
|
||||
|
||||
#if CORTEX_SIMPLIFIED_PRIORITY || defined(__DOXYGEN__)
|
||||
/**
|
||||
* @brief PendSV vector.
|
||||
* @details The PendSV vector is used for exception mode re-entering after a
|
||||
* context switch.
|
||||
* @note The PendSV vector is only used in compact kernel mode.
|
||||
*/
|
||||
void PendSV_Handler(void) {
|
||||
|
||||
/* The extctx structure is pointed by the PSP register.*/
|
||||
struct extctx *ctxp = (struct extctx *)__get_PSP();
|
||||
|
||||
/* Discarding the current exception context and positioning the stack to
|
||||
point to the real one.*/
|
||||
ctxp++;
|
||||
|
||||
#if CORTEX_USE_FPU
|
||||
/* Restoring the special register SCB_FPCCR.*/
|
||||
SCB_FPCCR = (uint32_t)ctxp->fpccr;
|
||||
SCB_FPCAR = SCB_FPCAR + sizeof (struct extctx);
|
||||
#endif
|
||||
|
||||
/* Writing back the modified PSP value.*/
|
||||
__set_PSP((uint32_t)ctxp);
|
||||
}
|
||||
#endif /* CORTEX_SIMPLIFIED_PRIORITY */
|
||||
|
||||
/*===========================================================================*/
|
||||
/* Module exported functions. */
|
||||
/*===========================================================================*/
|
||||
|
||||
/**
|
||||
* @brief Exception exit redirection to _port_switch_from_isr().
|
||||
*/
|
||||
void _port_irq_epilogue(void) {
|
||||
|
||||
port_lock_from_isr();
|
||||
if ((SCB->ICSR & SCB_ICSR_RETTOBASE_Msk) != 0) {
|
||||
|
||||
/* The extctx structure is pointed by the PSP register.*/
|
||||
struct extctx *ctxp = (struct extctx *)__get_PSP();
|
||||
|
||||
/* Adding an artificial exception return context, there is no need to
|
||||
populate it fully.*/
|
||||
ctxp--;
|
||||
|
||||
/* Writing back the modified PSP value.*/
|
||||
__set_PSP((uint32_t)ctxp);
|
||||
|
||||
/* Setting up a fake XPSR register value.*/
|
||||
ctxp->xpsr = (regarm_t)0x01000000;
|
||||
|
||||
/* The exit sequence is different depending on if a preemption is
|
||||
required or not.*/
|
||||
if (chSchIsPreemptionRequired()) {
|
||||
/* Preemption is required we need to enforce a context switch.*/
|
||||
ctxp->pc = (void *)_port_switch_from_isr;
|
||||
#if CORTEX_USE_FPU
|
||||
/* Enforcing a lazy FPU state save by accessing the FPCSR register.*/
|
||||
(void) __get_FPSCR();
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
/* Preemption not required, we just need to exit the exception
|
||||
atomically.*/
|
||||
ctxp->pc = (void *)_port_exit_from_isr;
|
||||
}
|
||||
|
||||
#if CORTEX_USE_FPU
|
||||
{
|
||||
uint32_t fpccr;
|
||||
|
||||
/* Saving the special register SCB_FPCCR into the reserved offset of
|
||||
the Cortex-M4 exception frame.*/
|
||||
(ctxp + 1)->fpccr = (regarm_t)(fpccr = SCB_FPCCR);
|
||||
|
||||
/* Now the FPCCR is modified in order to not restore the FPU status
|
||||
from the artificial return context.*/
|
||||
SCB_FPCCR = fpccr | FPCCR_LSPACT;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Note, returning without unlocking is intentional, this is done in
|
||||
order to keep the rest of the context switch atomic.*/
|
||||
return;
|
||||
}
|
||||
port_unlock_from_isr();
|
||||
}
|
||||
|
||||
/** @} */
|
|
@ -216,6 +216,8 @@
|
|||
/* Module data structures and types. */
|
||||
/*===========================================================================*/
|
||||
|
||||
/* The following code is not processed when the file is included from an
|
||||
asm module.*/
|
||||
#if !defined(_FROM_ASM_)
|
||||
|
||||
/**
|
||||
|
@ -418,22 +420,22 @@ extern "C" {
|
|||
static inline void port_init(void) {
|
||||
|
||||
/* Initialization of the vector table and priority related settings.*/
|
||||
SCB_VTOR = CORTEX_VTOR_INIT;
|
||||
SCB_AIRCR = AIRCR_VECTKEY | AIRCR_PRIGROUP(CORTEX_PRIGROUP_INIT);
|
||||
SCB->VTOR = CORTEX_VTOR_INIT;
|
||||
|
||||
/* Initializing priority grouping.*/
|
||||
NVIC_SetPriorityGrouping(CORTEX_PRIGROUP_INIT);
|
||||
|
||||
/* DWT cycle counter enable.*/
|
||||
SCS_DEMCR |= SCS_DEMCR_TRCENA;
|
||||
DWT_CTRL |= DWT_CTRL_CYCCNTENA;
|
||||
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
|
||||
DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk;
|
||||
|
||||
/* Initialization of the system vectors used by the port.*/
|
||||
nvicSetSystemHandlerPriority(HANDLER_SVCALL,
|
||||
CORTEX_PRIORITY_MASK(CORTEX_PRIORITY_SVCALL));
|
||||
nvicSetSystemHandlerPriority(HANDLER_PENDSV,
|
||||
CORTEX_PRIORITY_MASK(CORTEX_PRIORITY_PENDSV));
|
||||
#if CH_CFG_TIMEDELTA == 0
|
||||
nvicSetSystemHandlerPriority(HANDLER_SYSTICK,
|
||||
CORTEX_PRIORITY_MASK(CORTEX_PRIORITY_SYSTICK));
|
||||
#else
|
||||
NVIC_SetPriority(SVCall_IRQn, CORTEX_PRIORITY_SVCALL);
|
||||
NVIC_SetPriority(PendSV_IRQn, CORTEX_PRIORITY_PENDSV);
|
||||
|
||||
#if CH_CFG_TIMEDELTA > 0
|
||||
/* TODO: Remove initialization, all the timers handling has to be performed
|
||||
outside the port layer.*/
|
||||
port_timer_init();
|
||||
#endif
|
||||
}
|
||||
|
@ -595,13 +597,13 @@ static inline void port_enable(void) {
|
|||
static inline void port_wait_for_interrupt(void) {
|
||||
|
||||
#if CORTEX_ENABLE_WFI_IDLE
|
||||
asm volatile ("wfi" : : : "memory");
|
||||
__WFI;
|
||||
#endif
|
||||
}
|
||||
|
||||
static inline rtcnt_t port_rt_get_counter_value(void) {
|
||||
|
||||
return DWT_CYCCNT;
|
||||
return DWT->CYCCNT;
|
||||
}
|
||||
|
||||
#endif /* !defined(_FROM_ASM_) */
|
||||
|
|
|
@ -26,6 +26,7 @@
|
|||
* @{
|
||||
*/
|
||||
|
||||
#define _FROM_ASM_
|
||||
#include "chconf.h"
|
||||
#include "chcore.h"
|
||||
|
||||
|
@ -39,6 +40,11 @@
|
|||
|
||||
#if !defined(__DOXYGEN__)
|
||||
|
||||
|
||||
.set CONTEXT_OFFSET, 12
|
||||
.set SCB_ICSR, 0xE000ED04
|
||||
.set ICSR_PENDSVSET, 0x10000000
|
||||
|
||||
.syntax unified
|
||||
.cpu cortex-m4
|
||||
.fpu softvfp
|
||||
|
@ -46,14 +52,31 @@
|
|||
.thumb
|
||||
.text
|
||||
|
||||
/*
|
||||
* Thread trampoline code.
|
||||
/*--------------------------------------------------------------------------*
|
||||
* Performs a context switch between two threads.
|
||||
*--------------------------------------------------------------------------*/
|
||||
.thumb_func
|
||||
.globl _port_switch
|
||||
_port_switch:
|
||||
push {r4, r5, r6, r7, r8, r9, r10, r11, lr}
|
||||
#if CORTEX_USE_FPU
|
||||
vpush {s16-s31}
|
||||
#endif
|
||||
str sp, [r1, #CONTEXT_OFFSET]
|
||||
ldr sp, [r0, #CONTEXT_OFFSET]
|
||||
#if CORTEX_USE_FPU
|
||||
vpop {s16-s31}
|
||||
#endif
|
||||
pop {r4, r5, r6, r7, r8, r9, r10, r11, pc}
|
||||
|
||||
/*--------------------------------------------------------------------------*
|
||||
* Start a thread by invoking its work function.
|
||||
*
|
||||
* Threads execution starts here, the code leaves the system critical zone
|
||||
* and then jumps into the thread function passed in register R4. The
|
||||
* register R5 contains the thread parameter. The function chThdExit() is
|
||||
* called on thread function return.
|
||||
*/
|
||||
*--------------------------------------------------------------------------*/
|
||||
.thumb_func
|
||||
.globl _port_thread_start
|
||||
_port_thread_start:
|
||||
|
@ -69,6 +92,39 @@ _port_thread_start:
|
|||
blx r4
|
||||
bl chThdExit
|
||||
|
||||
/*--------------------------------------------------------------------------*
|
||||
* Post-IRQ switch code.
|
||||
*
|
||||
* Exception handlers return here for context switching.
|
||||
*--------------------------------------------------------------------------*/
|
||||
.thumb_func
|
||||
.globl _port_switch_from_isr
|
||||
_port_switch_from_isr:
|
||||
#if CH_DBG_STATISTICS
|
||||
bl _stats_start_measure_crit_thd
|
||||
#endif
|
||||
#if CH_DBG_SYSTEM_STATE_CHECK
|
||||
bl dbg_check_lock
|
||||
#endif
|
||||
bl chSchDoReschedule
|
||||
#if CH_DBG_SYSTEM_STATE_CHECK
|
||||
bl dbg_check_unlock
|
||||
#endif
|
||||
#if CH_DBG_STATISTICS
|
||||
bl _stats_stop_measure_crit_thd
|
||||
#endif
|
||||
_port_exit_from_isr:
|
||||
#if CORTEX_SIMPLIFIED_PRIORITY
|
||||
mov r3, #SCB_ICSR :AND: 0xFFFF
|
||||
movt r3, #SCB_ICSR :SHR: 16
|
||||
mov r2, #ICSR_PENDSVSET
|
||||
str r2, [r3, #0]
|
||||
cpsie i
|
||||
#else /* !CORTEX_SIMPLIFIED_PRIORITY */
|
||||
svc #0
|
||||
#endif /* !CORTEX_SIMPLIFIED_PRIORITY */
|
||||
.L1: b .L1
|
||||
|
||||
#endif /* !defined(__DOXYGEN__) */
|
||||
|
||||
/** @} */
|
||||
|
|
|
@ -0,0 +1,354 @@
|
|||
/*
|
||||
ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
|
||||
2011,2012,2013 Giovanni Di Sirio.
|
||||
|
||||
This file is part of ChibiOS/RT.
|
||||
|
||||
ChibiOS/RT 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.
|
||||
|
||||
ChibiOS/RT 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file GCC/crt0.c
|
||||
* @brief Generic GCC ARMvx-M (Cortex-M0/M1/M3/M4) startup file.
|
||||
*
|
||||
* @addtogroup ARMCMx_GCC_STARTUP
|
||||
* @{
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#if !defined(FALSE)
|
||||
#define FALSE 0
|
||||
#endif
|
||||
|
||||
#if !defined(TRUE)
|
||||
#define TRUE (!FALSE)
|
||||
#endif
|
||||
|
||||
#define SCB_CPACR *((uint32_t *)0xE000ED88U)
|
||||
#define SCB_FPCCR *((uint32_t *)0xE000EF34U)
|
||||
#define SCB_FPDSCR *((uint32_t *)0xE000EF3CU)
|
||||
#define FPCCR_ASPEN (0x1U << 31)
|
||||
#define FPCCR_LSPEN (0x1U << 30)
|
||||
|
||||
typedef void (*funcp_t)(void);
|
||||
typedef funcp_t * funcpp_t;
|
||||
|
||||
#define SYMVAL(sym) (uint32_t)(((uint8_t *)&(sym)) - ((uint8_t *)0))
|
||||
|
||||
/*
|
||||
* Area fill code, it is a macro because here functions cannot be called
|
||||
* until stacks are initialized.
|
||||
*/
|
||||
#define fill32(start, end, filler) { \
|
||||
uint32_t *p1 = start; \
|
||||
uint32_t *p2 = end; \
|
||||
while (p1 < p2) \
|
||||
*p1++ = filler; \
|
||||
}
|
||||
|
||||
/*===========================================================================*/
|
||||
/**
|
||||
* @name Startup settings
|
||||
* @{
|
||||
*/
|
||||
/*===========================================================================*/
|
||||
|
||||
/**
|
||||
* @brief Control special register initialization value.
|
||||
* @details The system is setup to run in privileged mode using the PSP
|
||||
* stack (dual stack mode).
|
||||
*/
|
||||
#if !defined(CRT0_CONTROL_INIT) || defined(__DOXYGEN__)
|
||||
#define CRT0_CONTROL_INIT 0x00000002
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Stack segments initialization switch.
|
||||
*/
|
||||
#if !defined(CRT0_STACKS_FILL_PATTERN) || defined(__DOXYGEN__)
|
||||
#define CRT0_STACKS_FILL_PATTERN 0x55555555
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Stack segments initialization switch.
|
||||
*/
|
||||
#if !defined(CRT0_INIT_STACKS) || defined(__DOXYGEN__)
|
||||
#define CRT0_INIT_STACKS TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief DATA segment initialization switch.
|
||||
*/
|
||||
#if !defined(CRT0_INIT_DATA) || defined(__DOXYGEN__)
|
||||
#define CRT0_INIT_DATA TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief BSS segment initialization switch.
|
||||
*/
|
||||
#if !defined(CRT0_INIT_BSS) || defined(__DOXYGEN__)
|
||||
#define CRT0_INIT_BSS TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Constructors invocation switch.
|
||||
*/
|
||||
#if !defined(CRT0_CALL_CONSTRUCTORS) || defined(__DOXYGEN__)
|
||||
#define CRT0_CALL_CONSTRUCTORS TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Destructors invocation switch.
|
||||
*/
|
||||
#if !defined(CRT0_CALL_DESTRUCTORS) || defined(__DOXYGEN__)
|
||||
#define CRT0_CALL_DESTRUCTORS TRUE
|
||||
#endif
|
||||
|
||||
/** @} */
|
||||
|
||||
/*===========================================================================*/
|
||||
/**
|
||||
* @name Symbols from the scatter file
|
||||
*/
|
||||
/*===========================================================================*/
|
||||
|
||||
/**
|
||||
* @brief Main stack lower boundary.
|
||||
* @details This symbol must be exported by the linker script and represents
|
||||
* the main stack lower boundary.
|
||||
*/
|
||||
extern uint32_t __main_stack_base__;
|
||||
|
||||
/**
|
||||
*
|
||||
* @brief Main stack initial position.
|
||||
* @details This symbol must be exported by the linker script and represents
|
||||
* the main stack initial position.
|
||||
*/
|
||||
extern uint32_t __main_stack_end__;
|
||||
|
||||
/**
|
||||
* @brief Process stack lower boundary.
|
||||
* @details This symbol must be exported by the linker script and represents
|
||||
* the process stack lower boundary.
|
||||
*/
|
||||
extern uint32_t __process_stack_base__;
|
||||
|
||||
/**
|
||||
* @brief Process stack initial position.
|
||||
* @details This symbol must be exported by the linker script and represents
|
||||
* the process stack initial position.
|
||||
*/
|
||||
extern uint32_t __process_stack_end__;
|
||||
|
||||
/**
|
||||
* @brief ROM image of the data segment start.
|
||||
* @pre The symbol must be aligned to a 32 bits boundary.
|
||||
*/
|
||||
extern uint32_t _textdata;
|
||||
|
||||
/**
|
||||
* @brief Data segment start.
|
||||
* @pre The symbol must be aligned to a 32 bits boundary.
|
||||
*/
|
||||
extern uint32_t _data;
|
||||
|
||||
/**
|
||||
* @brief Data segment end.
|
||||
* @pre The symbol must be aligned to a 32 bits boundary.
|
||||
*/
|
||||
extern uint32_t _edata;
|
||||
|
||||
/**
|
||||
* @brief BSS segment start.
|
||||
* @pre The symbol must be aligned to a 32 bits boundary.
|
||||
*/
|
||||
extern uint32_t _bss_start;
|
||||
|
||||
/**
|
||||
* @brief BSS segment end.
|
||||
* @pre The symbol must be aligned to a 32 bits boundary.
|
||||
*/
|
||||
extern uint32_t _bss_end;
|
||||
|
||||
/**
|
||||
* @brief Constructors table start.
|
||||
* @pre The symbol must be aligned to a 32 bits boundary.
|
||||
*/
|
||||
extern funcp_t __init_array_start;
|
||||
|
||||
/**
|
||||
* @brief Constructors table end.
|
||||
* @pre The symbol must be aligned to a 32 bits boundary.
|
||||
*/
|
||||
extern funcp_t __init_array_end;
|
||||
|
||||
/**
|
||||
* @brief Destructors table start.
|
||||
* @pre The symbol must be aligned to a 32 bits boundary.
|
||||
*/
|
||||
extern funcp_t __fini_array_start;
|
||||
|
||||
/**
|
||||
* @brief Destructors table end.
|
||||
* @pre The symbol must be aligned to a 32 bits boundary.
|
||||
*/
|
||||
extern funcp_t __fini_array_end;
|
||||
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @brief Application @p main() function.
|
||||
*/
|
||||
extern void main(void);
|
||||
|
||||
/**
|
||||
* @brief Early initialization.
|
||||
* @details This hook is invoked immediately after the stack initialization
|
||||
* and before the DATA and BSS segments initialization. The
|
||||
* default behavior is to do nothing.
|
||||
* @note This function is a weak symbol.
|
||||
*/
|
||||
#if !defined(__DOXYGEN__)
|
||||
__attribute__((weak))
|
||||
#endif
|
||||
void __early_init(void) {}
|
||||
|
||||
/**
|
||||
* @brief Late initialization.
|
||||
* @details This hook is invoked after the DATA and BSS segments
|
||||
* initialization and before any static constructor. The
|
||||
* default behavior is to do nothing.
|
||||
* @note This function is a weak symbol.
|
||||
*/
|
||||
#if !defined(__DOXYGEN__)
|
||||
__attribute__((weak))
|
||||
#endif
|
||||
void __late_init(void) {}
|
||||
|
||||
/**
|
||||
* @brief Default @p main() function exit handler.
|
||||
* @details This handler is invoked or the @p main() function exit. The
|
||||
* default behavior is to enter an infinite loop.
|
||||
* @note This function is a weak symbol.
|
||||
*/
|
||||
#if !defined(__DOXYGEN__)
|
||||
__attribute__((weak, naked))
|
||||
#endif
|
||||
void _default_exit(void) {
|
||||
while (1)
|
||||
;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Reset vector.
|
||||
*/
|
||||
#if !defined(__DOXYGEN__)
|
||||
__attribute__((naked))
|
||||
#endif
|
||||
void ResetHandler(void) {
|
||||
uint32_t psp, reg;
|
||||
|
||||
/* Process Stack initialization, it is allocated starting from the
|
||||
symbol __process_stack_end__ and its lower limit is the symbol
|
||||
__process_stack_base__.*/
|
||||
asm volatile ("cpsid i");
|
||||
psp = SYMVAL(__process_stack_end__);
|
||||
asm volatile ("msr PSP, %0" : : "r" (psp));
|
||||
|
||||
#if CORTEX_USE_FPU
|
||||
/* Initializing the FPU context save in lazy mode.*/
|
||||
SCB_FPCCR = FPCCR_ASPEN | FPCCR_LSPEN;
|
||||
|
||||
/* CP10 and CP11 set to full access.*/
|
||||
SCB_CPACR |= 0x00F00000;
|
||||
|
||||
/* FPSCR and FPDSCR initially zero.*/
|
||||
reg = 0;
|
||||
asm volatile ("vmsr FPSCR, %0" : : "r" (reg) : "memory");
|
||||
SCB_FPDSCR = reg;
|
||||
|
||||
/* CPU mode initialization, enforced FPCA bit.*/
|
||||
reg = CRT0_CONTROL_INIT | 4;
|
||||
#else
|
||||
/* CPU mode initialization.*/
|
||||
reg = CRT0_CONTROL_INIT;
|
||||
#endif
|
||||
asm volatile ("msr CONTROL, %0" : : "r" (reg));
|
||||
asm volatile ("isb");
|
||||
|
||||
#if CRT0_INIT_STACKS
|
||||
/* Main and Process stacks initialization.*/
|
||||
fill32(&__main_stack_base__,
|
||||
&__main_stack_end__,
|
||||
CRT0_STACKS_FILL_PATTERN);
|
||||
fill32(&__process_stack_base__,
|
||||
&__process_stack_end__,
|
||||
CRT0_STACKS_FILL_PATTERN);
|
||||
#endif
|
||||
|
||||
/* Early initialization hook invocation.*/
|
||||
__early_init();
|
||||
|
||||
#if CRT0_INIT_DATA
|
||||
/* DATA segment initialization.*/
|
||||
{
|
||||
uint32_t *tp, *dp;
|
||||
|
||||
tp = &_textdata;
|
||||
dp = &_data;
|
||||
while (dp < &_edata)
|
||||
*dp++ = *tp++;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if CRT0_INIT_BSS
|
||||
/* BSS segment initialization.*/
|
||||
fill32(&_bss_start, &_bss_end, 0);
|
||||
#endif
|
||||
|
||||
/* Late initialization hook invocation.*/
|
||||
__late_init();
|
||||
|
||||
#if CRT0_CALL_CONSTRUCTORS
|
||||
/* Constructors invocation.*/
|
||||
{
|
||||
funcpp_t fpp = &__init_array_start;
|
||||
while (fpp < &__init_array_end) {
|
||||
(*fpp)();
|
||||
fpp++;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Invoking application main() function.*/
|
||||
main();
|
||||
|
||||
#if CRT0_CALL_DESTRUCTORS
|
||||
/* Destructors invocation.*/
|
||||
{
|
||||
funcpp_t fpp = &__fini_array_start;
|
||||
while (fpp < &__fini_array_end) {
|
||||
(*fpp)();
|
||||
fpp++;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Invoking the exit handler.*/
|
||||
_default_exit();
|
||||
}
|
||||
|
||||
/** @} */
|
|
@ -0,0 +1,220 @@
|
|||
# ARM Cortex-Mx common makefile scripts and rules.
|
||||
|
||||
# Output directory and files
|
||||
ifeq ($(BUILDDIR),)
|
||||
BUILDDIR = build
|
||||
endif
|
||||
ifeq ($(BUILDDIR),.)
|
||||
BUILDDIR = build
|
||||
endif
|
||||
OUTFILES = $(BUILDDIR)/$(PROJECT).elf $(BUILDDIR)/$(PROJECT).hex \
|
||||
$(BUILDDIR)/$(PROJECT).bin $(BUILDDIR)/$(PROJECT).dmp
|
||||
|
||||
# Automatic compiler options
|
||||
OPT = $(USE_OPT)
|
||||
COPT = $(USE_COPT)
|
||||
CPPOPT = $(USE_CPPOPT)
|
||||
ifeq ($(USE_LINK_GC),yes)
|
||||
OPT += -ffunction-sections -fdata-sections -fno-common
|
||||
endif
|
||||
|
||||
# Source files groups and paths
|
||||
ifeq ($(USE_THUMB),yes)
|
||||
TCSRC += $(CSRC)
|
||||
TCPPSRC += $(CPPSRC)
|
||||
else
|
||||
ACSRC += $(CSRC)
|
||||
ACPPSRC += $(CPPSRC)
|
||||
endif
|
||||
ASRC = $(ACSRC)$(ACPPSRC)
|
||||
TSRC = $(TCSRC)$(TCPPSRC)
|
||||
SRCPATHS = $(sort $(dir $(ASMXSRC)) $(dir $(ASMSRC)) $(dir $(ASRC)) $(dir $(TSRC)))
|
||||
|
||||
# Various directories
|
||||
OBJDIR = $(BUILDDIR)/obj
|
||||
LSTDIR = $(BUILDDIR)/lst
|
||||
|
||||
# Object files groups
|
||||
ACOBJS = $(addprefix $(OBJDIR)/, $(notdir $(ACSRC:.c=.o)))
|
||||
ACPPOBJS = $(addprefix $(OBJDIR)/, $(notdir $(ACPPSRC:.cpp=.o)))
|
||||
TCOBJS = $(addprefix $(OBJDIR)/, $(notdir $(TCSRC:.c=.o)))
|
||||
TCPPOBJS = $(addprefix $(OBJDIR)/, $(notdir $(TCPPSRC:.cpp=.o)))
|
||||
ASMOBJS = $(addprefix $(OBJDIR)/, $(notdir $(ASMSRC:.s=.o)))
|
||||
ASMXOBJS = $(addprefix $(OBJDIR)/, $(notdir $(ASMXSRC:.S=.o)))
|
||||
OBJS = $(ASMXOBJS) $(ASMOBJS) $(ACOBJS) $(TCOBJS) $(ACPPOBJS) $(TCPPOBJS)
|
||||
|
||||
# Paths
|
||||
IINCDIR = $(patsubst %,-I%,$(INCDIR) $(DINCDIR) $(UINCDIR))
|
||||
LLIBDIR = $(patsubst %,-L%,$(DLIBDIR) $(ULIBDIR))
|
||||
|
||||
# Macros
|
||||
DEFS = $(DDEFS) $(UDEFS)
|
||||
ADEFS = $(DADEFS) $(UADEFS)
|
||||
|
||||
# Libs
|
||||
LIBS = $(DLIBS) $(ULIBS)
|
||||
|
||||
# Various settings
|
||||
MCFLAGS = -mcpu=$(MCU)
|
||||
ODFLAGS = -x --syms
|
||||
ASFLAGS = $(MCFLAGS) -Wa,-amhls=$(LSTDIR)/$(notdir $(<:.s=.lst)) $(ADEFS)
|
||||
ASXFLAGS = $(MCFLAGS) -Wa,-amhls=$(LSTDIR)/$(notdir $(<:.S=.lst)) $(ADEFS)
|
||||
CFLAGS = $(MCFLAGS) $(OPT) $(COPT) $(CWARN) -Wa,-alms=$(LSTDIR)/$(notdir $(<:.c=.lst)) $(DEFS)
|
||||
CPPFLAGS = $(MCFLAGS) $(OPT) $(CPPOPT) $(CPPWARN) -Wa,-alms=$(LSTDIR)/$(notdir $(<:.cpp=.lst)) $(DEFS)
|
||||
ifeq ($(USE_LINK_GC),yes)
|
||||
LDFLAGS = $(MCFLAGS) -nostartfiles -T$(LDSCRIPT) -Wl,-Map=$(BUILDDIR)/$(PROJECT).map,--cref,--no-warn-mismatch,--gc-sections $(LLIBDIR)
|
||||
else
|
||||
LDFLAGS = $(MCFLAGS) -nostartfiles -T$(LDSCRIPT) -Wl,-Map=$(BUILDDIR)/$(PROJECT).map,--cref,--no-warn-mismatch $(LLIBDIR)
|
||||
endif
|
||||
|
||||
# Thumb interwork enabled only if needed because it kills performance.
|
||||
ifneq ($(TSRC),)
|
||||
CFLAGS += -DTHUMB_PRESENT
|
||||
CPPFLAGS += -DTHUMB_PRESENT
|
||||
ASFLAGS += -DTHUMB_PRESENT
|
||||
ifneq ($(ASRC),)
|
||||
# Mixed ARM and THUMB mode.
|
||||
CFLAGS += -mthumb-interwork
|
||||
CPPFLAGS += -mthumb-interwork
|
||||
ASFLAGS += -mthumb-interwork
|
||||
LDFLAGS += -mthumb-interwork
|
||||
else
|
||||
# Pure THUMB mode, THUMB C code cannot be called by ARM asm code directly.
|
||||
CFLAGS += -mno-thumb-interwork -DTHUMB_NO_INTERWORKING
|
||||
CPPFLAGS += -mno-thumb-interwork -DTHUMB_NO_INTERWORKING
|
||||
ASFLAGS += -mno-thumb-interwork -DTHUMB_NO_INTERWORKING -mthumb
|
||||
LDFLAGS += -mno-thumb-interwork -mthumb
|
||||
endif
|
||||
else
|
||||
# Pure ARM mode
|
||||
CFLAGS += -mno-thumb-interwork
|
||||
CPPFLAGS += -mno-thumb-interwork
|
||||
ASFLAGS += -mno-thumb-interwork
|
||||
LDFLAGS += -mno-thumb-interwork
|
||||
endif
|
||||
|
||||
# Generate dependency information
|
||||
CFLAGS += -MD -MP -MF .dep/$(@F).d
|
||||
CPPFLAGS += -MD -MP -MF .dep/$(@F).d
|
||||
|
||||
# Paths where to search for sources
|
||||
VPATH = $(SRCPATHS)
|
||||
|
||||
#
|
||||
# Makefile rules
|
||||
#
|
||||
|
||||
all: $(OBJS) $(OUTFILES) MAKE_ALL_RULE_HOOK
|
||||
|
||||
MAKE_ALL_RULE_HOOK:
|
||||
|
||||
$(OBJS): | $(BUILDDIR)
|
||||
|
||||
$(BUILDDIR) $(OBJDIR) $(LSTDIR):
|
||||
ifneq ($(USE_VERBOSE_COMPILE),yes)
|
||||
@echo Compiler Options
|
||||
@echo $(CC) -c $(CFLAGS) -I. $(IINCDIR) main.c -o main.o
|
||||
@echo
|
||||
endif
|
||||
mkdir -p $(OBJDIR)
|
||||
mkdir -p $(LSTDIR)
|
||||
|
||||
$(ACPPOBJS) : $(OBJDIR)/%.o : %.cpp Makefile
|
||||
ifeq ($(USE_VERBOSE_COMPILE),yes)
|
||||
@echo
|
||||
$(CPPC) -c $(CPPFLAGS) $(AOPT) -I. $(IINCDIR) $< -o $@
|
||||
else
|
||||
@echo Compiling $(<F)
|
||||
@$(CPPC) -c $(CPPFLAGS) $(AOPT) -I. $(IINCDIR) $< -o $@
|
||||
endif
|
||||
|
||||
$(TCPPOBJS) : $(OBJDIR)/%.o : %.cpp Makefile
|
||||
ifeq ($(USE_VERBOSE_COMPILE),yes)
|
||||
@echo
|
||||
$(CPPC) -c $(CPPFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
|
||||
else
|
||||
@echo Compiling $(<F)
|
||||
@$(CPPC) -c $(CPPFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
|
||||
endif
|
||||
|
||||
$(ACOBJS) : $(OBJDIR)/%.o : %.c Makefile
|
||||
ifeq ($(USE_VERBOSE_COMPILE),yes)
|
||||
@echo
|
||||
$(CC) -c $(CFLAGS) $(AOPT) -I. $(IINCDIR) $< -o $@
|
||||
else
|
||||
@echo Compiling $(<F)
|
||||
@$(CC) -c $(CFLAGS) $(AOPT) -I. $(IINCDIR) $< -o $@
|
||||
endif
|
||||
|
||||
$(TCOBJS) : $(OBJDIR)/%.o : %.c Makefile
|
||||
ifeq ($(USE_VERBOSE_COMPILE),yes)
|
||||
@echo
|
||||
$(CC) -c $(CFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
|
||||
else
|
||||
@echo Compiling $(<F)
|
||||
@$(CC) -c $(CFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
|
||||
endif
|
||||
|
||||
$(ASMOBJS) : $(OBJDIR)/%.o : %.s Makefile
|
||||
ifeq ($(USE_VERBOSE_COMPILE),yes)
|
||||
@echo
|
||||
$(AS) -c $(ASFLAGS) -I. $(IINCDIR) $< -o $@
|
||||
else
|
||||
@echo Compiling $(<F)
|
||||
@$(AS) -c $(ASFLAGS) -I. $(IINCDIR) $< -o $@
|
||||
endif
|
||||
|
||||
$(ASMXOBJS) : $(OBJDIR)/%.o : %.S Makefile
|
||||
ifeq ($(USE_VERBOSE_COMPILE),yes)
|
||||
@echo
|
||||
$(CC) -c $(ASXFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
|
||||
else
|
||||
@echo Compiling $(<F)
|
||||
@$(CC) -c $(ASXFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
|
||||
endif
|
||||
|
||||
%.elf: $(OBJS) $(LDSCRIPT)
|
||||
ifeq ($(USE_VERBOSE_COMPILE),yes)
|
||||
@echo
|
||||
$(LD) $(OBJS) $(LDFLAGS) $(LIBS) -o $@
|
||||
else
|
||||
@echo Linking $@
|
||||
@$(LD) $(OBJS) $(LDFLAGS) $(LIBS) -o $@
|
||||
endif
|
||||
|
||||
%.hex: %.elf $(LDSCRIPT)
|
||||
ifeq ($(USE_VERBOSE_COMPILE),yes)
|
||||
$(HEX) $< $@
|
||||
else
|
||||
@echo Creating $@
|
||||
@$(HEX) $< $@
|
||||
endif
|
||||
|
||||
%.bin: %.elf $(LDSCRIPT)
|
||||
ifeq ($(USE_VERBOSE_COMPILE),yes)
|
||||
$(BIN) $< $@
|
||||
else
|
||||
@echo Creating $@
|
||||
@$(BIN) $< $@
|
||||
endif
|
||||
|
||||
%.dmp: %.elf $(LDSCRIPT)
|
||||
ifeq ($(USE_VERBOSE_COMPILE),yes)
|
||||
$(OD) $(ODFLAGS) $< > $@
|
||||
else
|
||||
@echo Creating $@
|
||||
@$(OD) $(ODFLAGS) $< > $@
|
||||
@echo Done
|
||||
endif
|
||||
|
||||
clean:
|
||||
@echo Cleaning
|
||||
-rm -fR .dep $(BUILDDIR)
|
||||
@echo Done
|
||||
|
||||
#
|
||||
# Include the dependency files, should be the last of the makefile
|
||||
#
|
||||
-include $(shell mkdir .dep 2>/dev/null) $(wildcard .dep/*)
|
||||
|
||||
# *** EOF ***
|
|
@ -41,7 +41,7 @@
|
|||
/**
|
||||
* @brief Type of an IRQ vector.
|
||||
*/
|
||||
typedef void (*irq_vector_t)(void) __attribute__((weak, alias("_unhandled_exception")));
|
||||
typedef void (*irq_vector_t)(void);
|
||||
|
||||
/**
|
||||
* @brief Type of a structure representing the whole vectors table.
|
||||
|
@ -457,6 +457,7 @@ void Vector3F4(void) __attribute__((weak, alias("_unhandled_exception")));
|
|||
void Vector3F8(void) __attribute__((weak, alias("_unhandled_exception")));
|
||||
void Vector3FC(void) __attribute__((weak, alias("_unhandled_exception")));
|
||||
#endif
|
||||
#endif /* !defined(__DOXYGEN__) */
|
||||
|
||||
/**
|
||||
* @brief STM32 vectors table.
|
||||
|
|
|
@ -37,11 +37,6 @@
|
|||
*/
|
||||
#define CORTEX_MODEL CORTEX_M4
|
||||
|
||||
/**
|
||||
* @brief Systick unit presence.
|
||||
*/
|
||||
#define CORTEX_HAS_ST TRUE
|
||||
|
||||
/**
|
||||
* @brief Memory Protection unit presence.
|
||||
*/
|
||||
|
@ -57,6 +52,36 @@
|
|||
*/
|
||||
#define CORTEX_PRIORITY_BITS 4
|
||||
|
||||
/**
|
||||
* @brief Number of interrupt vectors.
|
||||
* @note This number does not include the 16 system vectors and must be
|
||||
* rounded to a multiple of 4.
|
||||
*/
|
||||
#define CORTEX_NUM_VECTORS 84
|
||||
|
||||
/* The following code is not processed when the file is included from an
|
||||
asm module.*/
|
||||
#if !defined(_FROM_ASM_)
|
||||
|
||||
/* Including the device CMSIS header. Note, we are not using the definitions
|
||||
from this header because we need this file to be usable also from
|
||||
assembler source files. We verify that the info matches instead.*/
|
||||
#include "stm32f30x.h"
|
||||
|
||||
#if !CORTEX_HAS_MPU != !__MPU_PRESENT
|
||||
#error "CMSIS __MPU_PRESENT mismatch"
|
||||
#endif
|
||||
|
||||
#if !CORTEX_HAS_FPU != !__FPU_PRESENT
|
||||
#error "CMSIS __FPU_PRESENT mismatch"
|
||||
#endif
|
||||
|
||||
#if CORTEX_PRIORITY_BITS != __NVIC_PRIO_BITS
|
||||
#error "CMSIS __NVIC_PRIO_BITS mismatch"
|
||||
#endif
|
||||
|
||||
#endif /* !defined(_FROM_ASM_) */
|
||||
|
||||
#endif /* _CMPARAMS_H_ */
|
||||
|
||||
/** @} */
|
||||
|
|
|
@ -1,14 +1,14 @@
|
|||
# List of the ChibiOS/RT Cortex-M4 STM32F30x port files.
|
||||
PORTSRC = ${CHIBIOS}/os/kernel/ports/ARMCMx/chcore.c \
|
||||
${CHIBIOS}/os/kernel/ports/ARMCMx/chcore_v7m.c \
|
||||
$(CHIBIOS)/os/kernel/ports/ARMCMx/GCC/crt0.c \
|
||||
$(CHIBIOS)/os/kernel/ports/ARMCMx/GCC/vectors.c \
|
||||
$(CHIBIOS)/os/kernel/ports/ARMCMx/compilers/GCC/crt0.c \
|
||||
$(CHIBIOS)/os/kernel/ports/ARMCMx/compilers/GCC/vectors.c \
|
||||
|
||||
PORTASM = $(CHIBIOS)/os/kernel/ports/ARMCMx/GCC/chcoreasm_v7m.s
|
||||
PORTASM = $(CHIBIOS)/os/kernel/ports/ARMCMx/compilers/GCC/chcoreasm_v7m.s
|
||||
|
||||
PORTINC = ${CHIBIOS}/os/kernel/ports/ARMCMx \
|
||||
${CHIBIOS}/os/kernel/ports/ARMCMx/GCC \
|
||||
${CHIBIOS}/os/kernel/ports/ARMCMx/GCC/STM32F30x \
|
||||
${CHIBIOS}/os/kernel/ports/ARMCMx/common/CMSIS/include
|
||||
${CHIBIOS}/os/kernel/ports/ARMCMx/CMSIS/include \
|
||||
${CHIBIOS}/os/kernel/ports/ARMCMx/compilers/GCC \
|
||||
${CHIBIOS}/os/kernel/ports/ARMCMx/devices/STM32F30x
|
||||
|
||||
PORTLD = ${CHIBIOS}/os/ports/GCC/ld
|
||||
PORTLD = ${CHIBIOS}/os/kernel/ports/ARMCMx/compilers/GCC/ld
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,105 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32f30x.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 04-September-2012
|
||||
* @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2012 STMicroelectronics</center></h2>
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32f30x_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Define to prevent recursive inclusion
|
||||
*/
|
||||
#ifndef __SYSTEM_STM32F30X_H
|
||||
#define __SYSTEM_STM32F30X_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/** @addtogroup STM32F30x_System_Includes
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @addtogroup STM32F30x_System_Exported_types
|
||||
* @{
|
||||
*/
|
||||
|
||||
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Exported_Constants
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Exported_Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Exported_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
extern void SystemInit(void);
|
||||
extern void SystemCoreClockUpdate(void);
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /*__SYSTEM_STM32F30X_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
Loading…
Reference in New Issue