aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mathlib/CMSIS/Include/core_cm4.h
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/mathlib/CMSIS/Include/core_cm4.h')
-rw-r--r--src/modules/mathlib/CMSIS/Include/core_cm4.h57
1 files changed, 36 insertions, 21 deletions
diff --git a/src/modules/mathlib/CMSIS/Include/core_cm4.h b/src/modules/mathlib/CMSIS/Include/core_cm4.h
index 5f3b7d619..93efd3a7a 100644
--- a/src/modules/mathlib/CMSIS/Include/core_cm4.h
+++ b/src/modules/mathlib/CMSIS/Include/core_cm4.h
@@ -1,25 +1,40 @@
/**************************************************************************//**
* @file core_cm4.h
* @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File
- * @version V3.01
- * @date 22. March 2012
+ * @version V3.20
+ * @date 25. February 2013
*
* @note
- * Copyright (C) 2009-2012 ARM Limited. All rights reserved.
- *
- * @par
- * ARM Limited (ARM) is supplying this software for use with Cortex-M
- * processor based microcontrollers. This file can be freely distributed
- * within development tools that are supporting such ARM based processors.
- *
- * @par
- * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
- * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
- * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
- * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
- * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
*
******************************************************************************/
+/* Copyright (c) 2009 - 2013 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 */
#endif
@@ -54,7 +69,7 @@
/* CMSIS CM4 definitions */
#define __CM4_CMSIS_VERSION_MAIN (0x03) /*!< [31:16] CMSIS HAL main version */
-#define __CM4_CMSIS_VERSION_SUB (0x01) /*!< [15:0] CMSIS HAL sub version */
+#define __CM4_CMSIS_VERSION_SUB (0x20) /*!< [15:0] CMSIS HAL sub version */
#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16) | \
__CM4_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */
@@ -669,14 +684,14 @@ typedef struct
__IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */
uint32_t RESERVED2[15];
__IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */
- uint32_t RESERVED3[29];
+ uint32_t RESERVED3[29];
__O uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */
__I uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */
__IO uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */
- uint32_t RESERVED4[43];
+ uint32_t RESERVED4[43];
__O uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */
__I uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */
- uint32_t RESERVED5[6];
+ uint32_t RESERVED5[6];
__I uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */
__I uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */
__I uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */
@@ -1661,9 +1676,9 @@ __STATIC_INLINE void NVIC_SystemReset(void)
*/
__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks)
{
- if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */
+ if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */
- SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */
+ SysTick->LOAD = ticks - 1; /* set reload register */
NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */
SysTick->VAL = 0; /* Load the SysTick Counter Value */
SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |