@@ -138,6 +138,7 @@ env:
- RTT_BSP='xplorer4330/M4' RTT_TOOL_CHAIN='sourcery-arm'
- RTT_BSP='at32/at32f403a-start' RTT_TOOL_CHAIN='sourcery-arm'
- RTT_BSP='at32/at32f407-start' RTT_TOOL_CHAIN='sourcery-arm'
+ - RTT_BSP='smartfusion2' RTT_TOOL_CHAIN='sourcery-arm'
stage: compile
script:
@@ -258,7 +258,7 @@ const static struct rt_pin_ops drv_pin_ops =
int rt_hw_pin_init(void)
{
rt_err_t ret = RT_EOK;
- memset(pin_alloc_table, 0, sizeof pin_alloc_table);
+ memset(pin_alloc_table, -1, sizeof pin_alloc_table);
free_pin = GPIO_ALLOC_START;
ret = rt_device_pin_register("pin", &drv_pin_ops, RT_NULL);
@@ -9,8 +9,10 @@ src = Split("""
""")
if GetDepend(['BSP_USING_UART']):
- src += ['drv_uart.c']
-
+ if GetDepend(['NRFX_USING_UART']):
+ src += ['drv_uart.c']
+ else:
+ src += ['drv_uarte.c']
if GetDepend(['BSP_USING_ON_CHIP_FLASH']):
src += ['drv_flash.c']
@@ -0,0 +1,281 @@
+/*
+ * Copyright (c) 2006-2020, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ * Change Logs:
+ * Date Author Notes
+ * 2020-04-28 xckhmf Modify for <nrfx>
+ * 2020-10-31 xckhmf Support for UART1
+ */
+#include <rtdevice.h>
+#include <nrfx_uarte.h>
+#include "drv_uart.h"
+
+#ifdef BSP_USING_UART
+#if defined(BSP_USING_UART0) || defined(BSP_USING_UART1)
+typedef struct
+{
+ struct rt_serial_device *serial;
+ nrfx_uarte_t uarte_instance;
+ uint8_t rx_length;
+ uint8_t tx_buffer[1];
+ uint8_t rx_buffer[1];
+ bool isInit;
+ uint32_t rx_pin;
+ uint32_t tx_pin;
+} drv_uart_cb_t;
+#ifdef BSP_USING_UART0
+static struct rt_serial_device m_serial_0;
+drv_uart_cb_t m_uarte0_cb = {
+ .uarte_instance = NRFX_UARTE_INSTANCE(0),
+ .rx_length = 0,
+ .rx_pin = BSP_UART0_RX_PIN,
+ .tx_pin = BSP_UART0_TX_PIN,
+ .isInit = false
+};
+#endif /* BSP_USING_UART0 */
+#ifdef BSP_USING_UART1
+static struct rt_serial_device m_serial_1;
+drv_uart_cb_t m_uarte1_cb = {
+ .uarte_instance = NRFX_UARTE_INSTANCE(1),
+ .rx_pin = BSP_UART1_RX_PIN,
+ .tx_pin = BSP_UART1_TX_PIN,
+#endif /* BSP_USING_UART1 */
+static void uarte_evt_handler(nrfx_uarte_event_t const * p_event,
+ void * p_context)
+ drv_uart_cb_t *p_cb = RT_NULL;
+ p_cb = (drv_uart_cb_t*)p_context;
+ switch (p_event->type)
+ {
+ case NRFX_UARTE_EVT_RX_DONE:
+ p_cb->rx_length = p_event->data.rxtx.bytes;
+ if(p_cb->serial->parent.open_flag&RT_DEVICE_FLAG_INT_RX)
+ rt_hw_serial_isr(p_cb->serial, RT_SERIAL_EVENT_RX_IND);
+ }
+ (void)nrfx_uarte_rx(&(p_cb->uarte_instance), p_cb->rx_buffer, 1);
+ break;
+ case NRFX_UARTE_EVT_ERROR:
+ case NRFX_UARTE_EVT_TX_DONE:
+ if(p_cb->serial->parent.open_flag&RT_DEVICE_FLAG_INT_TX)
+ rt_hw_serial_isr(p_cb->serial, RT_SERIAL_EVENT_TX_DONE);
+ default:
+}
+static rt_err_t _uart_cfg(struct rt_serial_device *serial, struct serial_configure *cfg)
+ nrfx_uarte_config_t config = NRFX_UARTE_DEFAULT_CONFIG(NRF_UARTE_PSEL_DISCONNECTED,\
+ NRF_UARTE_PSEL_DISCONNECTED);
+ RT_ASSERT(serial != RT_NULL);
+ RT_ASSERT(cfg != RT_NULL);
+ if (serial->parent.user_data == RT_NULL)
+ return -RT_ERROR;
+ p_cb = (drv_uart_cb_t*)serial->parent.user_data;
+ if(p_cb->isInit)
+ nrfx_uarte_uninit(&(p_cb->uarte_instance));
+ p_cb->isInit = false;
+ switch (cfg->baud_rate)
+ case BAUD_RATE_2400:
+ config.baudrate = NRF_UARTE_BAUDRATE_2400;
+ case BAUD_RATE_4800:
+ config.baudrate = NRF_UARTE_BAUDRATE_4800;
+ case BAUD_RATE_9600:
+ config.baudrate = NRF_UARTE_BAUDRATE_9600;
+ case BAUD_RATE_19200:
+ config.baudrate = NRF_UARTE_BAUDRATE_19200;
+ case BAUD_RATE_38400:
+ config.baudrate = NRF_UARTE_BAUDRATE_38400;
+ case BAUD_RATE_57600:
+ config.baudrate = NRF_UARTE_BAUDRATE_57600;
+ case BAUD_RATE_115200:
+ config.baudrate = NRF_UARTE_BAUDRATE_115200;
+ case BAUD_RATE_230400:
+ config.baudrate = NRF_UARTE_BAUDRATE_230400;
+ case BAUD_RATE_460800:
+ config.baudrate = NRF_UARTE_BAUDRATE_460800;
+ case BAUD_RATE_921600:
+ config.baudrate = NRF_UARTE_BAUDRATE_921600;
+ case BAUD_RATE_2000000:
+ case BAUD_RATE_3000000:
+ return -RT_EINVAL;
+ config.hal_cfg.parity = (cfg->parity == PARITY_NONE)?\
+ NRF_UARTE_PARITY_EXCLUDED:NRF_UARTE_PARITY_INCLUDED;
+ config.hal_cfg.hwfc = NRF_UARTE_HWFC_DISABLED;
+ config.pselrxd = p_cb->rx_pin;
+ config.pseltxd = p_cb->tx_pin;
+ config.p_context = (void *)p_cb;
+ nrfx_uarte_init(&(p_cb->uarte_instance),(nrfx_uarte_config_t const *)&config,uarte_evt_handler);
+ nrfx_uarte_rx(&(p_cb->uarte_instance),p_cb->rx_buffer,1);
+ p_cb->isInit = true;
+ return RT_EOK;
+static rt_err_t _uart_ctrl(struct rt_serial_device *serial, int cmd, void *arg)
+ switch (cmd)
+ /* disable interrupt */
+ case RT_DEVICE_CTRL_CLR_INT:
+ /* enable interrupt */
+ case RT_DEVICE_CTRL_SET_INT:
+ case RT_DEVICE_CTRL_CUSTOM:
+ if ((rt_uint32_t)(arg) == UART_CONFIG_BAUD_RATE_9600)
+ p_cb->serial->config.baud_rate = 9600;
+ else if ((rt_uint32_t)(arg) == UART_CONFIG_BAUD_RATE_115200)
+ p_cb->serial->config.baud_rate = 115200;
+ _uart_cfg(serial, &(serial->config));
+ case RT_DEVICE_CTRL_PIN:
+ case RT_DEVICE_POWERSAVE:
+ case RT_DEVICE_WAKEUP:
+static int _uart_putc(struct rt_serial_device *serial, char c)
+ int rtn = -1;
+ if (serial->parent.user_data != RT_NULL)
+ p_cb->tx_buffer[0] = c;
+ nrfx_uarte_tx(&(p_cb->uarte_instance),p_cb->tx_buffer,1);
+ if(!(serial->parent.open_flag&RT_DEVICE_FLAG_INT_TX))
+ while(nrfx_uarte_tx_in_progress(&(p_cb->uarte_instance)))
+ return rtn;
+static int _uart_getc(struct rt_serial_device *serial)
+ int ch = -1;
+ if(p_cb->rx_length)
+ ch = p_cb->rx_buffer[0];
+ p_cb->rx_length--;
+ return ch;
+static struct rt_uart_ops _uart_ops = {
+ _uart_cfg,
+ _uart_ctrl,
+ _uart_putc,
+ _uart_getc
+void rt_hw_uart_init(void)
+ struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT;
+ m_serial_0.config = config;
+ m_serial_0.ops = &_uart_ops;
+ m_uarte0_cb.serial = &m_serial_0;
+ rt_hw_serial_register(&m_serial_0, "uart0", \
+ RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX , &m_uarte0_cb);
+ m_serial_1.config = config;
+ m_serial_1.ops = &_uart_ops;
+ m_uarte1_cb.serial = &m_serial_1;
+ rt_hw_serial_register(&m_serial_1, "uart1", \
+ RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX |RT_DEVICE_FLAG_INT_TX, &m_uarte1_cb);
+#endif /* defined(BSP_USING_UART0) || defined(BSP_USING_UART1) */
+#endif /* BSP_USING_UART */
@@ -0,0 +1,33 @@
+#ifndef __DRV_UART_H__
+#define __DRV_UART_H__
+#ifdef __cplusplus
+extern "C" {
+#endif
+#define RT_DEVICE_CTRL_CUSTOM 0x20
+#define RT_DEVICE_CTRL_PIN 0x21
+#define RT_DEVICE_POWERSAVE 0x22
+#define RT_DEVICE_WAKEUP 0x23
+#define UART_CONFIG_BAUD_RATE_9600 1
+#define UART_CONFIG_BAUD_RATE_115200 2
+void rt_hw_uart_init(void);
+#endif /* __DRV_UART_H__ */
@@ -120,6 +120,7 @@ CONFIG_RT_SERIAL_RB_BUFSZ=64
# CONFIG_RT_USING_HWTIMER is not set
# CONFIG_RT_USING_CPUTIME is not set
# CONFIG_RT_USING_I2C is not set
+# CONFIG_RT_USING_PHY is not set
CONFIG_RT_USING_PIN=y
# CONFIG_RT_USING_ADC is not set
# CONFIG_RT_USING_DAC is not set
@@ -195,15 +196,12 @@ CONFIG_RT_USING_LIBC=y
#
# IoT - internet of things
-# CONFIG_PKG_USING_LORAWAN_DRIVER is not set
# CONFIG_PKG_USING_PAHOMQTT is not set
-# CONFIG_PKG_USING_UMQTT is not set
# CONFIG_PKG_USING_WEBCLIENT is not set
# CONFIG_PKG_USING_WEBNET is not set
# CONFIG_PKG_USING_MONGOOSE is not set
# CONFIG_PKG_USING_MYMQTT is not set
# CONFIG_PKG_USING_KAWAII_MQTT is not set
-# CONFIG_PKG_USING_BC28_MQTT is not set
# CONFIG_PKG_USING_WEBTERMINAL is not set
# CONFIG_PKG_USING_CJSON is not set
# CONFIG_PKG_USING_JSMN is not set
@@ -230,7 +228,6 @@ CONFIG_RT_USING_LIBC=y
# CONFIG_PKG_USING_COAP is not set
# CONFIG_PKG_USING_NOPOLL is not set
# CONFIG_PKG_USING_NETUTILS is not set
-# CONFIG_PKG_USING_CMUX is not set
# CONFIG_PKG_USING_PPP_DEVICE is not set
# CONFIG_PKG_USING_AT_DEVICE is not set
# CONFIG_PKG_USING_ATSRV_SOCKET is not set
@@ -243,7 +240,7 @@ CONFIG_RT_USING_LIBC=y
# CONFIG_PKG_USING_GAGENT_CLOUD is not set
# CONFIG_PKG_USING_ALI_IOTKIT is not set
# CONFIG_PKG_USING_AZURE is not set
-# CONFIG_PKG_USING_TENCENT_IOT_EXPLORER is not set
+# CONFIG_PKG_USING_TENCENT_IOTHUB is not set
# CONFIG_PKG_USING_JIOT-C-SDK is not set
# CONFIG_PKG_USING_UCLOUD_IOT_SDK is not set
# CONFIG_PKG_USING_JOYLINK is not set
@@ -265,7 +262,6 @@ CONFIG_RT_USING_LIBC=y
# CONFIG_PKG_USING_CAPNP is not set
# CONFIG_PKG_USING_RT_CJSON_TOOLS is not set
# CONFIG_PKG_USING_AGILE_TELNET is not set
-# CONFIG_PKG_USING_NMEALIB is not set
# security packages
@@ -274,7 +270,6 @@ CONFIG_RT_USING_LIBC=y
# CONFIG_PKG_USING_libsodium is not set
# CONFIG_PKG_USING_TINYCRYPT is not set
# CONFIG_PKG_USING_TFM is not set
-# CONFIG_PKG_USING_YD_CRYPTO is not set
# language packages
@@ -309,8 +304,6 @@ CONFIG_RT_USING_LIBC=y
# CONFIG_PKG_USING_CHINESE_FONT_LIBRARY is not set
# CONFIG_PKG_USING_LUNAR_CALENDAR is not set
# CONFIG_PKG_USING_BS8116A is not set
-# CONFIG_PKG_USING_GPS_RMC is not set
-# CONFIG_PKG_USING_URLENCODE is not set
# system packages
@@ -321,7 +314,6 @@ CONFIG_RT_USING_LIBC=y
# CONFIG_PKG_USING_LWEXT4 is not set
# CONFIG_PKG_USING_PARTITION is not set
# CONFIG_PKG_USING_FAL is not set
-# CONFIG_PKG_USING_FLASHDB is not set
# CONFIG_PKG_USING_SQLITE is not set
# CONFIG_PKG_USING_RTI is not set
# CONFIG_PKG_USING_LITTLEVGL2RTT is not set
@@ -334,9 +326,6 @@ CONFIG_RT_USING_LIBC=y
# CONFIG_PKG_USING_SYSWATCH is not set
# CONFIG_PKG_USING_SYS_LOAD_MONITOR is not set
# CONFIG_PKG_USING_PLCCORE is not set
-# CONFIG_PKG_USING_RAMDISK is not set
-# CONFIG_PKG_USING_MININI is not set
-# CONFIG_PKG_USING_QBOOT is not set
# peripheral libraries and drivers
@@ -378,7 +367,6 @@ CONFIG_PKG_NRFX_VER="v2.1.0"
# CONFIG_PKG_USING_RPLIDAR is not set
# CONFIG_PKG_USING_AS608 is not set
# CONFIG_PKG_USING_RC522 is not set
-# CONFIG_PKG_USING_WS2812B is not set
# CONFIG_PKG_USING_EMBARC_BSP is not set
# CONFIG_PKG_USING_EXTERN_RTC_DRIVERS is not set
# CONFIG_PKG_USING_MULTI_RTIMER is not set
@@ -386,11 +374,6 @@ CONFIG_PKG_NRFX_VER="v2.1.0"
# CONFIG_PKG_USING_BEEP is not set
# CONFIG_PKG_USING_EASYBLINK is not set
# CONFIG_PKG_USING_PMS_SERIES is not set
-# CONFIG_PKG_USING_CAN_YMODEM is not set
-# CONFIG_PKG_USING_LORA_RADIO_DRIVER is not set
-# CONFIG_PKG_USING_QLED is not set
-# CONFIG_PKG_USING_PAJ7620 is not set
-# CONFIG_PKG_USING_AGILE_CONSOLE is not set
# miscellaneous packages
@@ -427,31 +410,36 @@ CONFIG_PKG_NRFX_VER="v2.1.0"
# CONFIG_PKG_USING_VT100 is not set
# CONFIG_PKG_USING_ULAPACK is not set
# CONFIG_PKG_USING_UKAL is not set
-# CONFIG_PKG_USING_CRCLIB is not set
# Hardware Drivers Config
CONFIG_SOC_NRF52832=y
+CONFIG_NRFX_CLOCK_ENABLED=1
+CONFIG_NRFX_CLOCK_DEFAULT_CONFIG_IRQ_PRIORITY=7
+CONFIG_NRFX_CLOCK_CONFIG_LF_SRC=1
CONFIG_SOC_NORDIC=y
# Onboard Peripheral Drivers
# CONFIG_BSP_USING_JLINK_TO_USART is not set
-# CONFIG_BSP_USING_QSPI_FLASH is not set
# On-chip Peripheral Drivers
CONFIG_BSP_USING_GPIO=y
+CONFIG_NRFX_GPIOTE_ENABLED=1
+# CONFIG_BSP_USING_SAADC is not set
# CONFIG_BSP_USING_PWM is not set
-# CONFIG_BSP_USING_SOFTDEVICE is not set
CONFIG_BSP_USING_UART=y
+CONFIG_NRFX_USING_UART=y
+# CONFIG_NRFX_USING_UARTE is not set
+CONFIG_NRFX_UART_ENABLED=1
CONFIG_BSP_USING_UART0=y
+CONFIG_NRFX_UART0_ENABLED=1
CONFIG_BSP_UART0_RX_PIN=8
CONFIG_BSP_UART0_TX_PIN=6
-# CONFIG_BSP_USING_UART1 is not set
# CONFIG_BSP_USING_SPI is not set
# CONFIG_BSP_USING_ON_CHIP_FLASH is not set
@@ -463,3 +451,8 @@ CONFIG_MCU_FLASH_SIZE_KB=1024
CONFIG_MCU_SRAM_START_ADDRESS=0x20000000
CONFIG_MCU_SRAM_SIZE_KB=256
CONFIG_MCU_FLASH_PAGE_SIZE=0x1000
+# CONFIG_BSP_USING_WDT is not set
+# CONFIG_BSP_USING_ONCHIP_RTC is not set
+CONFIG_BLE_STACK_USING_NULL=y
+# CONFIG_BSP_USING_SOFTDEVICE is not set
+# CONFIG_BSP_USING_NIMBLE is not set
@@ -157,12 +157,24 @@ menu "On-chip Peripheral Drivers"
endif
- menuconfig BSP_USING_UART
- bool "Enable UART"
+ config BSP_USING_UART
+ bool "Enable UART"
default y
select RT_USING_SERIAL
- if BSP_USING_UART
+ if BSP_USING_UART
+ choice
+ prompt "UART or UARTE"
+ default NRFX_USING_UART
+ help
+ Select the UART or UARTE
+ config NRFX_USING_UART
+ bool "UART"
+ config NRFX_USING_UARTE
+ bool "UARTE"
+ endchoice
+ endif
+ if BSP_USING_UART&&NRFX_USING_UART
config NRFX_UART_ENABLED
int
default 1
@@ -183,9 +195,28 @@ menu "On-chip Peripheral Drivers"
range 0 31
default 6
- config BSP_USING_UART1
- bool "Enable UART1"
- default n
+ if BSP_USING_UART&&NRFX_USING_UARTE
+ config NRFX_UARTE_ENABLED
+ int
+ default 1
+ config BSP_USING_UART0
+ bool "Enable UARTE0"
+ default n
+ if BSP_USING_UART0
+ config NRFX_UARTE0_ENABLED
+ config BSP_UART0_RX_PIN
+ int "uarte0 rx pin number"
+ range 0 31
+ default 8
+ config BSP_UART0_TX_PIN
+ int "uarte0 tx pin number"
+ default 6
config BSP_USING_SPI
@@ -152,6 +152,9 @@
/* Hardware Drivers Config */
#define SOC_NRF52832
+#define NRFX_CLOCK_ENABLED 1
+#define NRFX_CLOCK_DEFAULT_CONFIG_IRQ_PRIORITY 7
+#define NRFX_CLOCK_CONFIG_LF_SRC 1
#define SOC_NORDIC
/* Onboard Peripheral Drivers */
@@ -160,8 +163,12 @@
/* On-chip Peripheral Drivers */
#define BSP_USING_GPIO
+#define NRFX_GPIOTE_ENABLED 1
#define BSP_USING_UART
+#define NRFX_USING_UART
+#define NRFX_UART_ENABLED 1
#define BSP_USING_UART0
+#define NRFX_UART0_ENABLED 1
#define BSP_UART0_RX_PIN 8
#define BSP_UART0_TX_PIN 6
@@ -172,5 +179,6 @@
#define MCU_SRAM_START_ADDRESS 0x20000000
#define MCU_SRAM_SIZE_KB 256
#define MCU_FLASH_PAGE_SIZE 0x1000
+#define BLE_STACK_USING_NULL
#endif
@@ -65,7 +65,7 @@ CONFIG_RT_USING_DEVICE=y
# CONFIG_RT_USING_INTERRUPT_INFO is not set
CONFIG_RT_USING_CONSOLE=y
CONFIG_RT_CONSOLEBUF_SIZE=128
-CONFIG_RT_CONSOLE_DEVICE_NAME="uart0"
+CONFIG_RT_CONSOLE_DEVICE_NAME="uart1"
CONFIG_RT_VER_NUM=0x40003
# CONFIG_RT_USING_CPU_FFS is not set
# CONFIG_ARCH_CPU_STACK_GROWS_UPWARD is not set
@@ -273,7 +270,6 @@ CONFIG_RT_USING_LIBC=y
@@ -308,7 +304,6 @@ CONFIG_RT_USING_LIBC=y
@@ -319,7 +314,6 @@ CONFIG_RT_USING_LIBC=y
@@ -332,8 +326,6 @@ CONFIG_RT_USING_LIBC=y
@@ -353,8 +345,6 @@ CONFIG_RT_USING_LIBC=y
# CONFIG_PKG_USING_LITTLED is not set
# CONFIG_PKG_USING_LKDGUI is not set
# CONFIG_PKG_USING_NRF5X_SDK is not set
-# CONFIG_PKG_USING_NRF5X_SDK_V1300 is not set
-# CONFIG_PKG_USING_NRF5X_SDK_LATEST_VERSION is not set
CONFIG_PKG_USING_NRFX=y
CONFIG_PKG_NRFX_PATH="/packages/peripherals/nrfx"
CONFIG_PKG_USING_NRFX_V210=y
@@ -384,10 +374,6 @@ CONFIG_PKG_NRFX_VER="v2.1.0"
@@ -429,6 +415,10 @@ CONFIG_PKG_NRFX_VER="v2.1.0"
CONFIG_SOC_NRF52840=y
+CONFIG_SOC_NORDIC=y
@@ -440,12 +430,17 @@ CONFIG_SOC_NRF52840=y
+# CONFIG_BSP_USING_PWM is not set
@@ -457,3 +452,8 @@ CONFIG_MCU_FLASH_SIZE_KB=1024
@@ -194,12 +194,24 @@ menu "On-chip Peripheral Drivers"
@@ -220,9 +232,44 @@ menu "On-chip Peripheral Drivers"
config BSP_USING_UART1
+ bool "Enable UARTE1"
+ if BSP_USING_UART1
+ config NRFX_UARTE1_ENABLED
+ config BSP_UART1_RX_PIN
+ int "uarte1 rx pin number"
+ default 7
+ config BSP_UART1_TX_PIN
+ int "uarte1 tx pin number"
+ default 5
@@ -152,6 +152,10 @@
#define SOC_NRF52840
+#define SOC_NORDIC
@@ -159,8 +163,12 @@
@@ -171,5 +179,6 @@
@@ -0,0 +1,17 @@
+from building import *
+import rtconfig
+cwd = GetCurrentDir()
+src = Glob('*.c')
+if rtconfig.CROSS_TOOL == 'gcc':
+ src += ['startup_gcc/startup_m2sxxx.S']
+elif rtconfig.CROSS_TOOL == 'keil':
+ src += ['startup_arm/startup_m2sxxx.s']
+CPPPATH = [cwd]
+group = DefineGroup('CMSIS', src, depend = [''], CPPPATH = CPPPATH)
+Return('group')
@@ -0,0 +1,810 @@
+/**************************************************************************//**
+ * @file core_cm3.c
+ * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Source File
+ * @version V1.30
+ * @date 30. October 2009
+ * @note
+ * Copyright (C) 2009 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.
+ * 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.
+ ******************************************************************************/
+/*******************************************************************************
+ * Microsemi SoC Products Group SVN revision number for the purpose of tracking
+ * changes done to original file supplied by ARM:
+ * SVN $Revision: 6671 $
+ * SVN $Date: 2014-07-04 12:15:22 +0100 (Fri, 04 Jul 2014) $
+#include <stdint.h>
+/* define compiler specific symbols */
+#if defined ( __CC_ARM )
+ #define __ASM __asm /*!< asm keyword for ARM Compiler */
+ #define __INLINE __inline /*!< inline keyword for ARM Compiler */
+#elif defined ( __ICCARM__ )
+ #define __ASM __asm /*!< asm keyword for IAR Compiler */
+ #define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */
+#elif defined ( __GNUC__ )
+ #define __ASM __asm /*!< asm keyword for GNU Compiler */
+ #define __INLINE inline /*!< inline keyword for GNU Compiler */
+#elif defined ( __TASKING__ )
+ #define __ASM __asm /*!< asm keyword for TASKING Compiler */
+ #define __INLINE inline /*!< inline keyword for TASKING Compiler */
+/* ################### Compiler specific Intrinsics ########################### */
+#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
+/* ARM armcc specific functions */
+/**
+ * @brief Return the Process Stack Pointer
+ * @return ProcessStackPointer
+ * Return the actual process stack pointer
+__ASM uint32_t __get_PSP(void)
+ mrs r0, psp
+ bx lr
+ * @brief Set the Process Stack Pointer
+ * @param topOfProcStack Process Stack Pointer
+ * Assign the value ProcessStackPointer to the MSP
+ * (process stack pointer) Cortex processor register
+__ASM void __set_PSP(uint32_t topOfProcStack)
+ msr psp, r0
+ * @brief Return the Main Stack Pointer
+ * @return Main Stack Pointer
+ * Return the current value of the MSP (main stack pointer)
+ * Cortex processor register
+__ASM uint32_t __get_MSP(void)
+ mrs r0, msp
+ * @brief Set the Main Stack Pointer
+ * @param topOfMainStack Main Stack Pointer
+ * Assign the value mainStackPointer to the MSP
+ * (main stack pointer) Cortex processor register
+__ASM void __set_MSP(uint32_t mainStackPointer)
+ msr msp, r0
+ * @brief Reverse byte order in unsigned short value
+ * @param value value to reverse
+ * @return reversed value
+ * Reverse byte order in unsigned short value
+__ASM uint32_t __REV16(uint16_t value)
+ rev16 r0, r0
+ * @brief Reverse byte order in signed short value with sign extension to integer
+ * Reverse byte order in signed short value with sign extension to integer
+__ASM int32_t __REVSH(int16_t value)
+ revsh r0, r0
+#if (__ARMCC_VERSION < 400000)
+ * @brief Remove the exclusive lock created by ldrex
+ * Removes the exclusive lock which is created by ldrex.
+__ASM void __CLREX(void)
+ clrex
+ * @brief Return the Base Priority value
+ * @return BasePriority
+ * Return the content of the base priority register
+__ASM uint32_t __get_BASEPRI(void)
+ mrs r0, basepri
+ * @brief Set the Base Priority value
+ * @param basePri BasePriority
+ * Set the base priority register
+__ASM void __set_BASEPRI(uint32_t basePri)
+ msr basepri, r0
+ * @brief Return the Priority Mask value
+ * @return PriMask
+ * Return state of the priority mask bit from the priority mask register
+__ASM uint32_t __get_PRIMASK(void)
+ mrs r0, primask
+ * @brief Set the Priority Mask value
+ * @param priMask PriMask
+ * Set the priority mask bit in the priority mask register
+__ASM void __set_PRIMASK(uint32_t priMask)
+ msr primask, r0
+ * @brief Return the Fault Mask value
+ * @return FaultMask
+ * Return the content of the fault mask register
+__ASM uint32_t __get_FAULTMASK(void)
+ mrs r0, faultmask
+ * @brief Set the Fault Mask value
+ * @param faultMask faultMask value
+ * Set the fault mask register
+__ASM void __set_FAULTMASK(uint32_t faultMask)
+ msr faultmask, r0
+ * @brief Return the Control Register value
+ * @return Control value
+ * Return the content of the control register
+__ASM uint32_t __get_CONTROL(void)
+ mrs r0, control
+ * @brief Set the Control Register value
+ * @param control Control value
+ * Set the control register
+__ASM void __set_CONTROL(uint32_t control)
+ msr control, r0
+#endif /* __ARMCC_VERSION */
+#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/
+/* IAR iccarm specific functions */
+#pragma diag_suppress=Pe940
+#if (__VER__ < 6020000)
+uint32_t __get_PSP(void)
+ __ASM("mrs r0, psp");
+ __ASM("bx lr");
+void __set_PSP(uint32_t topOfProcStack)
+ __ASM("msr psp, r0");
+uint32_t __get_MSP(void)
+ __ASM("mrs r0, msp");
+void __set_MSP(uint32_t topOfMainStack)
+ __ASM("msr msp, r0");
+uint32_t __REV16(uint16_t value)
+ __ASM("rev16 r0, r0");
+ * @brief Reverse bit order of value
+ * Reverse bit order of value
+uint32_t __RBIT(uint32_t value)
+ __ASM("rbit r0, r0");
+ * @brief LDR Exclusive (8 bit)
+ * @param *addr address pointer
+ * @return value of (*address)
+ * Exclusive LDR command for 8 bit values)
+uint8_t __LDREXB(uint8_t *addr)
+ __ASM("ldrexb r0, [r0]");
+ * @brief LDR Exclusive (16 bit)
+ * Exclusive LDR command for 16 bit values
+uint16_t __LDREXH(uint16_t *addr)
+ __ASM("ldrexh r0, [r0]");
+ * @brief LDR Exclusive (32 bit)
+ * Exclusive LDR command for 32 bit values
+uint32_t __LDREXW(uint32_t *addr)
+ __ASM("ldrex r0, [r0]");
+ * @brief STR Exclusive (8 bit)
+ * @param value value to store
+ * @return successful / failed
+ * Exclusive STR command for 8 bit values
+uint32_t __STREXB(uint8_t value, uint8_t *addr)
+ __ASM("strexb r0, r0, [r1]");
+ * @brief STR Exclusive (16 bit)
+ * Exclusive STR command for 16 bit values
+uint32_t __STREXH(uint16_t value, uint16_t *addr)
+ __ASM("strexh r0, r0, [r1]");
+ * @brief STR Exclusive (32 bit)
+ * Exclusive STR command for 32 bit values
+uint32_t __STREXW(uint32_t value, uint32_t *addr)
+ __ASM("strex r0, r0, [r1]");
+#pragma diag_default=Pe940
+#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/
+/* GNU gcc specific functions */
+uint32_t __get_PSP(void) __attribute__( ( naked ) );
+ uint32_t result=0;
+ __ASM volatile ("MRS %0, psp\n\t"
+ "MOV r0, %0 \n\t"
+ "BX lr \n\t" : "=r" (result) );
+ return(result);
+void __set_PSP(uint32_t topOfProcStack) __attribute__( ( naked ) );
+ __ASM volatile ("MSR psp, %0\n\t"
+ "BX lr \n\t" : : "r" (topOfProcStack) );
+uint32_t __get_MSP(void) __attribute__( ( naked ) );
+ __ASM volatile ("MRS %0, msp\n\t"
+void __set_MSP(uint32_t topOfMainStack) __attribute__( ( naked ) );
+ __ASM volatile ("MSR msp, %0\n\t"
+ "BX lr \n\t" : : "r" (topOfMainStack) );
+uint32_t __get_BASEPRI(void)
+ __ASM volatile ("MRS %0, basepri_max" : "=r" (result) );
+void __set_BASEPRI(uint32_t value)
+ __ASM volatile ("MSR basepri, %0" : : "r" (value) );
+uint32_t __get_PRIMASK(void)
+ __ASM volatile ("MRS %0, primask" : "=r" (result) );
+void __set_PRIMASK(uint32_t priMask)
+ __ASM volatile ("MSR primask, %0" : : "r" (priMask) );
+uint32_t __get_FAULTMASK(void)
+ __ASM volatile ("MRS %0, faultmask" : "=r" (result) );
+void __set_FAULTMASK(uint32_t faultMask)
+ __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) );
+*
+* @return Control value
+uint32_t __get_CONTROL(void)
+ __ASM volatile ("MRS %0, control" : "=r" (result) );
+void __set_CONTROL(uint32_t control)
+ __ASM volatile ("MSR control, %0" : : "r" (control) );
+ * @brief Reverse byte order in integer value
+ * Reverse byte order in integer value
+uint32_t __REV(uint32_t value)
+ __ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) );
+ __ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) );
+int32_t __REVSH(int16_t value)
+ __ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) );
+ __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) );
+ * Exclusive LDR command for 8 bit value
+ uint8_t result=0;
+ __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) );
+ uint16_t result=0;
+ __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) );
+ __ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) );
+ __ASM volatile ("strexb %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) );
+ __ASM volatile ("strexh %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) );
+ __ASM volatile ("strex %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
+#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/
+/* TASKING carm specific functions */
+ * The CMSIS functions have been implemented as intrinsics in the compiler.
+ * Please use "carm -?i" to get an up to date list of all instrinsics,
+ * Including the CMSIS ones.
@@ -0,0 +1,1844 @@
+ * @file core_cm3.h
+ * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File
+ * SVN $Revision: 4048 $
+ * SVN $Date: 2011-12-06 16:05:56 +0000 (Tue, 06 Dec 2011) $
+#ifndef __CM3_CORE_H__
+#define __CM3_CORE_H__
+/** @addtogroup CMSIS_CM3_core_LintCinfiguration CMSIS CM3 Core Lint Configuration
+ * List of Lint messages which will be suppressed and not shown:
+ * - Error 10: \n
+ * register uint32_t __regBasePri __asm("basepri"); \n
+ * Error 10: Expecting ';'
+ * .
+ * - Error 530: \n
+ * return(__regBasePri); \n
+ * Warning 530: Symbol '__regBasePri' (line 264) not initialized
+ * - Error 550: \n
+ * __regBasePri = (basePri & 0x1ff); \n
+ * Warning 550: Symbol '__regBasePri' (line 271) not accessed
+ * - Error 754: \n
+ * uint32_t RESERVED0[24]; \n
+ * Info 754: local structure member '<some, not used in the HAL>' (line 109, file ./cm3_core.h) not referenced
+ * - Error 750: \n
+ * #define __CM3_CORE_H__ \n
+ * Info 750: local macro '__CM3_CORE_H__' (line 43, file./cm3_core.h) not referenced
+ * - Error 528: \n
+ * static __INLINE void NVIC_DisableIRQ(uint32_t IRQn) \n
+ * Warning 528: Symbol 'NVIC_DisableIRQ(unsigned int)' (line 419, file ./cm3_core.h) not referenced
+ * - Error 751: \n
+ * } InterruptType_Type; \n
+ * Info 751: local typedef 'InterruptType_Type' (line 170, file ./cm3_core.h) not referenced
+ * Note: To re-enable a Message, insert a space before 'lint' *
+/*lint -save */
+/*lint -e10 */
+/*lint -e530 */
+/*lint -e550 */
+/*lint -e754 */
+/*lint -e750 */
+/*lint -e528 */
+/*lint -e751 */
+/** @addtogroup CMSIS_CM3_core_definitions CM3 Core Definitions
+ This file defines all structures and symbols for CMSIS core:
+ - CMSIS version number
+ - Cortex-M core registers and bitfields
+ - Cortex-M core peripheral base address
+ @{
+ extern "C" {
+#define __CM3_CMSIS_VERSION_MAIN (0x01) /*!< [31:16] CMSIS HAL main version */
+#define __CM3_CMSIS_VERSION_SUB (0x30) /*!< [15:0] CMSIS HAL sub version */
+#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | __CM3_CMSIS_VERSION_SUB) /*!< CMSIS HAL version number */
+#define __CORTEX_M (0x03) /*!< Cortex core */
+#include <stdint.h> /* Include standard types */
+#if defined (__ICCARM__)
+ #include <intrinsics.h> /* IAR Intrinsics */
+#ifndef __NVIC_PRIO_BITS
+ #define __NVIC_PRIO_BITS 4 /*!< standard definition for NVIC Priority Bits */
+ * IO definitions
+ * define access restrictions to peripheral registers
+ #define __I volatile /*!< defines 'read only' permissions */
+#else
+ #define __I volatile const /*!< defines 'read only' permissions */
+#define __O volatile /*!< defines 'write only' permissions */
+#define __IO volatile /*!< defines 'read / write' permissions */
+ * Register Abstraction
+/** @addtogroup CMSIS_CM3_core_register CMSIS CM3 Core Register
+*/
+/** @addtogroup CMSIS_CM3_NVIC CMSIS CM3 NVIC
+ memory mapped structure for Nested Vectored Interrupt Controller (NVIC)
+ __IO uint32_t ISER[8]; /*!< Offset: 0x000 Interrupt Set Enable Register */
+ uint32_t RESERVED0[24];
+ __IO uint32_t ICER[8]; /*!< Offset: 0x080 Interrupt Clear Enable Register */
+ uint32_t RSERVED1[24];
+ __IO uint32_t ISPR[8]; /*!< Offset: 0x100 Interrupt Set Pending Register */
+ uint32_t RESERVED2[24];
+ __IO uint32_t ICPR[8]; /*!< Offset: 0x180 Interrupt Clear Pending Register */
+ uint32_t RESERVED3[24];
+ __IO uint32_t IABR[8]; /*!< Offset: 0x200 Interrupt Active bit Register */
+ uint32_t RESERVED4[56];
+ __IO uint8_t IP[240]; /*!< Offset: 0x300 Interrupt Priority Register (8Bit wide) */
+ uint32_t RESERVED5[644];
+ __O uint32_t STIR; /*!< Offset: 0xE00 Software Trigger Interrupt Register */
+} NVIC_Type;
+/*@}*/ /* end of group CMSIS_CM3_NVIC */
+/** @addtogroup CMSIS_CM3_SCB CMSIS CM3 SCB
+ memory mapped structure for System Control Block (SCB)
+ __I uint32_t CPUID; /*!< Offset: 0x00 CPU ID Base Register */
+ __IO uint32_t ICSR; /*!< Offset: 0x04 Interrupt Control State Register */
+ __IO uint32_t VTOR; /*!< Offset: 0x08 Vector Table Offset Register */
+ __IO uint32_t AIRCR; /*!< Offset: 0x0C Application Interrupt / Reset Control Register */
+ __IO uint32_t SCR; /*!< Offset: 0x10 System Control Register */
+ __IO uint32_t CCR; /*!< Offset: 0x14 Configuration Control Register */
+ __IO uint8_t SHP[12]; /*!< Offset: 0x18 System Handlers Priority Registers (4-7, 8-11, 12-15) */
+ __IO uint32_t SHCSR; /*!< Offset: 0x24 System Handler Control and State Register */
+ __IO uint32_t CFSR; /*!< Offset: 0x28 Configurable Fault Status Register */
+ __IO uint32_t HFSR; /*!< Offset: 0x2C Hard Fault Status Register */
+ __IO uint32_t DFSR; /*!< Offset: 0x30 Debug Fault Status Register */
+ __IO uint32_t MMFAR; /*!< Offset: 0x34 Mem Manage Address Register */
+ __IO uint32_t BFAR; /*!< Offset: 0x38 Bus Fault Address Register */
+ __IO uint32_t AFSR; /*!< Offset: 0x3C Auxiliary Fault Status Register */
+ __I uint32_t PFR[2]; /*!< Offset: 0x40 Processor Feature Register */
+ __I uint32_t DFR; /*!< Offset: 0x48 Debug Feature Register */
+ __I uint32_t ADR; /*!< Offset: 0x4C Auxiliary Feature Register */
+ __I uint32_t MMFR[4]; /*!< Offset: 0x50 Memory Model Feature Register */
+ __I uint32_t ISAR[5]; /*!< Offset: 0x60 ISA Feature Register */
+} SCB_Type;
+/* SCB CPUID Register Definitions */
+#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */
+#define SCB_CPUID_IMPLEMENTER_Msk (0xFFul << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */
+#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */
+#define SCB_CPUID_VARIANT_Msk (0xFul << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */
+#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */
+#define SCB_CPUID_PARTNO_Msk (0xFFFul << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */
+#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */
+#define SCB_CPUID_REVISION_Msk (0xFul << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */
+/* SCB Interrupt Control State Register Definitions */
+#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */
+#define SCB_ICSR_NMIPENDSET_Msk (1ul << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */
+#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */
+#define SCB_ICSR_PENDSVSET_Msk (1ul << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */
+#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */
+#define SCB_ICSR_PENDSVCLR_Msk (1ul << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */
+#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */
+#define SCB_ICSR_PENDSTSET_Msk (1ul << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */
+#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */
+#define SCB_ICSR_PENDSTCLR_Msk (1ul << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */
+#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */
+#define SCB_ICSR_ISRPREEMPT_Msk (1ul << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */
+#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */
+#define SCB_ICSR_ISRPENDING_Msk (1ul << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */
+#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */
+#define SCB_ICSR_VECTPENDING_Msk (0x1FFul << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */
+#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */
+#define SCB_ICSR_RETTOBASE_Msk (1ul << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */
+#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */
+#define SCB_ICSR_VECTACTIVE_Msk (0x1FFul << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */
+#define SCB_VTOR_TBLBASE_Pos 29 /*!< SCB VTOR: TBLBASE Position */
+#define SCB_VTOR_TBLBASE_Msk (0x1FFul << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */
+#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */
+#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFul << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */
+/* SCB Application Interrupt and Reset Control Register Definitions */
+#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */
+#define SCB_AIRCR_VECTKEY_Msk (0xFFFFul << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */
+#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */
+#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFul << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */
+#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */
+#define SCB_AIRCR_ENDIANESS_Msk (1ul << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */
+#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */
+#define SCB_AIRCR_PRIGROUP_Msk (7ul << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */
+#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */
+#define SCB_AIRCR_SYSRESETREQ_Msk (1ul << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */
+#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */
+#define SCB_AIRCR_VECTCLRACTIVE_Msk (1ul << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */
+#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */
+#define SCB_AIRCR_VECTRESET_Msk (1ul << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */
+/* SCB System Control Register Definitions */
+#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */
+#define SCB_SCR_SEVONPEND_Msk (1ul << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */
+#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */
+#define SCB_SCR_SLEEPDEEP_Msk (1ul << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */
+#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */
+#define SCB_SCR_SLEEPONEXIT_Msk (1ul << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */
+/* SCB Configuration Control Register Definitions */
+#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */
+#define SCB_CCR_STKALIGN_Msk (1ul << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */
+#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */
+#define SCB_CCR_BFHFNMIGN_Msk (1ul << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */
+#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */
+#define SCB_CCR_DIV_0_TRP_Msk (1ul << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */
+#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */
+#define SCB_CCR_UNALIGN_TRP_Msk (1ul << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */
+#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */
+#define SCB_CCR_USERSETMPEND_Msk (1ul << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */
+#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */
+#define SCB_CCR_NONBASETHRDENA_Msk (1ul << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */
+/* SCB System Handler Control and State Register Definitions */
+#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */
+#define SCB_SHCSR_USGFAULTENA_Msk (1ul << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */
+#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */
+#define SCB_SHCSR_BUSFAULTENA_Msk (1ul << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */
+#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */
+#define SCB_SHCSR_MEMFAULTENA_Msk (1ul << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */
+#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */
+#define SCB_SHCSR_SVCALLPENDED_Msk (1ul << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */
+#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */
+#define SCB_SHCSR_BUSFAULTPENDED_Msk (1ul << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */
+#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */
+#define SCB_SHCSR_MEMFAULTPENDED_Msk (1ul << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */
+#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */
+#define SCB_SHCSR_USGFAULTPENDED_Msk (1ul << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */
+#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */
+#define SCB_SHCSR_SYSTICKACT_Msk (1ul << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */
+#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */
+#define SCB_SHCSR_PENDSVACT_Msk (1ul << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */
+#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */
+#define SCB_SHCSR_MONITORACT_Msk (1ul << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */
+#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */
+#define SCB_SHCSR_SVCALLACT_Msk (1ul << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */
+#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */
+#define SCB_SHCSR_USGFAULTACT_Msk (1ul << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */
+#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */
+#define SCB_SHCSR_BUSFAULTACT_Msk (1ul << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */
+#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */
+#define SCB_SHCSR_MEMFAULTACT_Msk (1ul << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */
+/* SCB Configurable Fault Status Registers Definitions */
+#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */
+#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFul << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */
+#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */
+#define SCB_CFSR_BUSFAULTSR_Msk (0xFFul << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */
+#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */
+#define SCB_CFSR_MEMFAULTSR_Msk (0xFFul << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */
+/* SCB Hard Fault Status Registers Definitions */
+#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */
+#define SCB_HFSR_DEBUGEVT_Msk (1ul << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */
+#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */
+#define SCB_HFSR_FORCED_Msk (1ul << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */
+#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */
+#define SCB_HFSR_VECTTBL_Msk (1ul << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */
+/* SCB Debug Fault Status Register Definitions */
+#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */
+#define SCB_DFSR_EXTERNAL_Msk (1ul << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */
+#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */
+#define SCB_DFSR_VCATCH_Msk (1ul << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */
+#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */
+#define SCB_DFSR_DWTTRAP_Msk (1ul << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */
+#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */
+#define SCB_DFSR_BKPT_Msk (1ul << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */
+#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */
+#define SCB_DFSR_HALTED_Msk (1ul << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */
+/*@}*/ /* end of group CMSIS_CM3_SCB */
+/** @addtogroup CMSIS_CM3_SysTick CMSIS CM3 SysTick
+ memory mapped structure for SysTick
+ __IO uint32_t CTRL; /*!< Offset: 0x00 SysTick Control and Status Register */
+ __IO uint32_t LOAD; /*!< Offset: 0x04 SysTick Reload Value Register */
+ __IO uint32_t VAL; /*!< Offset: 0x08 SysTick Current Value Register */
+ __I uint32_t CALIB; /*!< Offset: 0x0C SysTick Calibration Register */
+} SysTick_Type;
+/* SysTick Control / Status Register Definitions */
+#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */
+#define SysTick_CTRL_COUNTFLAG_Msk (1ul << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */
+#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */
+#define SysTick_CTRL_CLKSOURCE_Msk (1ul << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */
+#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */
+#define SysTick_CTRL_TICKINT_Msk (1ul << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */
+#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */
+#define SysTick_CTRL_ENABLE_Msk (1ul << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */
+/* SysTick Reload Register Definitions */
+#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */
+#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFul << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */
+/* SysTick Current Register Definitions */
+#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */
+#define SysTick_VAL_CURRENT_Msk (0xFFFFFFul << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */
+/* SysTick Calibration Register Definitions */
+#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */
+#define SysTick_CALIB_NOREF_Msk (1ul << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */
+#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */
+#define SysTick_CALIB_SKEW_Msk (1ul << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */
+#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */
+#define SysTick_CALIB_TENMS_Msk (0xFFFFFFul << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */
+/*@}*/ /* end of group CMSIS_CM3_SysTick */
+/** @addtogroup CMSIS_CM3_ITM CMSIS CM3 ITM
+ memory mapped structure for Instrumentation Trace Macrocell (ITM)
+ __O union
+ __O uint8_t u8; /*!< Offset: ITM Stimulus Port 8-bit */
+ __O uint16_t u16; /*!< Offset: ITM Stimulus Port 16-bit */
+ __O uint32_t u32; /*!< Offset: ITM Stimulus Port 32-bit */
+ } PORT [32]; /*!< Offset: 0x00 ITM Stimulus Port Registers */
+ uint32_t RESERVED0[864];
+ __IO uint32_t TER; /*!< Offset: ITM Trace Enable Register */
+ uint32_t RESERVED1[15];
+ __IO uint32_t TPR; /*!< Offset: ITM Trace Privilege Register */
+ uint32_t RESERVED2[15];
+ __IO uint32_t TCR; /*!< Offset: ITM Trace Control Register */
+ uint32_t RESERVED3[29];
+ __IO uint32_t IWR; /*!< Offset: ITM Integration Write Register */
+ __IO uint32_t IRR; /*!< Offset: ITM Integration Read Register */
+ __IO uint32_t IMCR; /*!< Offset: ITM Integration Mode Control Register */
+ uint32_t RESERVED4[43];
+ __IO uint32_t LAR; /*!< Offset: ITM Lock Access Register */
+ __IO uint32_t LSR; /*!< Offset: ITM Lock Status Register */
+ uint32_t RESERVED5[6];
+ __I uint32_t PID4; /*!< Offset: ITM Peripheral Identification Register #4 */
+ __I uint32_t PID5; /*!< Offset: ITM Peripheral Identification Register #5 */
+ __I uint32_t PID6; /*!< Offset: ITM Peripheral Identification Register #6 */
+ __I uint32_t PID7; /*!< Offset: ITM Peripheral Identification Register #7 */
+ __I uint32_t PID0; /*!< Offset: ITM Peripheral Identification Register #0 */
+ __I uint32_t PID1; /*!< Offset: ITM Peripheral Identification Register #1 */
+ __I uint32_t PID2; /*!< Offset: ITM Peripheral Identification Register #2 */
+ __I uint32_t PID3; /*!< Offset: ITM Peripheral Identification Register #3 */
+ __I uint32_t CID0; /*!< Offset: ITM Component Identification Register #0 */
+ __I uint32_t CID1; /*!< Offset: ITM Component Identification Register #1 */
+ __I uint32_t CID2; /*!< Offset: ITM Component Identification Register #2 */
+ __I uint32_t CID3; /*!< Offset: ITM Component Identification Register #3 */
+} ITM_Type;
+/* ITM Trace Privilege Register Definitions */
+#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */
+#define ITM_TPR_PRIVMASK_Msk (0xFul << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */
+/* ITM Trace Control Register Definitions */
+#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */
+#define ITM_TCR_BUSY_Msk (1ul << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */
+#define ITM_TCR_ATBID_Pos 16 /*!< ITM TCR: ATBID Position */
+#define ITM_TCR_ATBID_Msk (0x7Ful << ITM_TCR_ATBID_Pos) /*!< ITM TCR: ATBID Mask */
+#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */
+#define ITM_TCR_TSPrescale_Msk (3ul << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */
+#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */
+#define ITM_TCR_SWOENA_Msk (1ul << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */
+#define ITM_TCR_DWTENA_Pos 3 /*!< ITM TCR: DWTENA Position */
+#define ITM_TCR_DWTENA_Msk (1ul << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */
+#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */
+#define ITM_TCR_SYNCENA_Msk (1ul << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */
+#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */
+#define ITM_TCR_TSENA_Msk (1ul << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */
+#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */
+#define ITM_TCR_ITMENA_Msk (1ul << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */
+/* ITM Integration Write Register Definitions */
+#define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */
+#define ITM_IWR_ATVALIDM_Msk (1ul << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */
+/* ITM Integration Read Register Definitions */
+#define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */
+#define ITM_IRR_ATREADYM_Msk (1ul << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */
+/* ITM Integration Mode Control Register Definitions */
+#define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */
+#define ITM_IMCR_INTEGRATION_Msk (1ul << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */
+/* ITM Lock Status Register Definitions */
+#define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */
+#define ITM_LSR_ByteAcc_Msk (1ul << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */
+#define ITM_LSR_Access_Pos 1 /*!< ITM LSR: Access Position */
+#define ITM_LSR_Access_Msk (1ul << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */
+#define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */
+#define ITM_LSR_Present_Msk (1ul << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */
+/*@}*/ /* end of group CMSIS_CM3_ITM */
+/** @addtogroup CMSIS_CM3_InterruptType CMSIS CM3 Interrupt Type
+ memory mapped structure for Interrupt Type
+ uint32_t RESERVED0;
+ __I uint32_t ICTR; /*!< Offset: 0x04 Interrupt Control Type Register */
+#if ((defined __CM3_REV) && (__CM3_REV >= 0x200))
+ __IO uint32_t ACTLR; /*!< Offset: 0x08 Auxiliary Control Register */
+ uint32_t RESERVED1;
+} InterruptType_Type;
+/* Interrupt Controller Type Register Definitions */
+#define InterruptType_ICTR_INTLINESNUM_Pos 0 /*!< InterruptType ICTR: INTLINESNUM Position */
+#define InterruptType_ICTR_INTLINESNUM_Msk (0x1Ful << InterruptType_ICTR_INTLINESNUM_Pos) /*!< InterruptType ICTR: INTLINESNUM Mask */
+/* Auxiliary Control Register Definitions */
+#define InterruptType_ACTLR_DISFOLD_Pos 2 /*!< InterruptType ACTLR: DISFOLD Position */
+#define InterruptType_ACTLR_DISFOLD_Msk (1ul << InterruptType_ACTLR_DISFOLD_Pos) /*!< InterruptType ACTLR: DISFOLD Mask */
+#define InterruptType_ACTLR_DISDEFWBUF_Pos 1 /*!< InterruptType ACTLR: DISDEFWBUF Position */
+#define InterruptType_ACTLR_DISDEFWBUF_Msk (1ul << InterruptType_ACTLR_DISDEFWBUF_Pos) /*!< InterruptType ACTLR: DISDEFWBUF Mask */
+#define InterruptType_ACTLR_DISMCYCINT_Pos 0 /*!< InterruptType ACTLR: DISMCYCINT Position */
+#define InterruptType_ACTLR_DISMCYCINT_Msk (1ul << InterruptType_ACTLR_DISMCYCINT_Pos) /*!< InterruptType ACTLR: DISMCYCINT Mask */
+/*@}*/ /* end of group CMSIS_CM3_InterruptType */
+#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1)
+/** @addtogroup CMSIS_CM3_MPU CMSIS CM3 MPU
+ memory mapped structure for Memory Protection Unit (MPU)
+ __I uint32_t TYPE; /*!< Offset: 0x00 MPU Type Register */
+ __IO uint32_t CTRL; /*!< Offset: 0x04 MPU Control Register */
+ __IO uint32_t RNR; /*!< Offset: 0x08 MPU Region RNRber Register */
+ __IO uint32_t RBAR; /*!< Offset: 0x0C MPU Region Base Address Register */
+ __IO uint32_t RASR; /*!< Offset: 0x10 MPU Region Attribute and Size Register */
+ __IO uint32_t RBAR_A1; /*!< Offset: 0x14 MPU Alias 1 Region Base Address Register */
+ __IO uint32_t RASR_A1; /*!< Offset: 0x18 MPU Alias 1 Region Attribute and Size Register */
+ __IO uint32_t RBAR_A2; /*!< Offset: 0x1C MPU Alias 2 Region Base Address Register */
+ __IO uint32_t RASR_A2; /*!< Offset: 0x20 MPU Alias 2 Region Attribute and Size Register */
+ __IO uint32_t RBAR_A3; /*!< Offset: 0x24 MPU Alias 3 Region Base Address Register */
+ __IO uint32_t RASR_A3; /*!< Offset: 0x28 MPU Alias 3 Region Attribute and Size Register */
+} MPU_Type;
+/* MPU Type Register */
+#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */
+#define MPU_TYPE_IREGION_Msk (0xFFul << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */
+#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */
+#define MPU_TYPE_DREGION_Msk (0xFFul << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */
+#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */
+#define MPU_TYPE_SEPARATE_Msk (1ul << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */
+/* MPU Control Register */
+#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */
+#define MPU_CTRL_PRIVDEFENA_Msk (1ul << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */
+#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */
+#define MPU_CTRL_HFNMIENA_Msk (1ul << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */
+#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */
+#define MPU_CTRL_ENABLE_Msk (1ul << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */
+/* MPU Region Number Register */
+#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */
+#define MPU_RNR_REGION_Msk (0xFFul << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */
+/* MPU Region Base Address Register */
+#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */
+#define MPU_RBAR_ADDR_Msk (0x7FFFFFFul << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */
+#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */
+#define MPU_RBAR_VALID_Msk (1ul << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */
+#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */
+#define MPU_RBAR_REGION_Msk (0xFul << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */
+/* MPU Region Attribute and Size Register */
+#define MPU_RASR_XN_Pos 28 /*!< MPU RASR: XN Position */
+#define MPU_RASR_XN_Msk (1ul << MPU_RASR_XN_Pos) /*!< MPU RASR: XN Mask */
+#define MPU_RASR_AP_Pos 24 /*!< MPU RASR: AP Position */
+#define MPU_RASR_AP_Msk (7ul << MPU_RASR_AP_Pos) /*!< MPU RASR: AP Mask */
+#define MPU_RASR_TEX_Pos 19 /*!< MPU RASR: TEX Position */
+#define MPU_RASR_TEX_Msk (7ul << MPU_RASR_TEX_Pos) /*!< MPU RASR: TEX Mask */
+#define MPU_RASR_S_Pos 18 /*!< MPU RASR: Shareable bit Position */
+#define MPU_RASR_S_Msk (1ul << MPU_RASR_S_Pos) /*!< MPU RASR: Shareable bit Mask */
+#define MPU_RASR_C_Pos 17 /*!< MPU RASR: Cacheable bit Position */
+#define MPU_RASR_C_Msk (1ul << MPU_RASR_C_Pos) /*!< MPU RASR: Cacheable bit Mask */
+#define MPU_RASR_B_Pos 16 /*!< MPU RASR: Bufferable bit Position */
+#define MPU_RASR_B_Msk (1ul << MPU_RASR_B_Pos) /*!< MPU RASR: Bufferable bit Mask */
+#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */
+#define MPU_RASR_SRD_Msk (0xFFul << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */
+#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */
+#define MPU_RASR_SIZE_Msk (0x1Ful << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */
+#define MPU_RASR_ENA_Pos 0 /*!< MPU RASR: Region enable bit Position */
+#define MPU_RASR_ENA_Msk (0x1Ful << MPU_RASR_ENA_Pos) /*!< MPU RASR: Region enable bit Disable Mask */
+/*@}*/ /* end of group CMSIS_CM3_MPU */
+/** @addtogroup CMSIS_CM3_CoreDebug CMSIS CM3 Core Debug
+ memory mapped structure for Core Debug Register
+ __IO uint32_t DHCSR; /*!< Offset: 0x00 Debug Halting Control and Status Register */
+ __O uint32_t DCRSR; /*!< Offset: 0x04 Debug Core Register Selector Register */
+ __IO uint32_t DCRDR; /*!< Offset: 0x08 Debug Core Register Data Register */
+ __IO uint32_t DEMCR; /*!< Offset: 0x0C Debug Exception and Monitor Control Register */
+} CoreDebug_Type;
+/* Debug Halting Control and Status Register */
+#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */
+#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFul << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */
+#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */
+#define CoreDebug_DHCSR_S_RESET_ST_Msk (1ul << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */
+#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */
+#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1ul << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */
+#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */
+#define CoreDebug_DHCSR_S_LOCKUP_Msk (1ul << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */
+#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */
+#define CoreDebug_DHCSR_S_SLEEP_Msk (1ul << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */
+#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */
+#define CoreDebug_DHCSR_S_HALT_Msk (1ul << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */
+#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */
+#define CoreDebug_DHCSR_S_REGRDY_Msk (1ul << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */
+#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */
+#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1ul << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */
+#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */
+#define CoreDebug_DHCSR_C_MASKINTS_Msk (1ul << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */
+#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */
+#define CoreDebug_DHCSR_C_STEP_Msk (1ul << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */
+#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */
+#define CoreDebug_DHCSR_C_HALT_Msk (1ul << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */
+#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */
+#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1ul << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */
+/* Debug Core Register Selector Register */
+#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */
+#define CoreDebug_DCRSR_REGWnR_Msk (1ul << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */
+#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */
+#define CoreDebug_DCRSR_REGSEL_Msk (0x1Ful << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */
+/* Debug Exception and Monitor Control Register */
+#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */
+#define CoreDebug_DEMCR_TRCENA_Msk (1ul << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */
+#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */
+#define CoreDebug_DEMCR_MON_REQ_Msk (1ul << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */
+#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */
+#define CoreDebug_DEMCR_MON_STEP_Msk (1ul << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */
+#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */
+#define CoreDebug_DEMCR_MON_PEND_Msk (1ul << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */
+#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */
+#define CoreDebug_DEMCR_MON_EN_Msk (1ul << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */
+#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */
+#define CoreDebug_DEMCR_VC_HARDERR_Msk (1ul << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */
+#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */
+#define CoreDebug_DEMCR_VC_INTERR_Msk (1ul << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */
+#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */
+#define CoreDebug_DEMCR_VC_BUSERR_Msk (1ul << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */
+#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */
+#define CoreDebug_DEMCR_VC_STATERR_Msk (1ul << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */
+#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */
+#define CoreDebug_DEMCR_VC_CHKERR_Msk (1ul << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */
+#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */
+#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1ul << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */
+#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */
+#define CoreDebug_DEMCR_VC_MMERR_Msk (1ul << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */
+#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */
+#define CoreDebug_DEMCR_VC_CORERESET_Msk (1ul << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */
+/*@}*/ /* end of group CMSIS_CM3_CoreDebug */
+/* Memory mapping of Cortex-M3 Hardware */
+#define SCS_BASE (0xE000E000) /*!< System Control Space Base Address */
+#define ITM_BASE (0xE0000000) /*!< ITM Base Address */
+#define CoreDebug_BASE (0xE000EDF0) /*!< Core Debug Base Address */
+#define SysTick_BASE (SCS_BASE + 0x0010) /*!< SysTick Base Address */
+#define NVIC_BASE (SCS_BASE + 0x0100) /*!< NVIC Base Address */
+#define SCB_BASE (SCS_BASE + 0x0D00) /*!< System Control Block Base Address */
+#define InterruptType ((InterruptType_Type *) SCS_BASE) /*!< Interrupt Type Register */
+#define SCB ((SCB_Type *) SCB_BASE) /*!< SCB configuration struct */
+#define SysTick ((SysTick_Type *) SysTick_BASE) /*!< SysTick configuration struct */
+#define NVIC ((NVIC_Type *) NVIC_BASE) /*!< NVIC configuration struct */
+#define ITM ((ITM_Type *) ITM_BASE) /*!< ITM configuration struct */
+#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */
+ #define MPU_BASE (SCS_BASE + 0x0D90) /*!< Memory Protection Unit */
+ #define MPU ((MPU_Type*) MPU_BASE) /*!< Memory Protection Unit */
+/*@}*/ /* end of group CMSIS_CM3_core_register */
+ * Hardware Abstraction Layer
+#define __enable_fault_irq __enable_fiq
+#define __disable_fault_irq __disable_fiq
+#define __NOP __nop
+#define __WFI __wfi
+#define __WFE __wfe
+#define __SEV __sev
+#define __ISB() __isb(0)
+#define __DSB() __dsb(0)
+#define __DMB() __dmb(0)
+#define __REV __rev
+#define __RBIT __rbit
+#define __LDREXB(ptr) ((unsigned char ) __ldrex(ptr))
+#define __LDREXH(ptr) ((unsigned short) __ldrex(ptr))
+#define __LDREXW(ptr) ((unsigned int ) __ldrex(ptr))
+#define __STREXB(value, ptr) __strex(value, ptr)
+#define __STREXH(value, ptr) __strex(value, ptr)
+#define __STREXW(value, ptr) __strex(value, ptr)
+/* intrinsic unsigned long long __ldrexd(volatile void *ptr) */
+/* intrinsic int __strexd(unsigned long long val, volatile void *ptr) */
+/* intrinsic void __enable_irq(); */
+/* intrinsic void __disable_irq(); */
+extern uint32_t __get_PSP(void);
+extern void __set_PSP(uint32_t topOfProcStack);
+extern uint32_t __get_MSP(void);
+extern void __set_MSP(uint32_t topOfMainStack);
+extern uint32_t __REV16(uint16_t value);
+extern int32_t __REVSH(int16_t value);
+extern void __CLREX(void);
+extern uint32_t __get_BASEPRI(void);
+extern void __set_BASEPRI(uint32_t basePri);
+extern uint32_t __get_PRIMASK(void);
+extern void __set_PRIMASK(uint32_t priMask);
+extern uint32_t __get_FAULTMASK(void);
+extern void __set_FAULTMASK(uint32_t faultMask);
+extern uint32_t __get_CONTROL(void);
+extern void __set_CONTROL(uint32_t control);
+#else /* (__ARMCC_VERSION >= 400000) */
+#define __CLREX __clrex
+static __INLINE uint32_t __get_BASEPRI(void)
+ register uint32_t __regBasePri __ASM("basepri");
+ return(__regBasePri);
+static __INLINE void __set_BASEPRI(uint32_t basePri)
+ __regBasePri = (basePri & 0xff);
+static __INLINE uint32_t __get_PRIMASK(void)
+ register uint32_t __regPriMask __ASM("primask");
+ return(__regPriMask);
+static __INLINE void __set_PRIMASK(uint32_t priMask)
+ __regPriMask = (priMask);
+static __INLINE uint32_t __get_FAULTMASK(void)
+ register uint32_t __regFaultMask __ASM("faultmask");
+ return(__regFaultMask);
+static __INLINE void __set_FAULTMASK(uint32_t faultMask)
+ __regFaultMask = (faultMask & 1);
+static __INLINE uint32_t __get_CONTROL(void)
+ register uint32_t __regControl __ASM("control");
+ return(__regControl);
+static __INLINE void __set_CONTROL(uint32_t control)
+ __regControl = control;
+#define __enable_irq __enable_interrupt /*!< global Interrupt enable */
+#define __disable_irq __disable_interrupt /*!< global Interrupt disable */
+static __INLINE void __enable_fault_irq() { __ASM ("cpsie f"); }
+static __INLINE void __disable_fault_irq() { __ASM ("cpsid f"); }
+#define __NOP __no_operation /*!< no operation intrinsic in IAR Compiler */
+static __INLINE void __WFI() { __ASM ("wfi"); }
+static __INLINE void __WFE() { __ASM ("wfe"); }
+static __INLINE void __SEV() { __ASM ("sev"); }
+static __INLINE void __CLREX() { __ASM ("clrex"); }
+/* intrinsic void __ISB(void) */
+/* intrinsic void __DSB(void) */
+/* intrinsic void __DMB(void) */
+/* intrinsic void __set_PRIMASK(); */
+/* intrinsic void __get_PRIMASK(); */
+/* intrinsic void __set_FAULTMASK(); */
+/* intrinsic void __get_FAULTMASK(); */
+/* intrinsic uint32_t __REV(uint32_t value); */
+/* intrinsic uint32_t __REVSH(uint32_t value); */
+/* intrinsic unsigned long __STREX(unsigned long, unsigned long); */
+/* intrinsic unsigned long __LDREX(unsigned long *); */
+extern uint32_t __RBIT(uint32_t value);
+extern uint8_t __LDREXB(uint8_t *addr);
+extern uint16_t __LDREXH(uint16_t *addr);
+extern uint32_t __LDREXW(uint32_t *addr);
+extern uint32_t __STREXB(uint8_t value, uint8_t *addr);
+extern uint32_t __STREXH(uint16_t value, uint16_t *addr);
+extern uint32_t __STREXW(uint32_t value, uint32_t *addr);
+static __INLINE void __enable_irq(void) { __ASM volatile ("cpsie i"); }
+static __INLINE void __disable_irq(void) { __ASM volatile ("cpsid i"); }
+static __INLINE void __enable_fault_irq(void) { __ASM volatile ("cpsie f"); }
+static __INLINE void __disable_fault_irq(void) { __ASM volatile ("cpsid f"); }
+static __INLINE void __NOP(void) { __ASM volatile ("nop"); }
+static __INLINE void __WFI(void) { __ASM volatile ("wfi"); }
+static __INLINE void __WFE(void) { __ASM volatile ("wfe"); }
+static __INLINE void __SEV(void) { __ASM volatile ("sev"); }
+static __INLINE void __ISB(void) { __ASM volatile ("isb"); }
+static __INLINE void __DSB(void) { __ASM volatile ("dsb"); }
+static __INLINE void __DMB(void) { __ASM volatile ("dmb"); }
+static __INLINE void __CLREX(void) { __ASM volatile ("clrex"); }
+extern uint32_t __REV(uint32_t value);
+/** @addtogroup CMSIS_CM3_Core_FunctionInterface CMSIS CM3 Core Function Interface
+ Core Function Interface containing:
+ - Core NVIC Functions
+ - Core SysTick Functions
+ - Core Reset Functions
+/*@{*/
+/* ########################## NVIC functions #################################### */
+ * @brief Set the Priority Grouping in NVIC Interrupt Controller
+ * @param PriorityGroup is priority grouping field
+ * Set the priority grouping field using the required unlock sequence.
+ * The parameter priority_grouping is assigned to the field
+ * SCB->AIRCR [10:8] PRIGROUP field. Only values from 0..7 are used.
+ * In case of a conflict between priority grouping and available
+ * priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set.
+static __INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup)
+ uint32_t reg_value;
+ uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */
+ reg_value = SCB->AIRCR; /* read old register configuration */
+ reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */
+ reg_value = (reg_value |
+ (0x5FA << SCB_AIRCR_VECTKEY_Pos) |
+ (PriorityGroupTmp << 8)); /* Insert write key and priorty group */
+ SCB->AIRCR = reg_value;
+ * @brief Get the Priority Grouping from NVIC Interrupt Controller
+ * @return priority grouping field
+ * Get the priority grouping from NVIC Interrupt Controller.
+ * priority grouping is SCB->AIRCR [10:8] PRIGROUP field.
+static __INLINE uint32_t NVIC_GetPriorityGrouping(void)
+ return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */
+ * @brief Enable Interrupt in NVIC Interrupt Controller
+ * @param IRQn The positive number of the external interrupt to enable
+ * Enable a device specific interupt in the NVIC interrupt controller.
+ * The interrupt number cannot be a negative value.
+static __INLINE void NVIC_EnableIRQ(IRQn_Type IRQn)
+ NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* enable interrupt */
+ * @brief Disable the interrupt line for external interrupt specified
+ * @param IRQn The positive number of the external interrupt to disable
+ * Disable a device specific interupt in the NVIC interrupt controller.
+static __INLINE void NVIC_DisableIRQ(IRQn_Type IRQn)
+ NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */
+ * @brief Read the interrupt pending bit for a device specific interrupt source
+ * @param IRQn The number of the device specifc interrupt
+ * @return 1 = interrupt pending, 0 = interrupt not pending
+ * Read the pending register in NVIC and return 1 if its status is pending,
+ * otherwise it returns 0
+static __INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn)
+ return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */
+ * @brief Set the pending bit for an external interrupt
+ * @param IRQn The number of the interrupt for set pending
+ * Set the pending bit for the specified interrupt.
+static __INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn)
+ NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */
+ * @brief Clear the pending bit for an external interrupt
+ * @param IRQn The number of the interrupt for clear pending
+ * Clear the pending bit for the specified interrupt.
+static __INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn)
+ NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */
+ * @brief Read the active bit for an external interrupt
+ * @param IRQn The number of the interrupt for read active bit
+ * @return 1 = interrupt active, 0 = interrupt not active
+ * Read the active register in NVIC and returns 1 if its status is active,
+ * otherwise it returns 0.
+static __INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn)
+ return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */
+ * @brief Set the priority for an interrupt
+ * @param IRQn The number of the interrupt for set priority
+ * @param priority The priority to set
+ * Set the priority for the specified interrupt. The interrupt
+ * number can be positive to specify an external (device specific)
+ * interrupt, or negative to specify an internal (core) interrupt.
+ * Note: The priority cannot be set for every core interrupt.
+static __INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority)
+ if(IRQn < 0) {
+ SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M3 System Interrupts */
+ else {
+ NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */
+ * @brief Read the priority for an interrupt
+ * @param IRQn The number of the interrupt for get priority
+ * @return The priority for the interrupt
+ * Read the priority for the specified interrupt. The interrupt
+ * The returned priority value is automatically aligned to the implemented
+ * priority bits of the microcontroller.
+static __INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn)
+ return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M3 system interrupts */
+ return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */
+ * @brief Encode the priority for an interrupt
+ * @param PriorityGroup The used priority group
+ * @param PreemptPriority The preemptive priority value (starting from 0)
+ * @param SubPriority The sub priority value (starting from 0)
+ * @return The encoded priority for the interrupt
+ * Encode the priority for an interrupt with the given priority group,
+ * preemptive priority value and sub priority value.
+ * priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set.
+ * The returned priority value can be used for NVIC_SetPriority(...) function
+static __INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority)
+ uint32_t PreemptPriorityBits;
+ uint32_t SubPriorityBits;
+ PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;
+ SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;
+ return (
+ ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) |
+ ((SubPriority & ((1 << (SubPriorityBits )) - 1)))
+ );
+ * @brief Decode the priority of an interrupt
+ * @param Priority The priority for the interrupt
+ * @param pPreemptPriority The preemptive priority value (starting from 0)
+ * @param pSubPriority The sub priority value (starting from 0)
+ * Decode an interrupt priority value with the given priority group to
+ * The priority value can be retrieved with NVIC_GetPriority(...) function
+static __INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority)
+ *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1);
+ *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1);
+/* ################################## SysTick function ############################################ */
+#if (!defined (__Vendor_SysTickConfig)) || (__Vendor_SysTickConfig == 0)
+ * @brief Initialize and start the SysTick counter and its interrupt.
+ * @param ticks number of ticks between two interrupts
+ * @return 1 = failed, 0 = successful
+ * Initialise the system tick timer and its interrupt and start the
+ * system tick timer / counter in free running mode to generate
+ * periodical interrupts.
+static __INLINE uint32_t SysTick_Config(uint32_t ticks)
+ if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */
+ SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */
+ NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Cortex-M0 System Interrupts */
+ SysTick->VAL = 0; /* Load the SysTick Counter Value */
+ SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
+ SysTick_CTRL_TICKINT_Msk |
+ SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */
+ return (0); /* Function successful */
+/* ################################## Reset function ############################################ */
+ * @brief Initiate a system reset request.
+ * Initiate a system reset request to reset the MCU
+static __INLINE void NVIC_SystemReset(void)
+ SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) |
+ (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) |
+ SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */
+ __DSB(); /* Ensure completion of memory access */
+ while(1); /* wait until reset */
+/*@}*/ /* end of group CMSIS_CM3_Core_FunctionInterface */
+/* ##################################### Debug In/Output function ########################################### */
+/** @addtogroup CMSIS_CM3_CoreDebugInterface CMSIS CM3 Core Debug Interface
+ Core Debug Interface containing:
+ - Core Debug Receive / Transmit Functions
+ - Core Debug Defines
+ - Core Debug Variables
+extern volatile int ITM_RxBuffer; /*!< variable to receive characters */
+#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< value identifying ITM_RxBuffer is ready for next character */
+ * @brief Outputs a character via the ITM channel 0
+ * @param ch character to output
+ * @return character to output
+ * The function outputs a character via the ITM channel 0.
+ * The function returns when no debugger is connected that has booked the output.
+ * It is blocking when a debugger is connected, but the previous character send is not transmitted.
+static __INLINE uint32_t ITM_SendChar (uint32_t ch)
+ if ((CoreDebug->DEMCR & CoreDebug_DEMCR_TRCENA_Msk) && /* Trace enabled */
+ (ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */
+ (ITM->TER & (1ul << 0) ) ) /* ITM Port #0 enabled */
+ while (ITM->PORT[0].u32 == 0);
+ ITM->PORT[0].u8 = (uint8_t) ch;
+ return (ch);
+ * @brief Inputs a character via variable ITM_RxBuffer
+ * @return received character, -1 = no character received
+ * The function inputs a character via variable ITM_RxBuffer.
+static __INLINE int ITM_ReceiveChar (void) {
+ int ch = -1; /* no character available */
+ if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) {
+ ch = ITM_RxBuffer;
+ ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */
+ * @brief Check if a character via variable ITM_RxBuffer is available
+ * @return 1 = character available, 0 = no character available
+ * The function checks variable ITM_RxBuffer whether a character is available or not.
+ * The function returns '1' if a character is available and '0' if no character is available.
+static __INLINE int ITM_CheckChar (void) {
+ if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) {
+ return (0); /* no character available */
+ } else {
+ return (1); /* character available */
+/*@}*/ /* end of group CMSIS_CM3_core_DebugInterface */
+/*@}*/ /* end of group CMSIS_CM3_core_definitions */
+#endif /* __CM3_CORE_H__ */
+/*lint -restore */
@@ -0,0 +1,113 @@
+ * (c) Copyright 2011-2013 Microsemi SoC Products Group. All rights reserved.
+ * SmartFusion2 Cortex Microcontroller Software Interface - Peripheral
+ * Access Layer.
+ * This file provides interfaces to perform register and register bit level
+ * read / write operations. These interfaces support bit-banding in case of
+ * Cortex-M3 CPU.
+ * SVN $Revision: 5263 $
+ * SVN $Date: 2013-03-21 14:44:58 +0000 (Thu, 21 Mar 2013) $
+#ifndef HW_REG_IO_H_
+#define HW_REG_IO_H_
+/*****************************************************************************************
+ * Definitions for register access
+#define HW_REG(addr) (*((volatile uint32_t *) (addr)))
+static __INLINE void write_reg32(volatile uint32_t * reg, uint32_t val)
+ HW_REG(reg) = val;
+static __INLINE void write_reg16(volatile uint16_t * reg, uint16_t val)
+static __INLINE void write_reg8(volatile uint8_t * reg, uint8_t val)
+static __INLINE uint32_t read_reg32(volatile uint32_t * reg)
+ return ( HW_REG(reg) );
+static __INLINE uint16_t read_reg16(volatile uint16_t * reg)
+static __INLINE uint8_t read_reg8(volatile uint8_t * reg)
+ * Definitions for register bits access using bit-band aliases for Cortex-M3
+#define BITBAND(addr,bitnum) (((uint32_t)addr & 0xF0000000)+0x02000000+(((uint32_t)addr & 0xFFFFF)<<5)+(bitnum<<2))
+#define HW_REG_BIT(reg,bitnum) (*(volatile unsigned int *)((BITBAND(reg,bitnum))))
+ * Functions to set a bit field in Cortex-M3
+static __INLINE void set_bit_reg32(volatile uint32_t * reg, uint8_t bit)
+ HW_REG_BIT(reg,bit) = 0x1;
+static __INLINE void set_bit_reg16(volatile uint16_t * reg, uint8_t bit)
+static __INLINE void set_bit_reg8(volatile uint8_t * reg, uint8_t bit)
+ * Functions to clear a bit field in Cortex-M3
+static __INLINE void clear_bit_reg32(volatile uint32_t * reg, uint8_t bit)
+ HW_REG_BIT(reg,bit) = 0x0;
+static __INLINE void clear_bit_reg16(volatile uint16_t * reg, uint8_t bit)
+static __INLINE void clear_bit_reg8(volatile uint8_t * reg, uint8_t bit)
+ * Functions to read a bit field in Cortex-M3
+static __INLINE uint8_t read_bit_reg32(volatile uint32_t * reg, uint8_t bit)
+ return (HW_REG_BIT(reg,bit));
+static __INLINE uint8_t read_bit_reg16(volatile uint16_t * reg, uint8_t bit)
+static __INLINE uint8_t read_bit_reg8(volatile uint8_t * reg, uint8_t bit)
+#endif /* HW_REG_IO_H_ */
@@ -0,0 +1,2826 @@
+ * (c) Copyright 2010-2013 Microsemi SoC Products Group. All rights reserved.
+ * Microsemi SmartFusion2 Cortex Microcontroller Software Interface - Peripheral
+ * This file describes the interrupt assignment and peripheral registers for
+ * the SmartFusion2 familly of devices.
+ * SVN $Revision: 6526 $
+ * SVN $Date: 2014-06-05 16:07:40 +0100 (Thu, 05 Jun 2014) $
+#ifndef __SMARTFUSION2_CMSIS_PAL_H__
+#define __SMARTFUSION2_CMSIS_PAL_H__
+ * ==========================================================================
+ * ---------- Interrupt Number Definition -----------------------------------
+typedef enum IRQn
+/****** Cortex-M3 Processor Exceptions Numbers *********************************************************/
+ NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt - Watchdog timeout interrupt*/
+ HardFault_IRQn = -13, /*!< 2 Hard Fault Interrupt */
+ MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */
+ BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */
+ UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */
+ SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */
+ DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */
+ PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */
+ SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */
+/****** SmartFusion2 specific Interrupt Numbers *********************************************************/
+ WdogWakeup_IRQn = 0, /*!< WatchDog wakeup interrupt */
+ RTC_Wakeup_IRQn = 1, /*!< RTC wakeup interrupt */
+ SPI0_IRQn = 2, /*!< SPI0 interrupt */
+ SPI1_IRQn = 3, /*!< SPI1 interrupt */
+ I2C0_IRQn = 4, /*!< I2C0 interrupt */
+ I2C0_SMBAlert_IRQn = 5, /*!< I2C0 SMBus Alert interrupt */
+ I2C0_SMBus_IRQn = 6, /*!< I2C0 SMBus Suspend interrupt */
+ I2C1_IRQn = 7, /*!< I2C1 interrupt */
+ I2C1_SMBAlert_IRQn = 8, /*!< I2C1 SMBus Alert interrupt */
+ I2C1_SMBus_IRQn = 9, /*!< I2C1 SMBus Suspend interrupt */
+ UART0_IRQn = 10, /*!< UART0 interrupt */
+ UART1_IRQn = 11, /*!< UART1 interrupt */
+ EthernetMAC_IRQn = 12, /*!< Ethernet MAC interrupt */
+ DMA_IRQn = 13, /*!< Peripheral DMA interrupt */
+ Timer1_IRQn = 14, /*!< Timer1 interrupt */
+ Timer2_IRQn = 15, /*!< Timer2 interrupt */
+ CAN_IRQn = 16, /*!< CAN controller interrupt */
+ ENVM0_IRQn = 17, /*!< eNVM0 operation completion interrupt */
+ ENVM1_IRQn = 18, /*!< eNVM1 operation completion interrupt */
+ ComBlk_IRQn = 19, /*!< COM block interrupt */
+ USB_IRQn = 20, /*!< USB interrupt */
+ USB_DMA_IRQn = 21, /*!< USB DMA interrupt */
+ PLL_Lock_IRQn = 22, /*!< PLL lock interrupt */
+ PLL_LockLost_IRQn = 23, /*!< PLL loss of lock interrupt */
+ CommSwitchError_IR = 24, /*!< Communications Switch error interrupt */
+ CacheError_IRQn = 25, /*!< Cache error interrupt */
+ DDR_IRQn = 26, /*!< DDR controller interrupt */
+ HPDMA_Complete_IRQn = 27, /*!< High speed DMA transfer complete interrupt */
+ HPDMA_Error_IRQn = 28, /*!< High speed DMA transfer error interrupt */
+ ECC_Error_IRQn = 29, /*!< ECC error detected */
+ MDDR_IOCalib_IRQn = 30, /*!< MDDR Calibration finished interrupt */
+ FAB_PLL_Lock_IRQn = 31, /*!< MSSDDR Fabric PLL lock interrupt */
+ FAB_PLL_LockLost_IRQn = 32, /*!< MSSDDR Fabric PLL lock lost interrupt */
+ FIC64_IRQn = 33, /*!< FIC64 interrupt */
+ FabricIrq0_IRQn = 34, /*!< FPGA fabric interrupt 0 */
+ FabricIrq1_IRQn = 35, /*!< FPGA fabric interrupt 1 */
+ FabricIrq2_IRQn = 36, /*!< FPGA fabric interrupt 2 */
+ FabricIrq3_IRQn = 37, /*!< FPGA fabric interrupt 3 */
+ FabricIrq4_IRQn = 38, /*!< FPGA fabric interrupt 4 */
+ FabricIrq5_IRQn = 39, /*!< FPGA fabric interrupt 5 */
+ FabricIrq6_IRQn = 40, /*!< FPGA fabric interrupt 6 */
+ FabricIrq7_IRQn = 41, /*!< FPGA fabric interrupt 7 */
+ FabricIrq8_IRQn = 42, /*!< FPGA fabric interrupt 8 */
+ FabricIrq9_IRQn = 43, /*!< FPGA fabric interrupt 9 */
+ FabricIrq10_IRQn = 44, /*!< FPGA fabric interrupt 10 */
+ FabricIrq11_IRQn = 45, /*!< FPGA fabric interrupt 11 */
+ FabricIrq12_IRQn = 46, /*!< FPGA fabric interrupt 12 */
+ FabricIrq13_IRQn = 47, /*!< FPGA fabric interrupt 13 */
+ FabricIrq14_IRQn = 48, /*!< FPGA fabric interrupt 14 */
+ FabricIrq15_IRQn = 49, /*!< FPGA fabric interrupt 15 */
+ GPIO0_IRQn = 50, /*!< GPIO 0 interrupt */
+ GPIO1_IRQn = 51, /*!< GPIO 1 interrupt */
+ GPIO2_IRQn = 52, /*!< GPIO 2 interrupt */
+ GPIO3_IRQn = 53, /*!< GPIO 3 interrupt */
+ GPIO4_IRQn = 54, /*!< GPIO 4 interrupt */
+ GPIO5_IRQn = 55, /*!< GPIO 5 interrupt */
+ GPIO6_IRQn = 56, /*!< GPIO 6 interrupt */
+ GPIO7_IRQn = 57, /*!< GPIO 7 interrupt */
+ GPIO8_IRQn = 58, /*!< GPIO 8 interrupt */
+ GPIO9_IRQn = 59, /*!< GPIO 9 interrupt */
+ GPIO10_IRQn = 60, /*!< GPIO 10 interrupt */
+ GPIO11_IRQn = 61, /*!< GPIO 11 interrupt */
+ GPIO12_IRQn = 62, /*!< GPIO 12 interrupt */
+ GPIO13_IRQn = 63, /*!< GPIO 13 interrupt */
+ GPIO14_IRQn = 64, /*!< GPIO 14 interrupt */
+ GPIO15_IRQn = 65, /*!< GPIO 15 interrupt */
+ GPIO16_IRQn = 66, /*!< GPIO 16 interrupt */
+ GPIO17_IRQn = 67, /*!< GPIO 17 interrupt */
+ GPIO18_IRQn = 68, /*!< GPIO 18 interrupt */
+ GPIO19_IRQn = 69, /*!< GPIO 19 interrupt */
+ GPIO20_IRQn = 70, /*!< GPIO 20 interrupt */
+ GPIO21_IRQn = 71, /*!< GPIO 21 interrupt */
+ GPIO22_IRQn = 72, /*!< GPIO 22 interrupt */
+ GPIO23_IRQn = 73, /*!< GPIO 23 interrupt */
+ GPIO24_IRQn = 74, /*!< GPIO 24 interrupt */
+ GPIO25_IRQn = 75, /*!< GPIO 25 interrupt */
+ GPIO26_IRQn = 76, /*!< GPIO 26 interrupt */
+ GPIO27_IRQn = 77, /*!< GPIO 27 interrupt */
+ GPIO28_IRQn = 78, /*!< GPIO 28 interrupt */
+ GPIO29_IRQn = 79, /*!< GPIO 29 interrupt */
+ GPIO30_IRQn = 80, /*!< GPIO 30 interrupt */
+ GPIO31_IRQn = 81 /*!< GPIO 31 interrupt */
+} IRQn_Type;
+ * ----------- Processor and Core Peripheral Section ------------------------
+#define __CM3_REV 0x0201 /*!< Core revision r2p1 */
+#define __MPU_PRESENT 1 /*!< MPU present or not */
+#define __NVIC_PRIO_BITS 4 /*!< Number of Bits used for Priority Levels */
+#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */
+#include <core_cm3.h> /* Cortex-M3 processor and core peripherals */
+/******************************************************************************/
+/* Device Specific Peripheral registers structures */
+ /* Enable anonymous unions when building using Keil-MDK */
+ #pragma anon_unions
+/*----------------------------------------------------------------------------*/
+/*----------------------------------- UART -----------------------------------*/
+ union
+ __I uint8_t RBR;
+ __O uint8_t THR;
+ __IO uint8_t DLR;
+ };
+ __IO uint8_t DMR;
+ __IO uint8_t IER;
+ __IO uint8_t IIR;
+ __IO uint8_t FCR;
+ uint32_t RESERVED2;
+ __IO uint8_t LCR;
+ uint8_t RESERVED3[3];
+ __IO uint8_t MCR;
+ uint8_t RESERVED4[3];
+ __I uint8_t LSR;
+ uint8_t RESERVED5[3];
+ __I uint8_t MSR;
+ uint8_t RESERVED6[3];
+ __IO uint8_t SR;
+ uint8_t RESERVED7[7];
+ __IO uint8_t IEM;
+ uint8_t RESERVED8[3];
+ __IO uint8_t IIM;
+ uint8_t RESERVED9[7];
+ __IO uint8_t MM0;
+ uint8_t RESERVED10[3];
+ __IO uint8_t MM1;
+ uint8_t RESERVED11[3];
+ __IO uint8_t MM2;
+ uint8_t RESERVED12[3];
+ __IO uint8_t DFR;
+ uint8_t RESERVED13[7];
+ __IO uint8_t GFR;
+ uint8_t RESERVED14[3];
+ __IO uint8_t TTG;
+ uint8_t RESERVED15[3];
+ __IO uint8_t RTO;
+ uint8_t RESERVED16[3];
+ __IO uint8_t ADR;
+ uint8_t RESERVED17[3];
+} UART_TypeDef;
+/*----------------------------------- I2C ------------------------------------*/
+ __IO uint8_t CTRL;
+ uint8_t RESERVED0;
+ uint16_t RESERVED1;
+ uint8_t STATUS;
+ uint8_t RESERVED2;
+ uint16_t RESERVED3;
+ __IO uint8_t DATA;
+ uint8_t RESERVED4;
+ uint16_t RESERVED5;
+ __IO uint8_t ADDR;
+ uint8_t RESERVED6;
+ uint16_t RESERVED7;
+ __IO uint8_t SMBUS;
+ uint8_t RESERVED8;
+ uint16_t RESERVED9;
+ __IO uint8_t FREQ;
+ uint8_t RESERVED10;
+ uint16_t RESERVED11;
+ __IO uint8_t GLITCHREG;
+ uint8_t RESERVED12;
+ uint16_t RESERVED13;
+ __IO uint8_t SLAVE1_ADDR;
+ uint8_t RESERVED14;
+ uint16_t RESERVED15;
+} I2C_TypeDef;
+/*------------------------------------------------------------------------------
+ * I2C bit band
+ __IO uint32_t CTRL_CR0;
+ __IO uint32_t CTRL_CR1;
+ __IO uint32_t CTRL_AA;
+ __IO uint32_t CTRL_SI;
+ __IO uint32_t CTRL_STO;
+ __IO uint32_t CTRL_STA;
+ __IO uint32_t CTRL_ENS1;
+ __IO uint32_t CTRL_CR2;
+ uint32_t RESERVED0[56];
+ __IO uint32_t DATA_DIR;
+ uint32_t RESERVED1[31];
+ __IO uint32_t ADDR_GC;
+} I2C_BitBand_TypeDef;
+/*----------------------------------- SPI ------------------------------------*/
+ __IO uint32_t CONTROL;
+ __IO uint32_t TXRXDF_SIZE;
+ __I uint32_t STATUS;
+ __O uint32_t INT_CLEAR;
+ __I uint32_t RX_DATA;
+ __O uint32_t TX_DATA;
+ __IO uint32_t CLK_GEN;
+ __IO uint32_t SLAVE_SELECT;
+ __I uint32_t MIS;
+ __I uint32_t RIS;
+ __IO uint32_t CONTROL2;
+ __IO uint32_t COMMAND;
+ __IO uint32_t PKTSIZE;
+ __IO uint32_t CMDSIZE;
+ __IO uint32_t HWSTATUS;
+ __IO uint32_t STAT8;
+ __IO uint32_t CTRL0;
+ __IO uint32_t CTRL1;
+ __IO uint32_t CTRL2;
+ __IO uint32_t CTRL3;
+} SPI_TypeDef;
+/*----------------------------------- GPIO -----------------------------------*/
+ __IO uint32_t GPIO_0_CFG;
+ __IO uint32_t GPIO_1_CFG;
+ __IO uint32_t GPIO_2_CFG;
+ __IO uint32_t GPIO_3_CFG;
+ __IO uint32_t GPIO_4_CFG;
+ __IO uint32_t GPIO_5_CFG;
+ __IO uint32_t GPIO_6_CFG;
+ __IO uint32_t GPIO_7_CFG;
+ __IO uint32_t GPIO_8_CFG;
+ __IO uint32_t GPIO_9_CFG;
+ __IO uint32_t GPIO_10_CFG;
+ __IO uint32_t GPIO_11_CFG;
+ __IO uint32_t GPIO_12_CFG;
+ __IO uint32_t GPIO_13_CFG;
+ __IO uint32_t GPIO_14_CFG;
+ __IO uint32_t GPIO_15_CFG;
+ __IO uint32_t GPIO_16_CFG;
+ __IO uint32_t GPIO_17_CFG;
+ __IO uint32_t GPIO_18_CFG;
+ __IO uint32_t GPIO_19_CFG;
+ __IO uint32_t GPIO_20_CFG;
+ __IO uint32_t GPIO_21_CFG;
+ __IO uint32_t GPIO_22_CFG;
+ __IO uint32_t GPIO_23_CFG;
+ __IO uint32_t GPIO_24_CFG;
+ __IO uint32_t GPIO_25_CFG;
+ __IO uint32_t GPIO_26_CFG;
+ __IO uint32_t GPIO_27_CFG;
+ __IO uint32_t GPIO_28_CFG;
+ __IO uint32_t GPIO_29_CFG;
+ __IO uint32_t GPIO_30_CFG;
+ __IO uint32_t GPIO_31_CFG;
+ __IO uint32_t GPIO_IRQ;
+ __I uint32_t GPIO_IN;
+ __IO uint32_t GPIO_OUT;
+} GPIO_TypeDef;
+ * GPIO bit band
+ __IO uint32_t GPIO_0_CFG[32];
+ __IO uint32_t GPIO_1_CFG[32];
+ __IO uint32_t GPIO_2_CFG[32];
+ __IO uint32_t GPIO_3_CFG[32];
+ __IO uint32_t GPIO_4_CFG[32];
+ __IO uint32_t GPIO_5_CFG[32];
+ __IO uint32_t GPIO_6_CFG[32];
+ __IO uint32_t GPIO_7_CFG[32];
+ __IO uint32_t GPIO_8_CFG[32];
+ __IO uint32_t GPIO_9_CFG[32];
+ __IO uint32_t GPIO_10_CFG[32];
+ __IO uint32_t GPIO_11_CFG[32];
+ __IO uint32_t GPIO_12_CFG[32];
+ __IO uint32_t GPIO_13_CFG[32];
+ __IO uint32_t GPIO_14_CFG[32];
+ __IO uint32_t GPIO_15_CFG[32];
+ __IO uint32_t GPIO_16_CFG[32];
+ __IO uint32_t GPIO_17_CFG[32];
+ __IO uint32_t GPIO_18_CFG[32];
+ __IO uint32_t GPIO_19_CFG[32];
+ __IO uint32_t GPIO_20_CFG[32];
+ __IO uint32_t GPIO_21_CFG[32];
+ __IO uint32_t GPIO_22_CFG[32];
+ __IO uint32_t GPIO_23_CFG[32];
+ __IO uint32_t GPIO_24_CFG[32];
+ __IO uint32_t GPIO_25_CFG[32];
+ __IO uint32_t GPIO_26_CFG[32];
+ __IO uint32_t GPIO_27_CFG[32];
+ __IO uint32_t GPIO_28_CFG[32];
+ __IO uint32_t GPIO_29_CFG[32];
+ __IO uint32_t GPIO_30_CFG[32];
+ __IO uint32_t GPIO_31_CFG[32];
+ __IO uint32_t GPIO_IRQ[32];
+ __I uint32_t GPIO_IN[32];
+ __IO uint32_t GPIO_OUT[32];
+} GPIO_BitBand_TypeDef;
+/*--------------------------------- HPDMA ------------------------------------*/
+ __IO uint32_t HPDMASAR_REG ;
+ __IO uint32_t HPDMADAR_REG ;
+ __IO uint32_t HPDMACR_REG ;
+ __I uint32_t HPDMASR_REG ;
+ __I uint32_t HPDMAPTR_REG ;
+}HPDMA_Descriptor_TypeDef;
+ __I uint32_t HPDMAEDR_REG ;
+ HPDMA_Descriptor_TypeDef Descriptor[4] ;
+ __O uint32_t HPDMAICR_REG ;
+ __I uint32_t HPDMADR_REG ;
+} HPDMA_TypeDef;
+ uint32_t RESERVED0[64];
+ __IO uint32_t HPDMACR_XFR_SIZE[16] ;
+ __IO uint32_t HPDMACR_DCP_VALID ;
+ __IO uint32_t HPDMACR_DCP_XFR_DIR ;
+ __IO uint32_t HPDMACR_DCP_CLR ;
+ __IO uint32_t HPDMACR_DCP_PAUSE ;
+ __IO uint32_t HPDMACR_XFR_CMP_INT ;
+ __IO uint32_t HPDMACR_XFR_ERR_INT ;
+ __IO uint32_t HPDMACR_NON_WORD_INT ;
+ uint32_t RESERVED1[9];
+ __I uint32_t HPDMASR_DCP_ACTIVE ;
+ __I uint32_t HPDMASR_DCP_CMPLET ;
+ __I uint32_t HPDMASR_DCP_SERR ;
+ __I uint32_t HPDMASR_DCP_DERR ;
+ uint32_t RESERVED2[60] ;
+}HPDMA_Descriptor_BitBand_TypeDef;
+ * HPDMA bit band
+ __I uint32_t HPDMAEDR_DCP_EMPTY[4] ;
+ __I uint32_t HPDMAEDR_DCP_CMPLET[4] ;
+ __I uint32_t HPDMAEDR_DCP_ERR[4] ;
+ __I uint32_t HPDMAEDR_DCP_NON_WORD_ERR[4] ;
+ uint32_t RESERVED0[16] ;
+ HPDMA_Descriptor_BitBand_TypeDef Descriptor[4];
+ __O uint32_t HPDMAICR_CLR_XFR_INT[4] ;
+ __O uint32_t HPDMAICR_NON_WORD_INT[4] ;
+ uint32_t RESERVED1[16] ;
+ __I uint32_t HPDMADR_BFR_EMPTY ;
+ __I uint32_t HPDMADR_BFR_FULL ;
+ __I uint32_t HPDMADR_BFR_RD_PNTR[3] ;
+ __I uint32_t HPDMADR_BFR_WR_PNTR [3] ;
+ __I uint32_t HPDMADR_AHM1_CST_DBG[4] ;
+ __I uint32_t HPDMADR_AHM2_CST_DBG[4] ;
+ __I uint32_t HPDMADR_WBC_CST_DBG[3] ;
+ __I uint32_t HPDMADR_RBC_CST_DBG[3] ;
+ __I uint32_t HPDMADR_RRBN_CST_DBG[4] ;
+ __I uint32_t HPDMADR_DMA_CST_DBG[4] ;
+ uint32_t RESERVED2[4] ;
+}HPDMA_BitBand_TypeDef;
+/*----------------------------------- RTC ------------------------------------*/
+ __IO uint32_t CONTROL_REG ;
+ __IO uint32_t MODE_REG ;
+ __IO uint32_t PRESCALER_REG ;
+ __IO uint32_t ALARM_LOWER_REG ;
+ __IO uint32_t ALARM_UPPER_REG ;
+ __IO uint32_t COMPARE_LOWER_REG ;
+ __IO uint32_t COMPARE_UPPER_REG ;
+ uint32_t RESERVED0 ;
+ __IO uint32_t DATE_TIME_LOWER_REG ;
+ __IO uint32_t DATE_TIME_UPPER_REG ;
+ uint32_t RESERVED1[2] ;
+ __IO uint32_t SECONDS_REG ;
+ __IO uint32_t MINUTES_REG ;
+ __IO uint32_t HOURS_REG ;
+ __IO uint32_t DAY_REG ;
+ __IO uint32_t MONTH_REG ;
+ __IO uint32_t YEAR_REG ;
+ __IO uint32_t WEEKDAY_REG ;
+ __IO uint32_t WEEK_REG ;
+ __IO uint32_t SECONDS_CNT_REG ;
+ __IO uint32_t MINUTES_CNT_REG ;
+ __IO uint32_t HOURS_CNT_REG ;
+ __IO uint32_t DAY_CNT_REG ;
+ __IO uint32_t MONTH_CNT_REG ;
+ __IO uint32_t YEAR_CNT_REG ;
+ __IO uint32_t WEEKDAY_CNT_REG ;
+ __IO uint32_t WEEK_CNT_REG ;
+} RTC_TypeDef;
+/*---------------------------------- Timer -----------------------------------*/
+ __I uint32_t TIM1_VAL;
+ __IO uint32_t TIM1_LOADVAL;
+ __IO uint32_t TIM1_BGLOADVAL;
+ __IO uint32_t TIM1_CTRL;
+ __IO uint32_t TIM1_RIS;
+ __I uint32_t TIM1_MIS;
+ __I uint32_t TIM2_VAL;
+ __IO uint32_t TIM2_LOADVAL;
+ __IO uint32_t TIM2_BGLOADVAL;
+ __IO uint32_t TIM2_CTRL;
+ __IO uint32_t TIM2_RIS;
+ __I uint32_t TIM2_MIS;
+ __I uint32_t TIM64_VAL_U;
+ __I uint32_t TIM64_VAL_L;
+ __IO uint32_t TIM64_LOADVAL_U;
+ __IO uint32_t TIM64_LOADVAL_L;
+ __IO uint32_t TIM64_BGLOADVAL_U;
+ __IO uint32_t TIM64_BGLOADVAL_L;
+ __IO uint32_t TIM64_CTRL;
+ __IO uint32_t TIM64_RIS;
+ __I uint32_t TIM64_MIS;
+ __IO uint32_t TIM64_MODE;
+} TIMER_TypeDef;
+ * Timer bit band
+ __I uint32_t TIM1_VALUE_BIT[32];
+ __IO uint32_t TIM1_LOADVAL[32];
+ __IO uint32_t TIM1_BGLOADVAL[32];
+ __IO uint32_t TIM1ENABLE;
+ __IO uint32_t TIM1MODE;
+ __IO uint32_t TIM1INTEN;
+ __IO uint32_t TIM1_CTRL_RESERVED[29];
+ __IO uint32_t TIM1_RIS[32];
+ __I uint32_t TIM1_MIS[32];
+ __I uint32_t TIM2_VALUE[32];
+ __IO uint32_t TIM2_LOADVAL[32];
+ __IO uint32_t TIM2_BGLOADVAL[32];
+ __IO uint32_t TIM2ENABLE;
+ __IO uint32_t TIM2MODE;
+ __IO uint32_t TIM2INTEN;
+ __IO uint32_t TIM2_CTRL[29];
+ __IO uint32_t TIM2_RIS[32];
+ __I uint32_t TIM2_MIS[32];
+ __I uint32_t TIM64VALUEU[32];
+ __I uint32_t TIM64VALUEL[32];
+ __IO uint32_t TIM64LOADVALUEU[32];
+ __IO uint32_t TIM64LOADVALUEL[32];
+ __IO uint32_t TIM64BGLOADVALUEU[32];
+ __IO uint32_t TIM64BGLOADVALUEL[32];
+ __IO uint32_t TIM64ENABLE;
+ __IO uint32_t TIM64MODE;
+ __IO uint32_t TIM64INTEN;
+ __IO uint32_t TIM64_CTRL[29];
+ __IO uint32_t TIM64_RIS[32];
+ __I uint32_t TIM64_MIS[32];
+ __IO uint32_t TIM64_MODE[32];
+} TIMER_BitBand_TypeDef;
+/*--------------------------------- Watchdog ---------------------------------*/
+ __I uint32_t WDOGVALUE;
+ __I uint32_t WDOGLOAD;
+ __I uint32_t WDOGMVRP;
+ __O uint32_t WDOGREFRESH;
+ __I uint32_t WDOGENABLE;
+ __IO uint32_t WDOGCONTROL;
+ __I uint32_t WDOGSTATUS;
+ __IO uint32_t WDOGRIS;
+ __I uint32_t WDOGMIS;
+} WATCHDOG_TypeDef;
+/*----------------------------- Real Time Clock ------------------------------*/
+/*----------------------------- Peripherals DMA ------------------------------*/
+ __IO uint32_t CRTL;
+ __IO uint32_t STATUS;
+ __IO uint32_t BUFFER_A_SRC_ADDR;
+ __IO uint32_t BUFFER_A_DEST_ADDR;
+ __IO uint32_t BUFFER_A_TRANSFER_COUNT;
+ __IO uint32_t BUFFER_B_SRC_ADDR;
+ __IO uint32_t BUFFER_B_DEST_ADDR;
+ __IO uint32_t BUFFER_B_TRANSFER_COUNT;
+} PDMA_Channel_TypeDef;
+ __IO uint32_t RATIO_HIGH_LOW;
+ __IO uint32_t BUFFER_STATUS;
+ uint32_t RESERVED[6];
+ PDMA_Channel_TypeDef CHANNEL[8];
+} PDMA_TypeDef;
+/*------------------------------ Ethernet MAC --------------------------------*/
+ /*
+ * MAC registers (MCXMAC)
+ __IO uint32_t CFG1;
+ __IO uint32_t CFG2;
+ __IO uint32_t IFG;
+ __IO uint32_t HALF_DUPLEX;
+ __IO uint32_t MAX_FRAME_LENGTH;
+ uint32_t RESERVED0[2];
+ __IO uint32_t TEST;
+ __IO uint32_t MII_CONFIG;
+ __IO uint32_t MII_COMMAND;
+ __IO uint32_t MII_ADDRESS;
+ __O uint32_t MII_CTRL;
+ __I uint32_t MII_STATUS;
+ __I uint32_t MII_INDICATORS;
+ __IO uint32_t INTERFACE_CTRL;
+ __I uint32_t INTERFACE_STATUS;
+ __IO uint32_t STATION_ADDRESS1;
+ __IO uint32_t STATION_ADDRESS2;
+ * FIFO Configuration / Access registers (MCXFIF)
+ __IO uint32_t FIFO_CFG0;
+ __IO uint32_t FIFO_CFG1;
+ __IO uint32_t FIFO_CFG2;
+ __IO uint32_t FIFO_CFG3;
+ __IO uint32_t FIFO_CFG4;
+ __IO uint32_t FIFO_CFG5;
+ __IO uint32_t FIFO_RAM_ACCESS0;
+ __IO uint32_t FIFO_RAM_ACCESS1;
+ __IO uint32_t FIFO_RAM_ACCESS2;
+ __I uint32_t FIFO_RAM_ACCESS3;
+ __IO uint32_t FIFO_RAM_ACCESS4;
+ __IO uint32_t FIFO_RAM_ACCESS5;
+ __IO uint32_t FIFO_RAM_ACCESS6;
+ __I uint32_t FIFO_RAM_ACCESS7;
+ * Statistics registers (MSTAT)
+ __IO uint32_t TR64;
+ __IO uint32_t TR127;
+ __IO uint32_t TR255;
+ __IO uint32_t TR511;
+ __IO uint32_t TR1K;
+ __IO uint32_t TRMAX;
+ __IO uint32_t TRMGV;
+ __IO uint32_t RBYT;
+ __IO uint32_t PPKT;
+ __IO uint32_t RFCS;
+ __IO uint32_t RMCA;
+ __IO uint32_t RBCA;
+ __IO uint32_t RXCF;
+ __IO uint32_t RXPF;
+ __IO uint32_t RXUO;
+ __IO uint32_t RALN;
+ __IO uint32_t RFLR;
+ __IO uint32_t RCDE;
+ __IO uint32_t RCSE;
+ __IO uint32_t RUND;
+ __IO uint32_t ROVR;
+ __IO uint32_t RFRG;
+ __IO uint32_t RJBR;
+ __IO uint32_t RDRP;
+ __IO uint32_t TBYT;
+ __IO uint32_t TPKT;
+ __IO uint32_t TMCA;
+ __IO uint32_t TBCA;
+ __IO uint32_t TXPF;
+ __IO uint32_t TDFR;
+ __IO uint32_t TEDF;
+ __IO uint32_t TSCL;
+ __IO uint32_t TMCL;
+ __IO uint32_t TLCL;
+ __IO uint32_t TXCL;
+ __IO uint32_t TNCL;
+ __IO uint32_t TPFH;
+ __IO uint32_t TDRP;
+ __IO uint32_t TJBR;
+ __IO uint32_t TFCS;
+ __IO uint32_t TXCF;
+ __IO uint32_t TOVR;
+ __IO uint32_t TUND;
+ __IO uint32_t TFRG;
+ __I uint32_t CAR1;
+ __I uint32_t CAR2;
+ __IO uint32_t CAM1;
+ __IO uint32_t CAM2;
+ uint32_t RESERVED1[16];
+ * DMA registers (MAHBE)
+ __IO uint32_t DMA_TX_CTRL;
+ __IO uint32_t DMA_TX_DESC;
+ __IO uint32_t DMA_TX_STATUS;
+ __IO uint32_t DMA_RX_CTRL;
+ __IO uint32_t DMA_RX_DESC;
+ __IO uint32_t DMA_RX_STATUS;
+ __IO uint32_t DMA_IRQ_MASK;
+ __I uint32_t DMA_IRQ;
+} MAC_TypeDef;
+/*------------------------------ USB --------------------------------*/
+ __IO uint16_t TX_MAX_P;
+ __IO uint16_t TX_CSR;
+ __IO uint16_t RX_MAX_P;
+ __IO uint16_t RX_CSR;
+ __IO uint16_t RX_COUNT;
+ __IO uint8_t TX_TYPE;
+ __IO uint8_t TX_INTERVAL;
+ __IO uint8_t RX_TYPE;
+ __IO uint8_t RX_INTERVAL;
+ __IO uint8_t RESERVED;
+ __IO uint8_t FIFO_SIZE;
+} USB_endpoint_regs_t;
+ __IO uint8_t TX_FUNC_ADDR;
+ __IO uint8_t UNUSED0;
+ __IO uint8_t TX_HUB_ADDR;
+ __IO uint8_t TX_HUB_PORT;
+ __IO uint8_t RX_FUNC_ADDR;
+ __IO uint8_t UNUSED1;
+ __IO uint8_t RX_HUB_ADDR;
+ __IO uint8_t RX_HUB_PORT;
+} USB_tar_t;
+typedef union
+ struct
+ __IO uint32_t VALUE;
+ } WORD;
+ __IO uint8_t VALUE;
+ __IO uint8_t RESERVED1;
+ __IO uint8_t RESERVED2;
+ __IO uint8_t RESERVED3;
+ } BYTE;
+ __IO uint16_t VALUE;
+ __IO uint16_t RESERVED;
+ } HALFWORD;
+} USB_fifo_t;
+ __IO uint16_t CSR0;
+ __IO uint16_t COUNT0;
+ __IO uint8_t RESERVED0;
+ __IO uint8_t RESERVED4;
+ __IO uint8_t CONFIG_DATA;
+ } DEVICE_EP0;
+ } DEVICE_EPN;
+ __IO uint8_t TYPE0;
+ __IO uint8_t NAK_LIMIT0;
+ } HOST_EP0;
+ } HOST_EPN;
+} USB_indexed_csr_t;
+typedef struct {
+ __IO uint32_t IRQ;
+ __IO uint32_t CNTL;
+ __IO uint32_t ADDR;
+ __IO uint32_t COUNT;
+} USB_DMA_channel;
+ * Common USB Registers
+ __IO uint8_t FADDR;
+ __IO uint8_t POWER;
+ __IO uint16_t TX_IRQ;
+ __IO uint16_t RX_IRQ;
+ __IO uint16_t TX_IRQ_ENABLE;
+ __IO uint16_t RX_IRQ_ENABLE;
+ __IO uint8_t USB_IRQ;
+ __IO uint8_t USB_ENABLE;
+ __IO uint16_t FRAME;
+ __IO uint8_t INDEX;
+ __IO uint8_t TEST_MODE;
+ * Indexed CSR
+ USB_indexed_csr_t INDEXED_CSR;
+ * Endpoint FIFOs
+ USB_fifo_t FIFO[16];
+ * OTG, dynamic FIFO and version
+ __IO uint8_t DEV_CTRL;
+ __IO uint8_t MISC;
+ __IO uint8_t TX_FIFO_SIZE;
+ __IO uint8_t RX_FIFO_SIZE;
+ __IO uint16_t TX_FIFO_ADDR;
+ __IO uint16_t RX_FIFO_ADDR;
+ __IO uint32_t VBUS_CSR;
+ __IO uint16_t HW_VERSION;
+ * ULPI and configuration registers
+ __IO uint8_t ULPI_VBUS_CTRL;
+ __IO uint8_t ULPI_CARKIT_CTRL;
+ __IO uint8_t ULPI_IRQ_MASK;
+ __IO uint8_t ULPI_IRQ_SRC;
+ __IO uint8_t ULPI_DATA_REG;
+ __IO uint8_t ULPI_ADDR_REG;
+ __IO uint8_t ULPI_CTRL_REG;
+ __IO uint8_t ULPI_RAW_DATA;
+ __IO uint8_t EP_INFO;
+ __IO uint8_t RAM_INFO;
+ __IO uint8_t LINK_INFO;
+ __IO uint8_t VP_LEN;
+ __IO uint8_t HS_EOF1;
+ __IO uint8_t FS_EOF1;
+ __IO uint8_t LS_EOF1;
+ __IO uint8_t SOFT_RST;
+ * Target Address registers
+ USB_tar_t TAR[16];
+ * Endpoints CSR
+ USB_endpoint_regs_t ENDPOINT[16];
+ * DMA
+ USB_DMA_channel DMA_CHANNEL[8];
+ __IO uint32_t RESERVED_EXT[32];
+ __IO uint32_t RQ_PKT_CNT[16];
+ __IO uint16_t RX_DPBUF_DIS;
+ __IO uint16_t TX_DPBUF_DIS;
+ __IO uint16_t C_T_UCH;
+ __IO uint16_t C_T_HHSRTN;
+ __IO uint16_t C_T_HSBT;
+} MSS_USB_TypeDef;
+/*---------------------- eNVM Special Function Registers ---------------------*/
+ __I uint8_t AB[128];
+ __IO uint8_t WD[128];
+ __I uint8_t RESERVED0[32];
+ __IO uint32_t RESERVED1;
+ __IO uint32_t NV_PAGE_STATUS;
+ __I uint32_t NV_FREQRNG;
+ __I uint32_t NV_DPD;
+ __IO uint32_t NV_CE;
+ __IO uint32_t RESERVED3;
+ __IO uint32_t PAGE_LOCK;
+ __IO uint32_t DWSIZE;
+ __IO uint32_t CMD;
+ __IO uint32_t RESERVED4;
+ __I uint32_t RESERVED5;
+ __IO uint32_t INTEN;
+ __IO uint32_t CLRHINT;
+ uint32_t RESERVED6[40];
+ __IO uint32_t REQ_ACCESS;
+} NVM_TypeDef;
+ __I uint32_t AB[32];
+ __IO uint32_t WD[32];
+ __I uint32_t RESERVED0[8];
+} NVM32_TypeDef;
+/*---------------------------------- COMBLK ----------------------------------*/
+ __IO uint32_t INT_ENABLE;
+ __IO uint32_t RESERVED;
+ __IO uint32_t DATA8;
+ __IO uint32_t DATA32;
+ __IO uint32_t FRAME_START8;
+ __IO uint32_t FRAME_START32;
+} COMBLK_TypeDef;
+/*--------------------- FPGA Fabric Interrupt Controller ---------------------*/
+ * Please refer to the SmartFusion2 Interrupt Controller User's Guide for a
+ * description of the following registers.
+ * The registers defined below can be accessed using INTERRUPT_CTRL as follows:
+ * uint32_t reason0;
+ * INTERRUPT_CTRL->INTERRUPT_MODE = 0;
+ * reason0 = INTERRUPT_CTRL->INTERRUPT_REASON0;
+ __IO uint32_t INTERRUPT_ENABLE0;
+ __IO uint32_t INTERRUPT_ENABLE1;
+ __IO uint32_t INTERRUPT_REASON0;
+ __IO uint32_t INTERRUPT_REASON1;
+ __IO uint32_t INTERRUPT_MODE;
+} INTERRUPT_CTRL_TypeDef;
+ * description of the following register bits.
+ * The register bits defined below can be accessed using INTERRUPT_CTRL_BITBAND
+ * as follows:
+ * setting/clearing a bit:
+ * INTERRUPT_CTRL_BITBAND->MAC_INT_ENBL = 1;
+ * INTERRUPT_CTRL_BITBAND->PDMAINTERRUPT_ENBL = 0;
+ * reading a bit value:
+ * uint32_t timer1_interrupt;
+ * timer1_interrupt = INTERRUPT_CTRL_BITBAND->TIMER1_INTR_STATUS;
+ * INTERRUPT_ENABLE0 register bitband definitions.
+ __IO uint32_t SPIINT0_ENBL;
+ __IO uint32_t SPIINT1_ENBL;
+ __IO uint32_t I2C_INT0_ENBL;
+ __IO uint32_t I2C_INT1_ENBL;
+ __IO uint32_t MMUART0_INTR_ENBL;
+ __IO uint32_t MMUART1_INTR_ENBL;
+ __IO uint32_t MAC_INT_ENBL;
+ __IO uint32_t USB_MC_INT_ENBL;
+ __IO uint32_t PDMAINTERRUPT_ENBL;
+ __IO uint32_t HPD_XFR_CMP_INT_ENBL;
+ __IO uint32_t TIMER1_INTR_ENBL;
+ __IO uint32_t TIMER2_INTR_ENBL;
+ __IO uint32_t CAN_INTR_ENBL;
+ __IO uint32_t RTC_WAKEUP_INTR_ENBL;
+ __IO uint32_t WDOGWAKEUPINT_ENBL;
+ __IO uint32_t MSSDDR_PLL_LOCKLOST_INT_ENBL;
+ __IO uint32_t ENVM_INT0_ENBL;
+ __IO uint32_t ENVM_INT1_ENBL;
+ __IO uint32_t I2C_SMBALERT0_ENBL;
+ __IO uint32_t I2C_SMBSUS0_ENBL;
+ __IO uint32_t I2C_SMBALERT1_ENBL;
+ __IO uint32_t I2C_SMBSUS1_ENBL;
+ __IO uint32_t HPD_XFR_ERR_INT_ENBL;
+ __IO uint32_t MSSDDR_PLL_LOCK_INT_ENBL;
+ __IO uint32_t SW_ERRORINTERRUPT_ENBL;
+ __IO uint32_t DDRB_INTR_ENBL;
+ __IO uint32_t ECCINTR_ENBL;
+ __IO uint32_t CACHE_ERRINTR_ENBL;
+ __IO uint32_t SOFTINTERRUPT_ENBL;
+ __IO uint32_t COMBLK_INTR_ENBL;
+ __IO uint32_t USB_DMA_INT_ENBL;
+ __IO uint32_t RESERVED0;
+ * INTERRUPT_ENABLE1 register bitband definitions.
+ __IO uint32_t RESERVED1[3];
+ __IO uint32_t MDDR_IO_CALIB_INT_ENBL;
+ __IO uint32_t RESERVED2;
+ __IO uint32_t FAB_PLL_LOCK_INT_ENBL;
+ __IO uint32_t FAB_PLL_LOCKLOST_INT_ENBL;
+ __IO uint32_t FIC64_INT_ENBL;
+ __IO uint32_t RESERVED3[24];
+ * INTERRUPT_REASON0 register bitband definitions.
+ __IO uint32_t SPIINT0_STATUS;
+ __IO uint32_t SPIINT1_STATUS;
+ __IO uint32_t I2C_INT0_STATUS;
+ __IO uint32_t I2C_INT1_STATUS;
+ __IO uint32_t MMUART0_INTR_STATUS;
+ __IO uint32_t MMUART1_INTR_STATUS;
+ __IO uint32_t MAC_INT_STATUS;
+ __IO uint32_t USB_MC_INT_STATUS;
+ __IO uint32_t PDMAINTERRUPT_STATUS;
+ __IO uint32_t HPD_XFR_CMP_INT_STATUS;
+ __IO uint32_t TIMER1_INTR_STATUS;
+ __IO uint32_t TIMER2_INTR_STATUS;
+ __IO uint32_t CAN_INTR_STATUS;
+ __IO uint32_t RTC_WAKEUP_INTR_STATUS;
+ __IO uint32_t WDOGWAKEUPINT_STATUS;
+ __IO uint32_t MSSDDR_PLL_LOCKLOST_INT_STATUS;
+ __IO uint32_t ENVM_INT0_STATUS;
+ __IO uint32_t ENVM_INT1_STATUS;
+ __IO uint32_t I2C_SMBALERT0_STATUS;
+ __IO uint32_t I2C_SMBSUS0_STATUS;
+ __IO uint32_t I2C_SMBALERT1_STATUS;
+ __IO uint32_t I2C_SMBSUS1_STATUS;
+ __IO uint32_t HPD_XFR_ERR_INT_STATUS;
+ __IO uint32_t MSSDDR_PLL_LOCK_INT_STATUS;
+ __IO uint32_t SW_ERRORINTERRUPT_STATUS;
+ __IO uint32_t DDRB_INTR_STATUS;
+ __IO uint32_t ECCINTR_STATUS;
+ __IO uint32_t CACHE_ERRINTR_STATUS;
+ __IO uint32_t SOFTINTERRUPT_STATUS;
+ __IO uint32_t COMBLK_INTR_STATUS;
+ __IO uint32_t USB_DMA_INT_STATUS;
+ * INTERRUPT_REASON1 register bitband definitions.
+ __IO uint32_t RESERVED5[3];
+ __IO uint32_t MDDR_IO_CALIB_INT_STATUS;
+ __IO uint32_t RESERVED6;
+ __IO uint32_t FAB_PLL_LOCK_INT_STATUS;
+ __IO uint32_t FAB_PLL_LOCKLOST_INT_STATUS;
+ __IO uint32_t FIC64_INT_STATUS;
+ __IO uint32_t RESERVED7[24];
+ * INTERRUPT_MODE register bitband definitions.
+ __IO uint32_t SELECT_MODE;
+ __IO uint32_t RESERVED8[31];
+} INTERRUPT_CTRL_BitBand_TypeDef;
+/*------------------------ DDR Controller APB Registers ----------------------*/
+ /*--------------------------------------------------------------------------
+ * DDR Controller registers.
+ * All registers are 16-bit wide unless mentioned beside the definition.
+ __IO uint32_t DYN_SOFT_RESET_CR;
+ __IO uint32_t DYN_REFRESH_1_CR;
+ __IO uint32_t DYN_REFRESH_2_CR;
+ __IO uint32_t DYN_POWERDOWN_CR;
+ __IO uint32_t DYN_DEBUG_CR;
+ __IO uint32_t MODE_CR;
+ __IO uint32_t ADDR_MAP_BANK_CR;
+ __IO uint32_t ECC_DATA_MASK_CR;
+ __IO uint32_t ADDR_MAP_COL_1_CR;
+ __IO uint32_t ADDR_MAP_COL_2_CR;
+ __IO uint32_t ADDR_MAP_ROW_1_CR;
+ __IO uint32_t ADDR_MAP_ROW_2_CR;
+ __IO uint32_t INIT_1_CR;
+ __IO uint32_t CKE_RSTN_CYCLES_CR[2]; /* 0:27 bits are valid */
+ __IO uint32_t INIT_MR_CR;
+ __IO uint32_t INIT_EMR_CR;
+ __IO uint32_t INIT_EMR2_CR;
+ __IO uint32_t INIT_EMR3_CR;
+ __IO uint32_t DRAM_BANK_TIMING_PARAM_CR;
+ __IO uint32_t DRAM_RD_WR_LATENCY_CR;
+ __IO uint32_t DRAM_RD_WR_PRE_CR;
+ __IO uint32_t DRAM_MR_TIMING_PARAM_CR;
+ __IO uint32_t DRAM_RAS_TIMING_CR;
+ __IO uint32_t DRAM_RD_WR_TRNARND_TIME_CR;
+ __IO uint32_t DRAM_T_PD_CR;
+ __IO uint32_t DRAM_BANK_ACT_TIMING_CR;
+ __IO uint32_t ODT_PARAM_1_CR;
+ __IO uint32_t ODT_PARAM_2_CR;
+ __IO uint32_t ADDR_MAP_COL_3_CR;
+ __IO uint32_t MODE_REG_RD_WR_CR;
+ __IO uint32_t MODE_REG_DATA_CR;
+ __IO uint32_t PWR_SAVE_1_CR;
+ __IO uint32_t PWR_SAVE_2_CR;
+ __IO uint32_t ZQ_LONG_TIME_CR;
+ __IO uint32_t ZQ_SHORT_TIME_CR;
+ __IO uint32_t ZQ_SHORT_INT_REFRESH_MARGIN_CR[2];
+ __IO uint32_t PERF_PARAM_1_CR;
+ __IO uint32_t HPR_QUEUE_PARAM_CR[2];
+ __IO uint32_t LPR_QUEUE_PARAM_CR[2];
+ __IO uint32_t WR_QUEUE_PARAM_CR;
+ __IO uint32_t PERF_PARAM_2_CR;
+ __IO uint32_t PERF_PARAM_3_CR;
+ __IO uint32_t DFI_RDDATA_EN_CR;
+ __IO uint32_t DFI_MIN_CTRLUPD_TIMING_CR;
+ __IO uint32_t DFI_MAX_CTRLUPD_TIMING_CR;
+ __IO uint32_t DFI_WR_LVL_CONTROL_CR[2];
+ __IO uint32_t DFI_RD_LVL_CONTROL_CR[2];
+ __IO uint32_t DFI_CTRLUPD_TIME_INTERVAL_CR;
+ __IO uint32_t DYN_SOFT_RESET_CR2;
+ __IO uint32_t AXI_FABRIC_PRI_ID_CR;
+ __I uint32_t DDRC_SR;
+ __I uint32_t SINGLE_ERR_CNT_SR;
+ __I uint32_t DOUBLE_ERR_CNT_SR;
+ __I uint32_t LUE_SYNDROME_SR[5]; /* LUE : Last Uncorrected Error */
+ __I uint32_t LUE_ADDRESS_SR[2];
+ __I uint32_t LCE_SYNDROME_SR[5]; /* LCE : Last Corrected Error */
+ __I uint32_t LCE_ADDRESS_SR[2];
+ __I uint32_t LCB_NUMBER_SR; /* LCB : Last Corrected Bit */
+ __I uint32_t LCB_MASK_SR[4];
+ __I uint32_t ECC_INT_SR;
+ __O uint32_t ECC_INT_CLR_REG;
+ __I uint32_t ECC_OUTPUT_DATA_SR;
+ __IO uint32_t RESERVED1[46];
+ } ddrc;
+ * DDR PHY configuration registers
+ __IO uint32_t DYN_BIST_TEST_CR;
+ __IO uint32_t DYN_BIST_TEST_ERRCLR_CR[3];
+ __IO uint32_t BIST_TEST_SHIFT_PATTERN_CR[3];
+ __IO uint32_t LOOPBACK_TEST_CR;
+ __IO uint32_t BOARD_LOOPBACK_CR;
+ __IO uint32_t CTRL_SLAVE_RATIO_CR;
+ __IO uint32_t CTRL_SLAVE_FORCE_CR;
+ __IO uint32_t CTRL_SLAVE_DELAY_CR;
+ __IO uint32_t DATA_SLICE_IN_USE_CR;
+ __IO uint32_t LVL_NUM_OF_DQ0_CR;
+ __IO uint32_t DQ_OFFSET_CR[3];
+ __IO uint32_t DIS_CALIB_RST_CR;
+ __IO uint32_t DLL_LOCK_DIFF_CR;
+ __IO uint32_t FIFO_WE_IN_DELAY_CR[3];
+ __IO uint32_t FIFO_WE_IN_FORCE_CR;
+ __IO uint32_t FIFO_WE_SLAVE_RATIO_CR[4];
+ __IO uint32_t GATELVL_INIT_MODE_CR;
+ __IO uint32_t GATELVL_INIT_RATIO_CR[4];
+ __IO uint32_t LOCAL_ODT_CR;
+ __IO uint32_t INVERT_CLKOUT_CR;
+ __IO uint32_t RD_DQS_SLAVE_DELAY_CR[3];
+ __IO uint32_t RD_DQS_SLAVE_FORCE_CR;
+ __IO uint32_t RD_DQS_SLAVE_RATIO_CR[4];
+ __IO uint32_t WR_DQS_SLAVE_DELAY_CR[3];
+ __IO uint32_t WR_DQS_SLAVE_FORCE_CR;
+ __IO uint32_t WR_DQS_SLAVE_RATIO_CR[4];
+ __IO uint32_t WR_DATA_SLAVE_DELAY_CR[3];
+ __IO uint32_t WR_DATA_SLAVE_FORCE_CR;
+ __IO uint32_t WR_DATA_SLAVE_RATIO_CR[4];
+ __IO uint32_t WRLVL_INIT_MODE_CR;
+ __IO uint32_t WRLVL_INIT_RATIO_CR[4];
+ __IO uint32_t WR_RD_RL_CR;
+ __IO uint32_t RDC_FIFO_RST_ERRCNTCLR_CR;
+ __IO uint32_t RDC_WE_TO_RE_DELAY_CR;
+ __IO uint32_t USE_FIXED_RE_CR;
+ __IO uint32_t USE_RANK0_DELAYS_CR;
+ __IO uint32_t USE_LVL_TRNG_LEVEL_CR;
+ __IO uint32_t CONFIG_CR;
+ __IO uint32_t RD_WR_GATE_LVL_CR;
+ __IO uint32_t DYN_RESET_CR;
+ /*----------------------------------------------------------------------
+ * DDR PHY status registers
+ __I uint32_t LEVELLING_FAILURE_SR;
+ __I uint32_t BIST_ERROR_SR[3];
+ __I uint32_t WRLVL_DQS_RATIO_SR[4];
+ __I uint32_t WRLVL_DQ_RATIO_SR[4];
+ __I uint32_t RDLVL_DQS_RATIO_SR[4];
+ __I uint32_t FIFO_SR[4];
+ __I uint32_t MASTER_DLL_SR;
+ __I uint32_t DLL_SLAVE_VALUE_SR[2];
+ __I uint32_t STATUS_OF_IN_DELAY_VAL_SR[2];
+ __I uint32_t STATUS_OF_OUT_DELAY_VAL_SR[2];
+ __I uint32_t DLL_LOCK_AND_SLAVE_VAL_SR;
+ __I uint32_t CTRL_OUTPUT_FILTER_SR;
+ __I uint32_t CTRL_OF_OUTPUT_DELAY_SR;
+ __I uint32_t RD_DQS_SLAVE_DLL_VAL_SR[3];
+ __I uint32_t WR_DATA_SLAVE_DLL_VAL_SR[3];
+ __I uint32_t FIFO_WE_SLAVE_DLL_VAL_SR[3];
+ __I uint32_t WR_DQS_SLAVE_DLL_VAL_SR[3];
+ __I uint32_t CTRL_SLAVE_DLL_VAL_SR;
+ __IO uint32_t RESERVED2[13];
+ } phy;
+ * FIC-64 registers
+ * These registers are 16-bit wide and 32-bit aligned.
+ __IO uint32_t NB_ADDR_CR;
+ __IO uint32_t NBRWB_SIZE_CR;
+ __IO uint32_t WB_TIMEOUT_CR;
+ __IO uint32_t HPD_SW_RW_EN_CR;
+ __IO uint32_t HPD_SW_RW_INVAL_CR;
+ __IO uint32_t SW_WR_ERCLR_CR;
+ __IO uint32_t ERR_INT_ENABLE_CR;
+ __IO uint32_t NUM_AHB_MASTERS_CR;
+ __I uint32_t HPB_ERR_ADDR_SR[2];
+ __I uint32_t SW_ERR_ADDR_SR[2];
+ __I uint32_t HPD_SW_WRB_EMPTY_SR;
+ __I uint32_t SW_HPB_LOCKOUT_SR;
+ __I uint32_t SW_HPD_WERR_SR;
+ __IO uint32_t LOCK_TIMEOUTVAL_CR[2];
+ __IO uint32_t LOCK_TIMEOUT_EN_CR;
+ uint32_t RESERVED1[5];
+ __IO uint32_t RDWR_ERR_SR;
+ } fic;
+} DDRCore_TypeDef;
+/*--------------------- MDDR APB Configuration Registers ---------------------*/
+ * MDDR core configuration registers.
+ * These registers are to be accessed as:
+ * MDDR->core.fic.<regname> = <value>;
+ * MDDR->core.phy.<regname> = <value>;
+ * MDDR->core.ddrc.<regname> = <value>;
+ DDRCore_TypeDef core;
+} MDDR_TypeDef;
+/*--------------------- FDDR APB Configuration Registers ---------------------*/
+ * FDDR core configuration registers. These are same as corresponding
+ * MDDR registers.
+ * FDDR->core.fic.<regname> = <value>;
+ * FDDR->core.phy.<regname> = <value>;
+ * FDDR->core.ddrc.<regname> = <value>;
+ __IO uint32_t RESERVED[39];
+ * FDDR system registers
+ * FDDR->sysreg.PLL_CONFIG_LOW_2 = 0x04u;
+ __IO uint32_t PLL_CONFIG_LOW_1;
+ __IO uint32_t PLL_CONFIG_LOW_2;
+ __IO uint32_t PLL_CONFIG_HIGH;
+ __IO uint32_t FACC_CLK_EN;
+ __IO uint32_t FACC_MUX_CONFIG;
+ __IO uint32_t FACC_DIVISOR_RATIO;
+ __IO uint32_t PLL_DELAY_LINE_SEL;
+ __IO uint32_t SOFT_RESET;
+ __IO uint32_t IO_CALIB;
+ __IO uint32_t INTERRUPT_ENABLE;
+ __IO uint32_t AXI_AHB_MODE_SEL;
+ __IO uint32_t PHY_SELF_REF_EN;
+ __IO uint32_t FAB_PLL_CLK_SR;
+ __IO uint32_t FPLL_CLK_SR;
+ __IO uint32_t CLK_CALIB_STATUS;
+ __IO uint32_t INTERRUPT_SR;
+ __IO uint32_t CLK_CALIB_CONFIG;
+ __IO uint32_t IO_CALIB_SR;
+ __IO uint32_t FATC_RESET;
+ } sysreg;
+} FDDR_TypeDef;
+/*------------------------------ SERDES Interface ----------------------------*/
+ AXI window
+ __IO uint32_t base;
+ __IO uint32_t size;
+ __IO uint32_t window_lsb;
+ __IO uint32_t window_msb;
+} axi_window_TypeDef;
+ PCI Express Bridge Core registers.
+ This data structure is used to access to the registers of the PCI Express
+ Bridge Core.
+ /*======================= Information registers ======================*/
+ /**
+ Information register: vendor_id & device_id
+ bits [15:0] vendor_id
+ bits [31:16] device_id
+ /* 0x000 */
+ __IO uint32_t VID_DEVID;
+ PCI Express Control & Status Register: cfg_prmscr
+ /* 0x004 */
+ __IO uint32_t CFG_PRMSCR;
+ Information register: class_code
+ /* 0x008 */
+ __IO uint32_t CLASS_CODE;
+ Bridge Configuration Register: bar0
+ /* 0x010 */
+ __IO uint32_t BAR0;
+ Bridge Configuration Register: bar1
+ /* 0x014 */
+ __IO uint32_t BAR1;
+ Bridge Configuration Register: bar2
+ /* 0x018 */
+ __IO uint32_t BAR2;
+ Bridge Configuration Register: bar3
+ /* 0x01C */
+ __IO uint32_t BAR3;
+ Bridge Configuration Register: bar4
+ /* 0x020 */
+ __IO uint32_t BAR4;
+ Bridge Configuration Register: bar5
+ /* 0x024 */
+ __IO uint32_t BAR5;
+ Information register: subsystem_id
+ /* 0x02C */
+ __IO uint32_t SUBSYSTEM_ID;
+ PCI Express Control & Status Register: pcie_devscr
+ /* 0x030 */
+ __IO uint32_t PCIE_DEVSCR;
+ PCI Express Control & Status Register: pcie_linkscr
+ /* 0x034 */
+ __IO uint32_t PCIE_LINKSCR;
+ Bridge Configuration Register: tc_vc_mapping
+ /* 0x038 */
+ __IO uint32_t TC_VC_MAPPING;
+ Information register: captured_bus_device_nb
+ /* 0x03C */
+ __IO uint32_t CAPTURED_BUS_DEVICE_NB;
+ Endpoint Interrupt register: msi_ctrl_status
+ /* 0x040 */
+ __IO uint32_t MSI_CTRL_STATUS;
+ Power Management register: ltssm
+ /* 0x044 */
+ __IO uint32_t LTSSM;
+ Power Management register: power_mgt_capability
+ /* 0x048 */
+ __IO uint32_t POWER_MGT_CAPABILITY;
+ PCI Express Control & Status Register: cfg_pmscr
+ /* 0x04C */
+ __IO uint32_t CFG_PMSCR;
+ Bridge Configuration Register: aer_ecrc_capability
+ /* 0x050 */
+ __IO uint32_t AER_ECRC_CAPABILITY;
+ Bridge Configuration Register: vc1_capability
+ /* 0x054 */
+ __IO uint32_t VC1_CAPABILITY;
+ Bridge Configuration Register: max_payload_size
+ /* 0x058 */
+ __IO uint32_t MAX_PAYLOAD_SIZE;
+ Bridge Configuration Register: clkreq
+ /* 0x05C */
+ __IO uint32_t CLKREQ;
+ Power Management register: aspm_l0s_capability
+ /* 0x060 */
+ __IO uint32_t ASPM_L0S_CAPABILITY;
+ Power Management register: aspm_l1_capability
+ /* 0x064 */
+ __IO uint32_t ASPM_L1_CAPABILITY;
+ Power Management register: timeout_completion
+ /* 0x068 */
+ __IO uint32_t TIMEOUT_COMPLETION;
+ Power Management register: pm_data_scale
+ /* 0x070 */
+ __IO uint32_t PM_DATA_SCALE[4];
+ Endpoint Interrupt register: msi
+ /* 0x080 */
+ __IO uint32_t MSI[8];
+ Bridge Configuration Register: error_counter
+ /* 0x0A0 */
+ __IO uint32_t ERROR_COUNTER[4];
+ Bridge Configuration Register: credit_allocation
+ /* 0x0B0 */
+ __IO uint32_t CREDIT_ALLOCATION[4];
+ Address Mapping register: axi_slave_window
+ /* 0x0C0 */
+ axi_window_TypeDef AXI_SLAVE_WINDOW[4];
+ Address Mapping register: axi_master_window
+ /* 0x100 */
+ axi_window_TypeDef AXI_MASTER_WINDOW[4];
+ Rootport Interrupt register: imask
+ /* 0x140 */
+ __IO uint32_t IMASK;
+ Rootport Interrupt register: istatus
+ /* 0x144 */
+ __IO uint32_t ISTATUS;
+ Rootport Interrupt register: icmd
+ /* 0x148 */
+ __IO uint32_t ICMD;
+ Rootport Interrupt register: irstatus
+ /* 0x14C */
+ __IO uint32_t IRSTATUS;
+ Rootport Interrupt register: imsiaddr
+ /* 0x150 */
+ __IO uint32_t IMSIADDR;
+ PCI Express Control & Status Register: slotcap
+ /* 0x154 */
+ __IO uint32_t SLOTCAP;
+ PCI Express Control & Status Register: slotcsr
+ /* 0x158 */
+ __IO uint32_t SLOTCSR;
+ PCI Express Control & Status Register: rootcsr
+ /* 0x15C */
+ __IO uint32_t ROOTCSR;
+ Configuration Register: cfg_control
+ /* 0x160 */
+ __IO uint32_t CFG_CONTROL;
+ Configuration Register: cfg_write_data
+ /* 0x164 */
+ __IO uint32_t CFG_WRITE_DATA;
+ Configuration Register: cfg_read_data
+ /* 0x168 */
+ __IO uint32_t CFG_READ_DATA;
+ Information register: info
+ /* 0x16C */
+ __IO uint32_t INFO;
+ Input/Output Control Register: io_control
+ /* 0x170 */
+ __IO uint32_t IO_CONTROL;
+ Input/Output Control Register: io_addr
+ /* 0x174 */
+ __IO uint32_t IO_ADDR;
+ Input/Output Control Register: io_write_data
+ /* 0x178 */
+ __IO uint32_t IO_WRITE_DATA;
+ Input/Output Control Register: io_read_data
+ /* 0x17C */
+ __IO uint32_t IO_READ_DATA;
+ Configuration Register: cfg_fbe
+ /* 0x180 */
+ __IO uint32_t CFG_FBE;
+ Address Mapping register: prefetch_io_window
+ /* 0x184 */
+ __IO uint32_t PREFETCH_IO_WINDOW;
+ __IO uint32_t RESERVED4[31];
+ Bridge Configuration Register: pcie_config
+ /* 0x204 */
+ __IO uint32_t PCIE_CONFIG;
+ __IO uint32_t RESERVED5[10];
+ PCI Express Control & Status Register: pcie_dev2scr
+ /* 0x230 */
+ __IO uint32_t PCIE_DEV2SCR;
+ PCI Express Control & Status Register: pcie_link2scr
+ /* 0x234 */
+ __IO uint32_t PCIE_LINK2SCR;
+ __IO uint32_t RESERVED6[10];
+ Power Management register: aspm_l0s_gen2 capability
+ /* 0x260 */
+ __IO uint32_t ASPM_L0S_GEN2;
+ __IO uint32_t RESERVED7[39];
+ Bridge Configuration Register: k_cnt_config
+ /* 0x300 */
+ __IO uint32_t K_CNT_CONFIG[6];
+ __IO uint32_t RESERVED8[826];
+} PCIE_TypeDef;
+ SERDESIF System Registers.
+ __IO uint32_t SER_PLL_CONFIG_LOW;
+ __IO uint32_t SER_PLL_CONFIG_HIGH;
+ __IO uint32_t SERDESIF_SOFT_RESET;
+ __IO uint32_t SER_INTERRUPT_ENABLE;
+ __IO uint32_t CONFIG_AXI_AHB_BRIDGE;
+ __IO uint32_t CONFIG_ECC_INTR_ENABLE;
+ __IO uint32_t CONFIG_TEST_IN;
+ __IO uint32_t TEST_OUT_READ_ADDR;
+ __IO uint32_t CONFIG_PCIE_PM;
+ __IO uint32_t CONFIG_PHY_MODE_0;
+ __IO uint32_t CONFIG_PHY_MODE_1;
+ __IO uint32_t CONFIG_PHY_MODE_2;
+ __IO uint32_t CONFIG_PCIE_0;
+ __IO uint32_t CONFIG_PCIE_1;
+ __IO uint32_t CONFIG_PCIE_2;
+ __IO uint32_t CONFIG_PCIE_3;
+ __IO uint32_t CONFIG_BAR_SIZE_0_1;
+ __IO uint32_t CONFIG_BAR_SIZE_2_3;
+ __IO uint32_t CONFIG_BAR_SIZE_3_4;
+ __IO uint32_t SER_CLK_STATUS;
+ __IO uint32_t SER_CLK_CALIB_STATUS;
+ __IO uint32_t TEST_OUT_READ_DATA;
+ __IO uint32_t SER_INTERRUPT;
+ __IO uint32_t SERDESIF_INTR_STATUS;
+ __IO uint32_t SER_CLK_CALIB_CONFIG;
+ __IO uint32_t REFCLK_SEL;
+ __IO uint32_t PCLK_SEL;
+ __IO uint32_t EPCS_RSTN_SEL;
+ __IO uint32_t CHIP_ENABLES;
+ __IO uint32_t SERDES_TEST_OUT;
+ __IO uint32_t SERDES_FATC_RESET;
+ __IO uint32_t RC_OSC_SPLL_REFCLK_SEL;
+ __IO uint32_t SPREAD_SPECTRUM_CLK;
+ __IO uint32_t CONF_AXI_MSTR_WNDW_0;
+ __IO uint32_t CONF_AXI_MSTR_WNDW_1;
+ __IO uint32_t CONF_AXI_MSTR_WNDW_2;
+ __IO uint32_t CONF_AXI_MSTR_WNDW_3;
+ __IO uint32_t CONF_AXI_SLV_WNDW_0;
+ __IO uint32_t CONF_AXI_SLV_WNDW_1;
+ __IO uint32_t CONF_AXI_SLV_WNDW_2;
+ __IO uint32_t CONF_AXI_SLV_WNDW_3;
+ __IO uint32_t DESKEW_CONFIG;
+ __IO uint32_t DEBUG_MODE_KEY;
+ * The following registers are only available on the M2S090.
+ __IO uint32_t IDDQ;
+ __IO uint32_t ADVCONFIG;
+ __IO uint32_t ADVSTATUS;
+ __IO uint32_t ECC_ERR_INJECT;
+ __IO uint32_t ENHANCEMENT;
+ __IO uint32_t RESERVED5;
+ __IO uint32_t RESERVED7;
+ __IO uint32_t RESERVED8;
+ __IO uint32_t RESERVED9;
+ __IO uint32_t RESERVED10;
+ __IO uint32_t RESERVED11;
+ __IO uint32_t RESERVED12;
+ __IO uint32_t RESERVED13;
+ __IO uint32_t RESERVED14;
+ __IO uint32_t RESERVED15;
+ __IO uint32_t RESERVED16;
+ __IO uint32_t RESERVED17;
+ __IO uint32_t RESERVED18;
+ __IO uint32_t RESERVED19;
+ __IO uint32_t RESERVED20;
+ __IO uint32_t CONFIG2_AXI_AHB_BRIDGE;
+ __IO uint32_t CONFIG2_ECC_INTR_ENABLE;
+ __IO uint32_t CONFIG2_TEST_IN;
+ __IO uint32_t TEST2_OUT_READ_ADDR;
+ __IO uint32_t CONFIG2_PCIE_PM;
+ __IO uint32_t RESERVED21;
+ __IO uint32_t RESERVED22;
+ __IO uint32_t RESERVED23;
+ __IO uint32_t CONFIG2_PCIE_0;
+ __IO uint32_t CONFIG2_PCIE_1;
+ __IO uint32_t CONFIG2_PCIE_2;
+ __IO uint32_t CONFIG2_PCIE_3;
+ __IO uint32_t CONFIG2_BAR_SIZE_0_1;
+ __IO uint32_t CONFIG2_BAR_SIZE_2_3;
+ __IO uint32_t CONFIG2_BAR_SIZE_3_4;
+ __IO uint32_t RESERVED24;
+ __IO uint32_t RESERVED25;
+ __IO uint32_t TEST2_OUT_READ_DATA;
+ __IO uint32_t RESERVED26;
+ __IO uint32_t SERDESIF2_INTR_STATUS;
+ __IO uint32_t RESERVED27;
+ __IO uint32_t RESERVED28;
+ __IO uint32_t RESERVED29;
+ __IO uint32_t RESERVED30;
+ __IO uint32_t RESERVED31;
+ __IO uint32_t RESERVED32;
+ __IO uint32_t RESERVED33;
+ __IO uint32_t RESERVED34;
+ __IO uint32_t RESERVED35;
+ __IO uint32_t CONF2_AXI_MSTR_WNDW_0;
+ __IO uint32_t CONF2_AXI_MSTR_WNDW_1;
+ __IO uint32_t CONF2_AXI_MSTR_WNDW_2;
+ __IO uint32_t CONF2_AXI_MSTR_WNDW_3;
+ __IO uint32_t CONF2_AXI_SLV_WNDW_0;
+ __IO uint32_t CONF2_AXI_SLV_WNDW_1;
+ __IO uint32_t CONF2_AXI_SLV_WNDW_2;
+ __IO uint32_t CONF2_AXI_SLV_WNDW_3;
+ __IO uint32_t RESERVED36;
+ __IO uint32_t RESERVED37;
+ __IO uint32_t RESERVED38;
+ __IO uint32_t RESERVED39;
+ __IO uint32_t ADVCONFIG2;
+ __IO uint32_t ADVSTATUS2;
+ __IO uint32_t ECC_ERR_INJECT2;
+} SERDES_INTF_SYSREG_TypeDef;
+ SERDES PHY registers
+ Control register 0
+ __IO uint32_t CR0;
+ Clock count for error counter decrement
+ __IO uint32_t ERRCNT_DEC;
+ Error counter threshold - Rx idle detect max latency
+ __IO uint32_t RXIDLE_MAX_ERRCNT_THR;
+ Tx Impedance ratio
+ __IO uint32_t IMPED_RATIO;
+ PLL F settings and PCLK ratio
+ __IO uint32_t PLL_F_PCLK_RATIO;
+ PLL M & N settings
+ __IO uint32_t PLL_M_N;
+ 250ns timer base count
+ __IO uint32_t CNT250NS_MAX;
+ Rx Equalization amplitude ratio
+ __IO uint32_t RE_AMP_RATIO;
+ Rx Equalization Cut frequency
+ __IO uint32_t RE_CUT_RATIO;
+ Tx Amplitude ratio
+ __IO uint32_t TX_AMP_RATIO;
+ Tx Post-Cursor ratio
+ __IO uint32_t TX_PST_RATIO;
+ Tx Pre-Cursor ratio
+ __IO uint32_t TX_PRE_RATIO;
+ End of calibration counter
+ __IO uint32_t ENDCALIB_MAX;
+ Calibration stability counter
+ __IO uint32_t CALIB_STABILITY_COUNT;
+ Power down feature
+ __IO uint32_t POWER_DOWN;
+ Rx offset counter
+ __IO uint32_t RX_OFFSET_COUNT;
+ PLL F settings and PCLK ratio (in PCIe 5 Gbps speed)
+ __IO uint32_t PLL_F_PCLK_RATIO_5GBPS;
+ PLL M & N sttings (in PCIe 5 Gbps spped)
+ __IO uint32_t PLL_M_N_5GBPS;
+ 250ns timer base count (in PCIe 5 Gbps speed)
+ __IO uint32_t CNT250NS_MAX_5GBPS;
+ reserved
+ Tx Post-Cursor ratio with TxDeemp=0, Full swing
+ __IO uint32_t TX_PST_RATIO_DEEMP0_FULL;
+ Tx Pre-Cursor ratio TxDeemp=0, full swing
+ __IO uint32_t TX_PRE_RATIO_DEEMP0_FULL;
+ Tx Post-Cursor ratio with TxDeemp=1, Full swing
+ __IO uint32_t TX_PST_RATIO_DEEMP1_FULL;
+ Tx Pre-Cursor ratio TxDeemp=1, full swing
+ __IO uint32_t TX_PRE_RATIO_DEEMP1_FULL;
+ Tx Amplitude ratio TxMargin=0, full swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN0_FULL;
+ Tx Amplitude ratio TxMargin=1, full swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN1_FULL;
+ Tx Amplitude ratio TxMargin=2, full swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN2_FULL;
+ Tx Amplitude ratio TxMargin=3, full swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN3_FULL;
+ Tx Amplitude ratio TxMargin=4, full swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN4_FULL;
+ Tx Amplitude ratio TxMargin=5, full swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN5_FULL;
+ Tx Amplitude ratio TxMargin=6, full swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN6_FULL;
+ Tx Amplitude ratio TxMargin=7, full swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN7_FULL;
+ Rx Equalization amplitude ratio TxDeemp=0
+ __IO uint32_t RE_AMP_RATIO_DEEMP0;
+ Rx Equalization Cut frequency TxDeemp=0
+ __IO uint32_t RE_CUT_RATIO_DEEMP0;
+ Rx Equalization amplitude ratio TxDeemp=1
+ __IO uint32_t RE_AMP_RATIO_DEEMP1;
+ Rx Equalization Cut frequency TxDeemp=1
+ __IO uint32_t RE_CUT_RATIO_DEEMP1;
+ Tx Post-Cursor ratio with TxDeemp=0, Half swing
+ __IO uint32_t TX_PST_RATIO_DEEMP0_HALF;
+ Tx Pre-Cursor ratio TxDeemp=0, Half swing
+ __IO uint32_t TX_PRE_RATIO_DEEMP0_HALF;
+ Tx Post-Cursor ratio with TxDeemp=1, Half swing
+ __IO uint32_t TX_PST_RATIO_DEEMP1_HALF;
+ Tx Pre-Cursor ratio TxDeemp=1, Half swing
+ __IO uint32_t TX_PRE_RATIO_DEEMP1_HALF;
+ Tx Amplitude ratio TxMargin=0, Half swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN0_HALF;
+ Tx Amplitude ratio TxMargin=1, Half swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN1_HALF;
+ Tx Amplitude ratio TxMargin=2, Half swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN2_HALF;
+ Tx Amplitude ratio TxMargin=3, Half swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN3_HALF;
+ Tx Amplitude ratio TxMargin=4, Half swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN4_HALF;
+ Tx Amplitude ratio TxMargin=5, Half swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN5_HALF;
+ Tx Amplitude ratio TxMargin=6, Half swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN6_HALF;
+ Tx Amplitude ratio TxMargin=7, Half swing
+ __IO uint32_t TX_AMP_RATIO_MARGIN7_HALF;
+ PMA status
+ __IO uint32_t PMA_STATUS;
+ Tx sweep center (RO)
+ __IO uint32_t TX_SWEEP_CENTER;
+ Rx seep center (RO)
+ __IO uint32_t RX_SWEEP_CENTER;
+ Rx Equalization sweep center (RO)
+ __IO uint32_t RE_SWEEP_CENTER;
+ Receiver Shift Loader parameter 0 (RO)
+ __IO uint32_t ATXDRR_7_0;
+ Receiver Shift Loader parameter 1 (RO)
+ __IO uint32_t ATXDRR_14_8;
+ Transmitter P Shift Loader parameter0-0
+ __IO uint32_t ATXDRP_DYN_7_0;
+ Transmitter P Shift Loader parameter0-1
+ __IO uint32_t ATXDRP_DYN_15_8;
+ Transmitter P Shift Loader parameter0-2
+ __IO uint32_t ATXDRP_DYN_20_16;
+ Transmitter A Shift Loader parameter0-0
+ __IO uint32_t ATXDRA_DYN_7_0;
+ Transmitter A Shift Loader parameter0-1
+ __IO uint32_t ATXDRA_DYN_15_8;
+ Transmitter A Shift Loader parameter0-2
+ __IO uint32_t ATXDRA_DYN_20_16;
+ Transmitter T Shift Loader parameter0-0
+ __IO uint32_t ATXDRT_DYN_7_0;
+ Transmitter T Shift Loader parameter0-1
+ __IO uint32_t ATXDRT_DYN_15_8;
+ Transmitter T Shift Loader parameter0-2
+ __IO uint32_t ATXDRT_DYN_20_16;
+ Transmitter P Shift Loader parameter 1-0 (RO)
+ __IO uint32_t ATXDRP_EI1_7_0;
+ Transmitter P Shift Loader parameter 1-1 (RO)
+ __IO uint32_t ATXDRP_EI1_15_8;
+ Transmitter P Shift Loader parameter 1-2 (RO)
+ __IO uint32_t ATXDRP_EI1_20_16;
+ Transmitter A Shift Loader parameter 1-0 (RO)
+ __IO uint32_t ATXDRA_EI1_7_0;
+ Transmitter A Shift Loader parameter 1-1 (RO)
+ __IO uint32_t ATXDRA_EI1_15_8;
+ Transmitter A Shift Loader parameter 1-2 (RO)
+ __IO uint32_t ATXDRA_EI1_20_16;
+ Transmitter T Shift Loader parameter 1-0 (RO)
+ __IO uint32_t ATXDRT_EI1_7_0;
+ Transmitter T Shift Loader parameter 1-1 (RO)
+ __IO uint32_t ATXDRT_EI1_15_8;
+ Transmitter T Shift Loader parameter 1-2 (RO)
+ __IO uint32_t ATXDRT_EI1_20_16;
+ Transmitter P shift Loader parameter 2-0 (RO)
+ __IO uint32_t ATXDRP_EI2_7_0;
+ Transmitter P shift Loader parameter 2-1 (RO)
+ __IO uint32_t ATXDRP_EI2_15_8;
+ Transmitter P shift Loader parameter 2-2 (RO)
+ __IO uint32_t ATXDRP_EI2_20_16;
+ Transmitter A Shift parametr 2-0 (RO)
+ __IO uint32_t ATXDRA_EI2_7_0;
+ Transmitter A Shift parametr 2-1 (RO)
+ __IO uint32_t ATXDRA_EI2_15_8;
+ Transmitter A Shift parametr 2-2 (RO)
+ __IO uint32_t ATXDRA_EI2_20_16;
+ Transmitter T Shift parametr 2-0 (RO)
+ __IO uint32_t ATXDRT_EI2_7_0;
+ Transmitter T Shift parametr 2-1 (RO)
+ __IO uint32_t ATXDRT_EI2_15_8;
+ Transmitter T Shift parametr 2-2 (RO)
+ __IO uint32_t ATXDRT_EI2_20_16;
+ Override calibration register (RW)
+ __IO uint32_t OVERRIDE_CALIB;
+ Force Receiver Shift Loader parameter 0 (RW)
+ __IO uint32_t FORCE_ATXDRR_7_0;
+ Force Receiver Shift Loader parameter 1 (RW)
+ __IO uint32_t FORCE_ATXDRR_15_8;
+ Force Receiver Shift Loader parameter 2 (RW)
+ __IO uint32_t FORCE_ATXDRR_20_16;
+ Force Transmitter P Shift Loader parameter 0 (RW)
+ __IO uint32_t FORCE_ATXDRP_7_0;
+ Force Transmitter P Shift Loader parameter 1 (RW)
+ __IO uint32_t FORCE_ATXDRP_15_8;
+ Force Transmitter P Shift Loader parameter 2 (RW)
+ __IO uint32_t FORCE_ATXDRP_20_16;
+ Force Transmitter A Shift Loader parameter 0 (RW)
+ __IO uint32_t FORCE_ATXDRA_7_0;
+ Force Transmitter A Shift Loader parameter 1 (RW)
+ __IO uint32_t FORCE_ATXDRA_15_8;
+ Force Transmitter A Shift Loader parameter 2 (RW)
+ __IO uint32_t FORCE_ATXDRA_20_16;
+ Force Transmitter T Shift parameter 0-0 (RO)
+ __IO uint32_t FORCE_ATXDRT_7_0;
+ Force Transmitter T Shift parameter 0-1 (RO)
+ __IO uint32_t FORCE_ATXDRT_15_8;
+ Force Transmitter T Shift parameter 0-2 (RO)
+ __IO uint32_t FORCE_ATXDRT_20_16;
+ RxD offset calibration result (RO)
+ __IO uint32_t RXD_OFFSET_CALIB_RESULT;
+ RxT offset calibration result (RO)
+ __IO uint32_t RXT_OFFSET_CALIB_RESULT;
+ Schmitt trigger calibration result (RO)
+ __IO uint32_t SCHMITT_TRIG_CALIB_RESULT;
+ Force RxD offset calibration settings (RW)
+ __IO uint32_t FORCE_RXD_OFFSET_CALIB;
+ Force RxT offset calibration settings (RW)
+ __IO uint32_t FORCE_RXT_OFFSET_CALIB;
+ Force Schmitt trigger calibration settings (RW)
+ __IO uint32_t FORCE_SCHMITT_TRIG_CALIB;
+ PRBS control register (RW)
+ __IO uint32_t PRBS_CTRL;
+ PRBS error counter register (RO)
+ __IO uint32_t PRBS_ERRCNT;
+ PHY reset override register (RW)
+ __IO uint32_t PHY_RESET_OVERRIDE;
+ PHY power override register (RW)
+ __IO uint32_t PHY_POWER_OVERRIDE;
+ Custom Pattern Byte 0 (RW)
+ __IO uint32_t CUSTOM_PATTERN_7_0;
+ Custom Pattern Byte 1 (RW)
+ __IO uint32_t CUSTOM_PATTERN_15_8;
+ Custom Pattern Byte 2 (RW)
+ __IO uint32_t CUSTOM_PATTERN_23_16;
+ Custom Pattern Byte 3 (RW)
+ __IO uint32_t CUSTOM_PATTERN_31_24;
+ Custom Pattern Byte 4 (RW)
+ __IO uint32_t CUSTOM_PATTERN_39_32;
+ Custom Pattern Byte 5 (RW)
+ __IO uint32_t CUSTOM_PATTERN_47_40;
+ Custom Pattern Byte 6 (RW)
+ __IO uint32_t CUSTOM_PATTERN55_48;
+ Custom Pattern Byte 7 (RW)
+ __IO uint32_t CUSTOM_PATTERN_63_56;
+ Custom Pattern Byte 8 (RW)
+ __IO uint32_t CUSTOM_PATTERN_71_64;
+ Custom Pattern Byte 9 (RW)
+ __IO uint32_t CUSTOM_PATTERN_79_72;
+ Custom Pattern Control (RW)
+ __IO uint32_t CUSTOM_PATTERN_CTRL;
+ Custom Pattern Status register (RO)
+ __IO uint32_t CUSTOM_PATTERN_STATUS;
+ PCS Loopback Control (RW)
+ __IO uint32_t PCS_LOOPBBACK_CTRL;
+ Gen1 Transmit PLL Current Charge Pump (RW)
+ __IO uint32_t GEN1_TX_PLL_CCP;
+ Gen1 Receive PLL Current Charge Pump (RW)
+ __IO uint32_t GEN1_RX_PLL_CCP;
+ Gen2 Transmit PLL Current Charge Pump (RW)
+ __IO uint32_t GEN2_TX_PLL_CCP;
+ Gen2 Receive PLL Current Charge Pump (RW)
+ __IO uint32_t GEN2_RX_PLL_CCP;
+ CDR PLL manual control
+ __IO uint32_t CDR_PLL_MANUAL_CR;
+ Reserved0
+ __IO uint32_t RESERVED0[6];
+ Update settings command register
+ __IO uint32_t UPDATE_SETTINGS;
+ Reserved1
+ __IO uint32_t RESERVED1[31];
+ PRBS first error cycle counter bits [7:0]
+ __IO uint32_t PRBS_ERR_CYC_FIRST_7_0;
+ PRBS first error cycle counter bits [15:8]
+ __IO uint32_t PRBS_ERR_CYC_FIRST_15_8;
+ PRBS first error cycle counter bits [23:16]
+ __IO uint32_t PRBS_ERR_CYC_FIRST_23_16;
+ PRBS first error cycle counter bits [31:24]
+ __IO uint32_t PRBS_ERR_CYC_FIRST_31_24;
+ PRBS first error cycle counter bits [39:32]
+ __IO uint32_t PRBS_ERR_CYC_FIRST_39_32;
+ PRBS first error cycle counter bits [47:40]
+ __IO uint32_t PRBS_ERR_CYC_FIRST_47_40;
+ PRBS first error cycle counter bits [49:48]
+ __IO uint32_t PRBS_ERR_CYC_FIRST_49_48;
+ Reserved2
+ PRBS last error cycle counter bits [7:0]
+ __IO uint32_t PRBS_ERR_CYC_LAST_7_0;
+ PRBS last error cycle counter bits [15:8]
+ __IO uint32_t PRBS_ERR_CYC_LAST_15_8;
+ PRBS last error cycle counter bits [23:16]
+ __IO uint32_t PRBS_ERR_CYC_LAST_23_16;
+ PRBS last error cycle counter bits [31:24]
+ __IO uint32_t PRBS_ERR_CYC_LAST_31_24;
+ PRBS last error cycle counter bits [39:32]
+ __IO uint32_t PRBS_ERR_CYC_LAST_39_32;
+ PRBS last error cycle counter bits [47:40]
+ __IO uint32_t PRBS_ERR_CYC_LAST_47_40;
+ PRBS last error cycle counter bits [49:48]
+ __IO uint32_t PRBS_ERR_CYC_LAST_49_48;
+ Reserved3
+ __IO uint32_t RESERVED3[81];
+} SERDES_TypeDef;
+/*-------------------------------------------------------------------------*//**
+ The serdesif_regs_t data structure provides access to the complete set of the
+ SERDES Interface hardware block configuration registers. These registers are
+ accessed through the APB interface of the SERDES Interface hardware block.
+ PCIe core registers.
+ PCIE_TypeDef core;
+ SERDES macro registers.
+ SERDES_TypeDef lane[4];
+ SERDESIF system registers.
+ SERDES_INTF_SYSREG_TypeDef sys_regs;
+} SERDESIF_TypeDef;
+/*------------------------------ System Registers ----------------------------*/
+ __IO uint32_t ESRAM_CR; /*0X0 */
+ __IO uint32_t ESRAM_MAX_LAT_CR; /*0X4 */
+ __IO uint32_t DDR_CR; /*0X8 */
+ __IO uint32_t ENVM_CR; /*0XC */
+ __IO uint32_t ENVM_REMAP_BASE_CR; /*0X10 */
+ __IO uint32_t ENVM_REMAP_FAB_CR; /*0X14 */
+ __IO uint32_t CC_CR; /*0X18 */
+ __IO uint32_t CC_REGION_CR; /*0X1C */
+ __IO uint32_t CC_LOCK_BASE_ADDR_CR; /*0X20 */
+ __IO uint32_t CC_FLUSH_INDX_CR; /*0X24 */
+ __IO uint32_t DDRB_BUF_TIMER_CR; /*0X28 */
+ __IO uint32_t DDRB_NB_ADDR_CR; /*0X2C */
+ __IO uint32_t DDRB_NB_SIZE_CR; /*0X30 */
+ __IO uint32_t DDRB_CR; /*0X34 */
+ __IO uint32_t EDAC_CR; /*0X38 */
+ __IO uint32_t MASTER_WEIGHT0_CR; /*0X3C */
+ __IO uint32_t MASTER_WEIGHT1_CR; /*0X40 */
+ __IO uint32_t SOFT_IRQ_CR; /*0X44 */
+ __IO uint32_t SOFT_RST_CR; /*0X48 */
+ __IO uint32_t M3_CR; /*0X4C */
+ __IO uint32_t FAB_IF_CR; /*0X50 */
+ __IO uint32_t LOOPBACK_CR; /*0X54 */
+ __IO uint32_t GPIO_SYSRESET_SEL_CR; /*0X58 */
+ __IO uint32_t GPIN_SRC_SEL_CR; /*0X5C */
+ __IO uint32_t MDDR_CR; /*0X60 */
+ __IO uint32_t USB_IO_INPUT_SEL_CR; /*0X64 */
+ __IO uint32_t PERIPH_CLK_MUX_SEL_CR; /*0X68 */
+ __IO uint32_t WDOG_CR; /*0X6C */
+ __IO uint32_t MDDR_IO_CALIB_CR; /*0X70 */
+ __IO uint32_t SPARE_OUT_CR; /*0X74 */
+ __IO uint32_t EDAC_IRQ_ENABLE_CR; /*0X78 */
+ __IO uint32_t USB_CR; /*0X7C */
+ __IO uint32_t ESRAM_PIPELINE_CR; /*0X80 */
+ __IO uint32_t MSS_IRQ_ENABLE_CR; /*0X84 */
+ __IO uint32_t RTC_WAKEUP_CR; /*0X88 */
+ __IO uint32_t MAC_CR; /*0X8C */
+ __IO uint32_t MSSDDR_PLL_STATUS_LOW_CR; /*0X90 */
+ __IO uint32_t MSSDDR_PLL_STATUS_HIGH_CR; /*0X94 */
+ __IO uint32_t MSSDDR_FACC1_CR; /*0X98 */
+ __IO uint32_t MSSDDR_FACC2_CR; /*0X9C */
+ __IO uint32_t PLL_LOCK_EN_CR; /*0XA0 */
+ __IO uint32_t MSSDDR_CLK_CALIB_CR; /*0XA4 */
+ __IO uint32_t PLL_DELAY_LINE_SEL_CR; /*0XA8 */
+ __IO uint32_t MAC_STAT_CLRONRD_CR; /*0XAC */
+ __IO uint32_t RESET_SOURCE_CR; /*0XB0 */
+ __I uint32_t CC_DC_ERR_ADDR_SR; /*0XB4 */
+ __I uint32_t CC_IC_ERR_ADDR_SR; /*0XB8 */
+ __I uint32_t CC_SB_ERR_ADDR_SR; /*0XBC */
+ __I uint32_t CC_DECC_ERR_ADDR_SR; /*0XC0 */
+ __I uint32_t CC_IC_MISS_CNT_SR; /*0XC4 */
+ __I uint32_t CC_IC_HIT_CNT_SR; /*0XC8 */
+ __I uint32_t CC_DC_MISS_CNT_SR; /*0XCC */
+ __I uint32_t CC_DC_HIT_CNT_SR; /*0XD0 */
+ __I uint32_t CC_IC_TRANS_CNT_SR; /*0XD4 */
+ __I uint32_t CC_DC_TRANS_CNT_SR; /*0XD8 */
+ __I uint32_t DDRB_DS_ERR_ADR_SR; /*0XDC */
+ __I uint32_t DDRB_HPD_ERR_ADR_SR; /*0XE0 */
+ __I uint32_t DDRB_SW_ERR_ADR_SR; /*0XE4 */
+ __I uint32_t DDRB_BUF_EMPTY_SR; /*0XE8 */
+ __I uint32_t DDRB_DSBL_DN_SR; /*0XEC */
+ __I uint32_t ESRAM0_EDAC_CNT; /*0XF0 */
+ __I uint32_t ESRAM1_EDAC_CNT; /*0XF4 */
+ __I uint32_t CC_EDAC_CNT; /*0XF8 */
+ __I uint32_t MAC_EDAC_TX_CNT; /*0XFC */
+ __I uint32_t MAC_EDAC_RX_CNT; /*0X100 */
+ __I uint32_t USB_EDAC_CNT; /*0X104 */
+ __I uint32_t CAN_EDAC_CNT; /*0X108 */
+ __I uint32_t ESRAM0_EDAC_ADR; /*0X10C */
+ __I uint32_t ESRAM1_EDAC_ADR; /*0X110 */
+ __I uint32_t MAC_EDAC_RX_ADR; /*0X114 */
+ __I uint32_t MAC_EDAC_TX_ADR; /*0X118 */
+ __I uint32_t CAN_EDAC_ADR; /*0X11C */
+ __I uint32_t USB_EDAC_ADR; /*0X120 */
+ __I uint32_t MM0_1_2_SECURITY; /*0X124 */
+ __I uint32_t MM4_5_FIC64_SECURITY; /*0X128 */
+ __I uint32_t MM3_6_7_8_SECURITY; /*0X12C */
+ __I uint32_t MM9_SECURITY; /*0X130 */
+ __I uint32_t M3_SR; /*0X134 */
+ __I uint32_t ETM_COUNT_LOW; /*0X138 */
+ __I uint32_t ETM_COUNT_HIGH; /*0X13C */
+ __I uint32_t DEVICE_SR; /*0X140 */
+ __I uint32_t ENVM_PROTECT_USER; /*0X144 */
+ __I uint32_t ENVM_STATUS; /*0X148 */
+ __I uint32_t DEVICE_VERSION; /*0X14C */
+ __I uint32_t MSSDDR_PLL_STATUS; /*0X150 */
+ __I uint32_t USB_SR; /*0X154 */
+ __I uint32_t ENVM_SR; /*0X158 */
+ __I uint32_t SPARE_IN; /*0X15C */
+ __I uint32_t DDRB_STATUS; /*0X160 */
+ __I uint32_t MDDR_IO_CALIB_STATUS; /*0X164 */
+ __I uint32_t MSSDDR_CLK_CALIB_STATUS; /*0X168 */
+ __I uint32_t WDOGLOAD; /*0X16C */
+ __I uint32_t WDOGMVRP; /*0X170 */
+ __I uint32_t USERCONFIG0; /*0X174 */
+ __I uint32_t USERCONFIG1; /*0X178 */
+ __I uint32_t USERCONFIG2; /*0X17C */
+ __I uint32_t USERCONFIG3; /*0X180 */
+ __I uint32_t FAB_PROT_SIZE; /*0X184 */
+ __I uint32_t FAB_PROT_BASE; /*0X188 */
+ __I uint32_t MSS_GPIO_DEF; /*0X18C */
+ __IO uint32_t EDAC_SR; /*0X190 */
+ __IO uint32_t MSS_INTERNAL_SR; /*0X194 */
+ __IO uint32_t MSS_EXTERNAL_SR; /*0X198 */
+ __IO uint32_t WDOGTIMEOUTEVENT; /*0X19C */
+ __IO uint32_t CLR_MSS_COUNTERS; /*0X1A0 */
+ __IO uint32_t CLR_EDAC_COUNTERS; /*0X1A4 */
+ __IO uint32_t FLUSH_CR; /*0X1A8 */
+ __IO uint32_t MAC_STAT_CLR_CR; /*0X1AC */
+ __IO uint32_t IOMUXCELL_CONFIG[57]; /*0X1B0 */
+ __I uint32_t NVM_PROTECT_FACTORY; /*0X294 */
+ __I uint32_t DEVICE_STATUS_FIXED; /*0X298 */
+ __I uint32_t MBIST_ES0; /*0X29C */
+ __I uint32_t MBIST_ES1; /*0X2A0 */
+ __IO uint32_t MSDDR_PLL_STAUS_1; /*0X2A4 */
+ __I uint32_t REDUNDANCY_ESRAM0; /*0X2A8 */
+ __I uint32_t REDUNDANCY_ESRAM1; /*0X2AC */
+ __I uint32_t SERDESIF; /*0X2B0 */
+} SYSREG_TypeDef;
+#define SYSREG_ENVM0_SOFTRESET_MASK ( (uint32_t)0x01u << 0u )
+#define SYSREG_ENVM1_SOFTRESET_MASK ( (uint32_t)0x01u << 1u )
+#define SYSREG_ESRAM0_SOFTRESET_MASK ( (uint32_t)0x01u << 2u )
+#define SYSREG_ESRAM1_SOFTRESET_MASK ( (uint32_t)0x01u << 3u )
+#define SYSREG_MAC_SOFTRESET_MASK ( (uint32_t)0x01u << 4u )
+#define SYSREG_PDMA_SOFTRESET_MASK ( (uint32_t)0x01u << 5u )
+#define SYSREG_TIMER_SOFTRESET_MASK ( (uint32_t)0x01u << 6u )
+#define SYSREG_MMUART0_SOFTRESET_MASK ( (uint32_t)0x01u << 7u )
+#define SYSREG_MMUART1_SOFTRESET_MASK ( (uint32_t)0x01u << 8u )
+#define SYSREG_SPI0_SOFTRESET_MASK ( (uint32_t)0x01u << 9u )
+#define SYSREG_SPI1_SOFTRESET_MASK ( (uint32_t)0x01u << 10u )
+#define SYSREG_I2C0_SOFTRESET_MASK ( (uint32_t)0x01u << 11u )
+#define SYSREG_I2C1_SOFTRESET_MASK ( (uint32_t)0x01u << 12u )
+#define SYSREG_CAN_SOFTRESET_MASK ( (uint32_t)0x01u << 13u )
+#define SYSREG_USB_SOFTRESET_MASK ( (uint32_t)0x01u << 14u )
+#define SYSREG_COMBLK_SOFTRESET_MASK ( (uint32_t)0x01u << 15u )
+#define SYSREG_FPGA_SOFTRESET_MASK ( (uint32_t)0x01u << 16u )
+#define SYSREG_HPDMA_SOFTRESET_MASK ( (uint32_t)0x01u << 17u )
+#define SYSREG_FIC32_0_SOFTRESET_MASK ( (uint32_t)0x01u << 18u )
+#define SYSREG_FIC32_1_SOFTRESET_MASK ( (uint32_t)0x01u << 19u )
+#define SYSREG_GPIO_SOFTRESET_MASK ( (uint32_t)0x01u << 20u )
+#define SYSREG_GPIO_7_0_SOFTRESET_MASK ( (uint32_t)0x01u << 21u )
+#define SYSREG_GPIO_15_8_SOFTRESET_MASK ( (uint32_t)0x01u << 22u )
+#define SYSREG_GPIO_23_16_SOFTRESET_MASK ( (uint32_t)0x01u << 23u )
+#define SYSREG_GPIO_31_24_SOFTRESET_MASK ( (uint32_t)0x01u << 24u )
+#define SYSREG_MDDR_SOFTRESET_MASK ( (uint32_t)0x01u << 25u )
+#define SYSREG_FIC64_SOFTRESET_MASK ( (uint32_t)0x01u << 26u )
+/*-------------------------- CoreSF2Config Registers -------------------------*/
+ __IO uint32_t CONFIG_DONE;
+ __I uint32_t INIT_DONE;
+ __IO uint32_t CLR_INIT_DONE;
+ __I uint32_t CONFIG_SR;
+ __IO uint32_t SOFT_RESET_CR;
+ __I uint32_t IP_VERSION_SR;
+} CoreSF2Config_TypeDef;
+/* Peripheral memory map */
+#define UART0_BASE 0x40000000u
+#define SPI0_BASE 0x40001000u
+#define I2C0_BASE 0x40002000u
+#define PDMA_BASE 0x40003000u
+#define TIMER_BASE 0x40004000u
+#define WATCHDOG_BASE 0x40005000u
+#define H2F_IRQ_CTRL_BASE 0x40006000u
+#define UART1_BASE 0x40010000u
+#define SPI1_BASE 0x40011000u
+#define I2C1_BASE 0x40012000u
+#define GPIO_BASE 0x40013000u
+#define HPDMA_BASE 0x40014000u
+#define CAN_BASE 0x40015000u
+#define COMBLK_BASE 0x40016000u
+#define RTC_BASE 0x40017000u
+#define DDR0_CFG_BASE 0x40020800u
+#define DDR1_CFG_BASE 0x40021000u
+#define CORE_SF2_CFG_BASE 0x40022000u
+#define SERDES0_CFG_BASE 0x40028000u
+#define SERDES1_CFG_BASE 0x4002C000u
+#define SERDES2_CFG_BASE 0x40030000u
+#define SERDES3_CFG_BASE 0x40034000u
+#define SYSREG_BASE 0x40038000u
+#define ETHERNET_BASE 0x40041000u
+#define USB_BASE 0x40043000u
+#define ENVM1_BASE 0x60080000u
+#define ENVM2_BASE 0x600C0000u
+/* bitband address calculation macro */
+#define BITBAND_ADDRESS(X) ((X & 0xF0000000U) + 0x02000000U + ((X & 0xFFFFFU) << 5))
+/* Peripheral declaration */
+#define UART0 ((UART_TypeDef *) UART0_BASE)
+#define SPI0 ((SPI_TypeDef *) SPI0_BASE)
+#define I2C0 ((I2C_TypeDef *) I2C0_BASE)
+#define I2C0_BITBAND ((I2C_BitBand_TypeDef *) BITBAND_ADDRESS(I2C0_BASE))
+#define MAC ((MAC_TypeDef *) ETHERNET_BASE)
+#define PDMA ((PDMA_TypeDef *) PDMA_BASE)
+#define TIMER ((TIMER_TypeDef *) TIMER_BASE)
+#define TIMER_BITBAND ((TIMER_BitBand_TypeDef *) BITBAND_ADDRESS(TIMER_BASE))
+#define WATCHDOG ((WATCHDOG_TypeDef *) WATCHDOG_BASE)
+#define INTERRUPT_CTRL ((INTERRUPT_CTRL_TypeDef *) H2F_IRQ_CTRL_BASE)
+#define INTERRUPT_CTRL_BITBAND ((INTERRUPT_CTRL_BitBand_TypeDef *) BITBAND_ADDRESS(H2F_IRQ_CTRL_BASE))
+#define UART1 ((UART_TypeDef *) UART1_BASE)
+#define SPI1 ((SPI_TypeDef *) SPI1_BASE)
+#define I2C1 ((I2C_TypeDef *) I2C1_BASE)
+#define I2C1_BITBAND ((I2C_BitBand_TypeDef *) BITBAND_ADDRESS(I2C1_BASE))
+#define GPIO ((GPIO_TypeDef *) GPIO_BASE)
+#define GPIO_BITBAND ((GPIO_BitBand_TypeDef *) BITBAND_ADDRESS(GPIO_BASE))
+#define HPDMA ((HPDMA_TypeDef *) HPDMA_BASE)
+#define HPDMA_BITBAND ((HPDMA_BitBand_TypeDef *) BITBAND_ADDRESS(HPDMA_BASE))
+#define COMBLK ((COMBLK_TypeDef *) COMBLK_BASE)
+#define RTC ((RTC_TypeDef *) RTC_BASE)
+#define ENVM_1 ((NVM_TypeDef *) ENVM1_BASE)
+#define ENVM_2 ((NVM_TypeDef *) ENVM2_BASE)
+#define SYSREG ((SYSREG_TypeDef *) SYSREG_BASE)
+#define MDDR ((MDDR_TypeDef *) DDR0_CFG_BASE)
+#define FDDR ((FDDR_TypeDef *) DDR1_CFG_BASE)
+#define USB ((MSS_USB_TypeDef *) USB_BASE)
+#define SERDES0 ((SERDESIF_TypeDef *) SERDES0_CFG_BASE)
+#define SERDES1 ((SERDESIF_TypeDef *) SERDES1_CFG_BASE)
+#define SERDES2 ((SERDESIF_TypeDef *) SERDES2_CFG_BASE)
+#define SERDES3 ((SERDESIF_TypeDef *) SERDES3_CFG_BASE)
+#define CORE_SF2_CFG ((CoreSF2Config_TypeDef *) CORE_SF2_CFG_BASE)
+#endif /* __SMARTFUSION2_CMSIS_PAL_H__ */
@@ -0,0 +1,62 @@
+ * (c) Copyright 2009-2013 Microsemi SoC Products Group. All rights reserved.
+ * Assertion implementation.
+ * This file provides the implementation of the ASSERT macro. This file can be
+ * modified to cater for project specific requirements regarding the way
+ * assertions are handled.
+ * SVN $Revision: 6422 $
+ * SVN $Date: 2014-05-14 14:37:56 +0100 (Wed, 14 May 2014) $
+#ifndef __MSS_ASSERT_H_
+#define __MSS_ASSERT_H_
+#if defined(NDEBUG)
+#define ASSERT(CHECK)
+#else /* NDEBUG */
+#include <assert.h>
+#if defined ( __GNUC__ )
+ * SoftConsole assertion handling
+#define ASSERT(CHECK) \
+ do { \
+ if (!(CHECK)) \
+ { \
+ __asm volatile ("BKPT\n\t"); \
+ } \
+ } while (0);
+ * IAR Embedded Workbench assertion handling.
+ * Call C library assert function which should result in error message
+ * displayed in debugger.
+#define ASSERT(X) assert(X)
+ * Keil assertion handling.
+#ifndef __MICROLIB
+ #define ASSERT(X) assert(X)
+ #define ASSERT(X)
+#endif /* Tool Chain */
+#endif /* NDEBUG */
+#endif /* __MSS_ASSERT_H_ */
@@ -0,0 +1,44 @@
+ * (c) Copyright 2014 Microsemi SoC Products Group. All rights reserved.
+ * Keil-MDK specific system initialization.
+ * SVN $Revision: 7375 $
+ * SVN $Date: 2015-05-01 14:57:40 +0100 (Fri, 01 May 2015) $
+#ifdef MSCC_NO_RELATIVE_PATHS
+#include "m2sxxx.h"
+#include "..\m2sxxx.h"
+#define ENVM_BASE_ADDRESS 0x60000000U
+#define MDDR_BASE_ADDRESS 0xA0000000U
+//extern unsigned int Image$$ER_RW$$Base;
+//extern unsigned int Image$$ER_RO$$Base;
+/*==============================================================================
+ * The __low_level_init() function is called after SystemInit. Therefore, the
+ * external RAM should be configured at this stage if it is used.
+/* void low_level_init(void)
+ volatile unsigned int rw_region_base;
+ volatile unsigned int readonly_region_base;
+ rw_region_base = (unsigned int)&Image$$ER_RW$$Base;
+ if (rw_region_base >= MDDR_BASE_ADDRESS)
+ / --------------------------------------------------------------------------
+ * Remap MDDR to address 0x00000000.
+ /
+ SYSREG->ESRAM_CR = 0u;
+ SYSREG->ENVM_REMAP_BASE_CR = 0u;
+ SYSREG->DDR_CR = 1u;
+ readonly_region_base = (unsigned int)&Image$$ER_RO$$Base;
+ SCB->VTOR = readonly_region_base;
+} */
@@ -0,0 +1,150 @@
+ * (c) Copyright 2013 Microsemi SoC Products Group. All rights reserved.
+ * Redirection of the standard library I/O to one of the SmartFusion2
+ * MMUART.
+ * The content of this source file will only be compiled if either one of the
+ * following two defined symbols are defined in the project settings:
+ * - MICROSEMI_STDIO_THRU_MMUART0
+ * - MICROSEMI_STDIO_THRU_MMUART1
+#ifdef MICROSEMI_STDIO_THRU_MMUART0
+#ifndef MICROSEMI_STDIO_THRU_UART
+#define MICROSEMI_STDIO_THRU_UART
+#endif /* MICROSEMI_STDIO_THRU_MMUART0 */
+#ifdef MICROSEMI_STDIO_THRU_MMUART1
+#endif /* MICROSEMI_STDIO_THRU_MMUART1 */
+ * Actual implementation.
+#ifdef MICROSEMI_STDIO_THRU_UART
+#include <stdio.h>
+#include <rt_misc.h>
+#include "mss_uart.h"
+#include "core_uart_apb.h"
+ * The baud rate will default to 57600 baud if no baud rate is specified though the
+ * MICROSEMI_STDIO_BAUD_RATE define.
+#ifndef MICROSEMI_STDIO_BAUD_RATE
+#define MICROSEMI_STDIO_BAUD_RATE MSS_UART_115200_BAUD
+static mss_uart_instance_t * const gp_my_uart = &g_mss_uart0;
+static mss_uart_instance_t * const gp_my_uart = &g_mss_uart1;
+ * Flag used to indicate if the UART driver needs to be initialized.
+static int g_stdio_uart_init_done = 0;
+#define LSR_THRE_MASK 0x20u
+ * Disable semihosting apis
+#pragma import(__use_no_semihosting_swi)
+ * sendchar()
+int sendchar(int ch)
+ uint32_t tx_ready;
+ //第一次调用时,初始化串口
+ if(!g_stdio_uart_init_done)
+ MSS_UART_init(gp_my_uart,
+ MICROSEMI_STDIO_BAUD_RATE,
+ MSS_UART_DATA_8_BITS | MSS_UART_NO_PARITY);
+ g_stdio_uart_init_done = 1;
+ do {
+ tx_ready = gp_my_uart->hw_reg->LSR & LSR_THRE_MASK;
+ } while(!tx_ready);
+ gp_my_uart->hw_reg->THR = ch;
+struct __FILE { int handle; /* Add whatever you need here */ };
+FILE __stdout;
+FILE __stdin;
+ * fputc()
+int fputc(int ch, FILE *f)
+ return (sendchar(ch));
+ * fgetc()
+int fgetc(FILE *f)
+ uint8_t rx_size;
+ uint8_t rx_byte;
+ rx_size = MSS_UART_get_rx(gp_my_uart, &rx_byte, 1);
+ } while(0u == rx_size);
+ return rx_byte;
+ * ferror()
+int ferror(FILE *f)
+ /* Your implementation of ferror */
+ return EOF;
+ * _ttywrch()
+void _ttywrch(int ch)
+ sendchar(ch);
+ * _sys_exit()
+void _sys_exit(int return_code)
+ for(;;)
+ ; /* endless loop */
+#endif /* MICROSEMI_STDIO_THRU_UART */
@@ -0,0 +1,49 @@
+;*******************************************************************************
+; (c) Copyright 2015 Microsemi SoC Products Group. All rights reserved.
+; SmartFusion2 scatter file for debugging code executing in internal eSRAM.
+;
+; SVN $Revision: 7419 $
+; SVN $Date: 2015-05-15 16:50:21 +0100 (Fri, 15 May 2015) $
+; * Some current (April 2015) dev kit memory map possibilities are
+; * --Type-------Device-----------address start---address end----size---Dbus--RAM IC-------SF2--Comment---------------
+; * --eNVM-------M2S010-----------0x60000000------0x6007FFFF-----256KB---------------------010------------------------
+; * --eNVM-------M2S090-----------0x60000000------0x6007FFFF-----512KB---------------------090------------------------
+; * --eSRAM------M2Sxxx-----------0x20000000------0x2000FFFF-----64KB----------------------xxx--All have same amount--
+; * --eSRAM------M2Sxxx-----------0x20000000------0x20013FFF-----80KB----------------------xxx--If ECC/SECDED not used
+; * --Fabric-----M2S010-----------0x30000000------0x6007FFFF-----400Kb---------------------010--note-K bits-----------
+; * --Fabric-----M2S090-----------0x30000000------0x6007FFFF-----2074Kb--------------------090--note-K bits-----------
+; * --LPDDR------STARTER-KIT------0xA0000000------0xA3FFFFFF-----64MB---16--MT46H32M16-----050------------------------
+; * --LPDDR------484-STARTER-KIT--0xA0000000------0xA3FFFFFF-----64MB---16--MT46H32M16-----010------------------------
+; * --LPDDR------SEC-EVAL-KIT-----0xA0000000------0xA3FFFFFF-----64MB---16--MT46H32M16LF---090--Security eval kit-----
+; * --DDR3-------ADevKit----------0xA0000000------0xBFFFFFFF-----1GB----32--MT41K256M8DA---150------------------------
+; * --Some older physical memory map possibilities are
+; * --Type-------location---------address start---address end----size---Dbus---RAM IC------SF2--Comment--------------
+; * --LPDDR------EVAL KIT---------0xA0000000------0xA3FFFFFF-----64MB-=-16--MT46H32M16LF---025--Eval Kit--------------
+; * --DDR3-------DevKit-----------0xA0000000------0xAFFFFFFF-----512MB--16--MT41K256M8DA---050------------------------
+; Example linker scripts use lowest practicl values so will work accross dev kits
+; eNVM=256KB eRAM=64KB External memory = 64MB
+RAM_LOAD 0x20000000 0x10000
+ ; First half of RAM allocated to RO Execute and data
+ ER_RO 0x20000000 0x8000
+ *.o (RESET, +First)
+ *(InRoot$$Sections)
+ .ANY (+RO)
+ ; Heap size is defined in startup_m2sxxx.s
+ ; Heap will be added after RW data in ER_RW unless explicitly
+ ; allocated a meemory region in .sct file
+ ; Stack size is defined in startup_m2sxxx.s
+ ; Stack will be added after heap in ER_RW unless explicitly
+ ; allocated a memory region in .sct file
+ ; Second half of RAM allocated to RW data, heap and stack
+ ER_RW 0x20008000 0x8000
+ .ANY (+RW +ZI)
@@ -0,0 +1,48 @@
+; SmartFusion2 scatter file for executing code in internal eNVM.
+FLASH_LOAD 0x00000000 0x40000
+; All R only code/data is located in ENVM
+ ER_RO 0x00000000 0x40000
+; Heap size is defined in startup_m2sxxx.s
+; Heap will be added after RW data in ER_RW unless explicitly
+; allocated a meemory region in .sct file
+; Stack size is defined in startup_m2sxxx.s
+; Stack will be added after heap in ER_RW unless explicitly
+; allocated a memory region in .sct file
+ ER_RW 0x20000000 0x10000
@@ -0,0 +1,54 @@
+; SmartFusion2 scatter file for debugging code executing in external MDDR.
+; Extern RAM 64M in total
+; allocate 1/2 to progam, 1/2 to variable data
+RAM_LOAD 0x00000000 0x04000000
+; Total = 64MB (lowest common amount accross dev kits) 32MB - First half of external memory allocated to RO Code
+ ER_RO 0x00000000 0x02000000
+ ; allocated a memory region in .sct file as is the case below
+ STACKS 0x20000000 UNINIT
+ startup_m2sxxx.o (STACK)
+; 32 MB- Second half of external memory allocated to RW data
+ ER_RW 0xA2000000 0x02000000
@@ -0,0 +1,74 @@
+; SmartFusion2 scatter file for relocating code to external RAM.
+FLASH_LOAD 0x60000000 0x40000
+; All code required on start-up located here before relocation has occured
+ ER_RO 0x60000000 0x40000
+ startup_m2sxxx.o
+ system_m2sxxx.o
+ sys_config.o
+ low_level_init.o
+ sys_config_SERDESIF_?.o
+ mscc_post_hw_cfg_init.o
+ ecc_error_handler.o
+ ; MDDR_RAM 0xA0000000 0x4000000
+ ; -MDDR is mapped to address space from 0 on startup
+ ; This allows the use of cache which is restriced to this area.
+ ; Code is copied to RAM_EXEC space on startup by boot code.
+ RAM_EXEC 0x00000000 0x00040000
+; All internal RAM has been allocatd to the stack
+; INTERNAL_RAM 0x20008000 0x10000
+; {
+; .ANY (+RW +ZI)
+; }
+; MDDR_RAM 0xA0000000 0x4000000 So use top half of this for RW data
+; Bottom half has been assigned to R only code already
+ ER_RW 0xA2000000 0x2000000
@@ -0,0 +1,586 @@
+; SmartFusion2 startup code for Keil-MDK.
+; SmartFusion2 vector table and startup code for ARM tool chain.
+; *------- <<< Use Configuration Wizard in Context Menu >>> ------------------
+; <h> Stack Configuration
+; <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
+; </h>
+Stack_Size EQU 0x00001000
+ AREA STACK, NOINIT, READWRITE, ALIGN=3
+stack_start
+Stack_Mem SPACE Stack_Size
+__initial_sp
+stack_end
+; <h> Heap Configuration
+; <o> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
+Heap_Size EQU 0x00000200
+ AREA HEAP, NOINIT, READWRITE, ALIGN=3
+__heap_base
+Heap_Mem SPACE Heap_Size
+__heap_limit
+ PRESERVE8
+ THUMB
+;===============================================================================
+; Vector Table Mapped to Address 0 at Reset
+ AREA RESET, DATA, READONLY
+ EXPORT __Vectors
+ EXPORT __Vectors_End
+ EXPORT __Vectors_Size
+__Vectors DCD __initial_sp ; Top of Stack
+ DCD Reset_Handler ; Reset Handler
+ DCD NMI_Handler ; NMI Handler
+ DCD HardFault_Handler ; Hard Fault Handler
+ DCD MemManage_Handler ; MPU Fault Handler
+ DCD BusFault_Handler ; Bus Fault Handler
+ DCD UsageFault_Handler ; Usage Fault Handler
+ DCD 0 ; Reserved
+ DCD SVC_Handler ; SVCall Handler
+ DCD DebugMon_Handler ; Debug Monitor Handler
+ DCD PendSV_Handler ; PendSV Handler
+ DCD SysTick_Handler ; SysTick Handler
+ ; External Interrupts
+ DCD WdogWakeup_IRQHandler
+ DCD RTC_Wakeup_IRQHandler
+ DCD SPI0_IRQHandler
+ DCD SPI1_IRQHandler
+ DCD I2C0_IRQHandler
+ DCD I2C0_SMBAlert_IRQHandler
+ DCD I2C0_SMBus_IRQHandler
+ DCD I2C1_IRQHandler
+ DCD I2C1_SMBAlert_IRQHandler
+ DCD I2C1_SMBus_IRQHandler
+ DCD UART0_IRQHandler
+ DCD UART1_IRQHandler
+ DCD EthernetMAC_IRQHandler
+ DCD DMA_IRQHandler
+ DCD Timer1_IRQHandler
+ DCD Timer2_IRQHandler
+ DCD CAN_IRQHandler
+ DCD ENVM0_IRQHandler
+ DCD ENVM1_IRQHandler
+ DCD ComBlk_IRQHandler
+ DCD USB_IRQHandler
+ DCD USB_DMA_IRQHandler
+ DCD PLL_Lock_IRQHandler
+ DCD PLL_LockLost_IRQHandler
+ DCD CommSwitchError_IRQHandler
+ DCD CacheError_IRQHandler
+ DCD DDR_IRQHandler
+ DCD HPDMA_Complete_IRQHandler
+ DCD HPDMA_Error_IRQHandler
+ DCD ECC_Error_IRQHandler
+ DCD MDDR_IOCalib_IRQHandler
+ DCD FAB_PLL_Lock_IRQHandler
+ DCD FAB_PLL_LockLost_IRQHandler
+ DCD FIC64_IRQHandler
+ DCD FabricIrq0_IRQHandler
+ DCD FabricIrq1_IRQHandler
+ DCD FabricIrq2_IRQHandler
+ DCD FabricIrq3_IRQHandler
+ DCD FabricIrq4_IRQHandler
+ DCD FabricIrq5_IRQHandler
+ DCD FabricIrq6_IRQHandler
+ DCD FabricIrq7_IRQHandler
+ DCD FabricIrq8_IRQHandler
+ DCD FabricIrq9_IRQHandler
+ DCD FabricIrq10_IRQHandler
+ DCD FabricIrq11_IRQHandler
+ DCD FabricIrq12_IRQHandler
+ DCD FabricIrq13_IRQHandler
+ DCD FabricIrq14_IRQHandler
+ DCD FabricIrq15_IRQHandler
+ DCD GPIO0_IRQHandler
+ DCD GPIO1_IRQHandler
+ DCD GPIO2_IRQHandler
+ DCD GPIO3_IRQHandler
+ DCD GPIO4_IRQHandler
+ DCD GPIO5_IRQHandler
+ DCD GPIO6_IRQHandler
+ DCD GPIO7_IRQHandler
+ DCD GPIO8_IRQHandler
+ DCD GPIO9_IRQHandler
+ DCD GPIO10_IRQHandler
+ DCD GPIO11_IRQHandler
+ DCD GPIO12_IRQHandler
+ DCD GPIO13_IRQHandler
+ DCD GPIO14_IRQHandler
+ DCD GPIO15_IRQHandler
+ DCD GPIO16_IRQHandler
+ DCD GPIO17_IRQHandler
+ DCD GPIO18_IRQHandler
+ DCD GPIO19_IRQHandler
+ DCD GPIO20_IRQHandler
+ DCD GPIO21_IRQHandler
+ DCD GPIO22_IRQHandler
+ DCD GPIO23_IRQHandler
+ DCD GPIO24_IRQHandler
+ DCD GPIO25_IRQHandler
+ DCD GPIO26_IRQHandler
+ DCD GPIO27_IRQHandler
+ DCD GPIO28_IRQHandler
+ DCD GPIO29_IRQHandler
+ DCD GPIO30_IRQHandler
+ DCD GPIO31_IRQHandler
+__Vectors_End
+__Vectors_Size EQU __Vectors_End - __Vectors
+; Reset Handler
+ AREA |.text|, CODE, READONLY
+Reset_Handler PROC
+ EXPORT Reset_Handler [WEAK]
+ IMPORT SystemInit
+ ; IMPORT low_level_init
+ IMPORT __main
+ ;---------------------------------------------------------------
+ ; Initialize stack RAM content to initialize the error detection
+ ; and correction (EDAC). This is done if EDAC is enabled for the
+ ; eSRAM blocks or the ECC/SECDED is enabled for the MDDR.
+ ; Register R11 is used to keep track of the RAM intialization
+ ; decision outcome for later use for heap RAM initialization at
+ ; the end of the startup code.
+ ; Please note that the stack has to be located in eSRAM at this
+ ; point and cannot be located in MDDR since MDDR is not available
+ ; at this point.
+ ; The bits of the content of register R11 have the foolwing
+ ; meaning:
+ ; reg11[0]: eSRAM EDAC enabled
+ ; reg11[1]: MDDR ECC/SECDED enabled
+ ;
+ MOV R11, #0
+ LDR R0, SF2_MDDR_MODE_CR
+ LDR R0, [R0]
+ LDR R1, SF2_EDAC_CR
+ LDR R1, [R1]
+ AND R1, R1, #3
+ AND R0, R0, #0x1C
+ CMP R0, #0x14
+ BNE check_esram_edac
+ ORR R11, R11, #2
+check_esram_edac
+ CMP R1, #0
+ BEQ check_stack_init
+ ORR R11, R11, #1
+check_stack_init
+ CMP R11, #0
+ BEQ call_system_init
+clear_stack
+ LDR R0, =stack_start
+ LDR R1, =stack_end
+ LDR R2, RAM_INIT_PATTERN
+ BL fill_memory ; fill_memory takes r0 - r2 as arguments uses r4, r5, r6, r7, r8, r9, and does not preserve contents */
+ ; Call SystemInit() to perform Libero specified configuration.
+call_system_init
+ LDR R0, =SystemInit
+ BLX R0
+ ; LDR R0, =low_level_init
+ ; BLX R0
+ ; Modify MDDR configuration if ECC/SECDED is enabled for MDDR.
+ ; Enable write combining on MDDR bridge, disable non-bufferable
+ ; regions.
+adjust_mddr_cfg
+ AND R10, R11, #0x2
+ CMP R10, #0
+ BEQ branch_to_main
+ LDR R0, SF2_DDRB_NB_SIZE
+ LDR R1, SF2_DDRB_CR
+ LDR R2, [R0]
+ LDR R3, [R1]
+ push {R0, R1, R2, R3}
+ MOV R2, #0
+ MOV R3, #0xFF
+ STR R2, [R0]
+ STR R3, [R1]
+ ; --------------------------------------------------------------
+ ; Initialize heap RAM content to initialize the error detection
+ ; and correction (EDAC). We use the decision made earlier in the
+ ; startup code of whether or not the stack RAM should be
+ ; initialized. This decision is held in register R11. A non-zero
+ ; value indicates that the RAM content should be initialized.
+clear_heap
+ LDR R0, =__heap_base
+ LDR R1, =__heap_limit
+ LDR R2, HEAP_INIT_PATTERN
+ ; Branch to __main
+branch_to_main
+ LDR R0, =__main
+ BX R0
+ ENDP
+SF2_EDAC_CR DCD 0x40038038
+SF2_DDRB_NB_SIZE DCD 0x40038030
+SF2_DDRB_CR DCD 0x40038034
+SF2_MDDR_MODE_CR DCD 0x40020818
+RAM_INIT_PATTERN DCD 0x00000000
+HEAP_INIT_PATTERN DCD 0x00000000
+;------------------------------------------------------------------------------
+; * fill_memory.
+; * @brief Fills memory with Pattern contained in r2
+; * This routine uses the stmne instruction to copy 4 words at a time which is very efficient
+; * The instruction can only write to word aligned memory, hence the code at the start and end of this routine
+; * to handle possible unaligned bytes at start and end.
+; *
+; * @param param1 r0: start address
+; * @param param2 r1: end address
+; * @param param3 r2: FILL PATTETN
+; * @note note: Most efficient if memory aligned. Linker ALIGN(4) command
+; * should be used as per example linker scripts
+; * Stack is not used in this routine
+; * register contents r4, r5, r6, r7, r8, r9, will are used and will be returned undefined
+; * @return none - Used Registers are not preserved
+; */
+fill_memory PROC
+ ;push {r4, r5, r6, r7, r8, r9, lr} We will not use stack as may be not available */
+ cmp r0, r1
+ beq fill_memory_exit ; Exit early if source and destination the same */
+ ; copy non-aligned bytes at the start */
+ and.w r6, r0, #3 ; see if non-alaigned bytes at the start */
+ cmp r6, #0
+ beq fill_memory_end_start ; no spare bytes at start, continue */
+ mov r5, #4
+ sub.w r4, r5, r6 ; now have number of non-aligned bytes in r4 */
+ mov r7, #8
+ mul r8, r7, r6 ; calculate number of shifts required to initalise pattern for non-aligned bytes */
+ mov r9, r2 ; copy pattern */
+ ror r9, r9, r8 ; Rotate right to keep pattern consistent */
+fill_memory_spare_bytes_start ; From above, R0 contains source address, R1 contains destination address */
+ cmp r4, #0 ; no spare bytes at end- end now */
+ beq fill_memory_end_start
+ strb r9, [r0] ; fill byte */
+ ror.w r9, r9, r7 ; Rotate right by one byte for the next time, to keep pattern consistent */
+ add r0, r0, #1 ; add one to address */
+ subs r4, r4, #1 ; subtract one from byte count 1 */
+ b fill_memory_spare_bytes_start
+fill_memory_end_start
+ mov r6, #0
+ mov r7, r1 ; save end address */
+ subs r1, r1, r0 ; Calculate number of bytes to fill */
+ mov r8,r1 ; Save copy of byte count */
+ asrs r1,r1, #4 ; Div by 16 to get number of chunks to move */
+ mov r4, r2 ; copy pattern */
+ mov r5, r2 ; copy pattern */
+ cmp r1, r6 ; compare to see if all chunks copied */
+ beq fill_memory_spare_bytes_end
+fill_memory_loop
+ it ne
+ stmne r0!, {r2, r4, r5, r9} ; copy pattern- note: stmne instruction must me word aligned (address in r0) */
+ add.w r6, r6, #1 ; use Thumb2- make sure condition code reg. not updated */
+ bne fill_memory_loop
+fill_memory_spare_bytes_end ; copy spare bytes at the end if any */
+ and.w r8, r8, #15 ; get spare bytes --check can you do an ands? */
+fill_memory_spare_end_loop ; From above, R0 contains source address, R1 contains destination address */
+ cmp r8, #0 ; no spare bytes at end- end now */
+ beq fill_memory_exit
+ strb r2, [r0]
+ ror.w r2, r2, #8 ; Rotate right by one byte for the next time, to keep pattern consistent */
+ subs r8, r8, #1 ; subtract one from byte count 1 */
+ b fill_memory_spare_end_loop
+fill_memory_exit
+ bx lr ; We will not use pop as stack may be not available */
+; Dummy Exception Handlers (infinite loops which can be modified)
+NMI_Handler PROC
+ EXPORT NMI_Handler [WEAK]
+ B .
+HardFault_Handler\
+ PROC
+ EXPORT HardFault_Handler [WEAK]
+MemManage_Handler\
+ EXPORT MemManage_Handler [WEAK]
+BusFault_Handler\
+ EXPORT BusFault_Handler [WEAK]
+UsageFault_Handler\
+ EXPORT UsageFault_Handler [WEAK]
+SVC_Handler PROC
+ EXPORT SVC_Handler [WEAK]
+DebugMon_Handler\
+ EXPORT DebugMon_Handler [WEAK]
+PendSV_Handler PROC
+ EXPORT PendSV_Handler [WEAK]
+SysTick_Handler PROC
+ EXPORT SysTick_Handler [WEAK]
+Default_Handler PROC
+ EXPORT WdogWakeup_IRQHandler [WEAK]
+ EXPORT RTC_Wakeup_IRQHandler [WEAK]
+ EXPORT SPI0_IRQHandler [WEAK]
+ EXPORT SPI1_IRQHandler [WEAK]
+ EXPORT I2C0_IRQHandler [WEAK]
+ EXPORT I2C0_SMBAlert_IRQHandler [WEAK]
+ EXPORT I2C0_SMBus_IRQHandler [WEAK]
+ EXPORT I2C1_IRQHandler [WEAK]
+ EXPORT I2C1_SMBAlert_IRQHandler [WEAK]
+ EXPORT I2C1_SMBus_IRQHandler [WEAK]
+ EXPORT UART0_IRQHandler [WEAK]
+ EXPORT UART1_IRQHandler [WEAK]
+ EXPORT EthernetMAC_IRQHandler [WEAK]
+ EXPORT DMA_IRQHandler [WEAK]
+ EXPORT Timer1_IRQHandler [WEAK]
+ EXPORT Timer2_IRQHandler [WEAK]
+ EXPORT CAN_IRQHandler [WEAK]
+ EXPORT ENVM0_IRQHandler [WEAK]
+ EXPORT ENVM1_IRQHandler [WEAK]
+ EXPORT ComBlk_IRQHandler [WEAK]
+ EXPORT USB_IRQHandler [WEAK]
+ EXPORT USB_DMA_IRQHandler [WEAK]
+ EXPORT PLL_Lock_IRQHandler [WEAK]
+ EXPORT PLL_LockLost_IRQHandler [WEAK]
+ EXPORT CommSwitchError_IRQHandler [WEAK]
+ EXPORT CacheError_IRQHandler [WEAK]
+ EXPORT DDR_IRQHandler [WEAK]
+ EXPORT HPDMA_Complete_IRQHandler [WEAK]
+ EXPORT HPDMA_Error_IRQHandler [WEAK]
+ EXPORT ECC_Error_IRQHandler [WEAK]
+ EXPORT MDDR_IOCalib_IRQHandler [WEAK]
+ EXPORT FAB_PLL_Lock_IRQHandler [WEAK]
+ EXPORT FAB_PLL_LockLost_IRQHandler [WEAK]
+ EXPORT FIC64_IRQHandler [WEAK]
+ EXPORT FabricIrq0_IRQHandler [WEAK]
+ EXPORT FabricIrq1_IRQHandler [WEAK]
+ EXPORT FabricIrq2_IRQHandler [WEAK]
+ EXPORT FabricIrq3_IRQHandler [WEAK]
+ EXPORT FabricIrq4_IRQHandler [WEAK]
+ EXPORT FabricIrq5_IRQHandler [WEAK]
+ EXPORT FabricIrq6_IRQHandler [WEAK]
+ EXPORT FabricIrq7_IRQHandler [WEAK]
+ EXPORT FabricIrq8_IRQHandler [WEAK]
+ EXPORT FabricIrq9_IRQHandler [WEAK]
+ EXPORT FabricIrq10_IRQHandler [WEAK]
+ EXPORT FabricIrq11_IRQHandler [WEAK]
+ EXPORT FabricIrq12_IRQHandler [WEAK]
+ EXPORT FabricIrq13_IRQHandler [WEAK]
+ EXPORT FabricIrq14_IRQHandler [WEAK]
+ EXPORT FabricIrq15_IRQHandler [WEAK]
+ EXPORT GPIO0_IRQHandler [WEAK]
+ EXPORT GPIO1_IRQHandler [WEAK]
+ EXPORT GPIO2_IRQHandler [WEAK]
+ EXPORT GPIO3_IRQHandler [WEAK]
+ EXPORT GPIO4_IRQHandler [WEAK]
+ EXPORT GPIO5_IRQHandler [WEAK]
+ EXPORT GPIO6_IRQHandler [WEAK]
+ EXPORT GPIO7_IRQHandler [WEAK]
+ EXPORT GPIO8_IRQHandler [WEAK]
+ EXPORT GPIO9_IRQHandler [WEAK]
+ EXPORT GPIO10_IRQHandler [WEAK]
+ EXPORT GPIO11_IRQHandler [WEAK]
+ EXPORT GPIO12_IRQHandler [WEAK]
+ EXPORT GPIO13_IRQHandler [WEAK]
+ EXPORT GPIO14_IRQHandler [WEAK]
+ EXPORT GPIO15_IRQHandler [WEAK]
+ EXPORT GPIO16_IRQHandler [WEAK]
+ EXPORT GPIO17_IRQHandler [WEAK]
+ EXPORT GPIO18_IRQHandler [WEAK]
+ EXPORT GPIO19_IRQHandler [WEAK]
+ EXPORT GPIO20_IRQHandler [WEAK]
+ EXPORT GPIO21_IRQHandler [WEAK]
+ EXPORT GPIO22_IRQHandler [WEAK]
+ EXPORT GPIO23_IRQHandler [WEAK]
+ EXPORT GPIO24_IRQHandler [WEAK]
+ EXPORT GPIO25_IRQHandler [WEAK]
+ EXPORT GPIO26_IRQHandler [WEAK]
+ EXPORT GPIO27_IRQHandler [WEAK]
+ EXPORT GPIO28_IRQHandler [WEAK]
+ EXPORT GPIO29_IRQHandler [WEAK]
+ EXPORT GPIO30_IRQHandler [WEAK]
+ EXPORT GPIO31_IRQHandler [WEAK]
+WdogWakeup_IRQHandler
+RTC_Wakeup_IRQHandler
+SPI0_IRQHandler
+SPI1_IRQHandler
+I2C0_IRQHandler
+I2C0_SMBAlert_IRQHandler
+I2C0_SMBus_IRQHandler
+I2C1_IRQHandler
+I2C1_SMBAlert_IRQHandler
+I2C1_SMBus_IRQHandler
+UART0_IRQHandler
+UART1_IRQHandler
+EthernetMAC_IRQHandler
+DMA_IRQHandler
+Timer1_IRQHandler
+Timer2_IRQHandler
+CAN_IRQHandler
+ENVM0_IRQHandler
+ENVM1_IRQHandler
+ComBlk_IRQHandler
+USB_IRQHandler
+USB_DMA_IRQHandler
+PLL_Lock_IRQHandler
+PLL_LockLost_IRQHandler
+CommSwitchError_IRQHandler
+CacheError_IRQHandler
+DDR_IRQHandler
+HPDMA_Complete_IRQHandler
+HPDMA_Error_IRQHandler
+ECC_Error_IRQHandler
+MDDR_IOCalib_IRQHandler
+FAB_PLL_Lock_IRQHandler
+FAB_PLL_LockLost_IRQHandler
+FIC64_IRQHandler
+FabricIrq0_IRQHandler
+FabricIrq1_IRQHandler
+FabricIrq2_IRQHandler
+FabricIrq3_IRQHandler
+FabricIrq4_IRQHandler
+FabricIrq5_IRQHandler
+FabricIrq6_IRQHandler
+FabricIrq7_IRQHandler
+FabricIrq8_IRQHandler
+FabricIrq9_IRQHandler
+FabricIrq10_IRQHandler
+FabricIrq11_IRQHandler
+FabricIrq12_IRQHandler
+FabricIrq13_IRQHandler
+FabricIrq14_IRQHandler
+FabricIrq15_IRQHandler
+GPIO0_IRQHandler
+GPIO1_IRQHandler
+GPIO2_IRQHandler
+GPIO3_IRQHandler
+GPIO4_IRQHandler
+GPIO5_IRQHandler
+GPIO6_IRQHandler
+GPIO7_IRQHandler
+GPIO8_IRQHandler
+GPIO9_IRQHandler
+GPIO10_IRQHandler
+GPIO11_IRQHandler
+GPIO12_IRQHandler
+GPIO13_IRQHandler
+GPIO14_IRQHandler
+GPIO15_IRQHandler
+GPIO16_IRQHandler
+GPIO17_IRQHandler
+GPIO18_IRQHandler
+GPIO19_IRQHandler
+GPIO20_IRQHandler
+GPIO21_IRQHandler
+GPIO22_IRQHandler
+GPIO23_IRQHandler
+GPIO24_IRQHandler
+GPIO25_IRQHandler
+GPIO26_IRQHandler
+GPIO27_IRQHandler
+GPIO28_IRQHandler
+GPIO29_IRQHandler
+GPIO30_IRQHandler
+GPIO31_IRQHandler
+mscc_post_hw_cfg_init PROC
+ EXPORT mscc_post_hw_cfg_init [WEAK]
+ BX LR
+ ALIGN
+; User Initial Stack & Heap
+ IF :DEF:__MICROLIB
+ EXPORT __initial_sp
+ EXPORT __heap_base
+ EXPORT __heap_limit
+ ELSE
+ IMPORT __use_two_region_memory
+ EXPORT __user_initial_stackheap
+__user_initial_stackheap
+ LDR R0, = Heap_Mem
+ LDR R1, =(Stack_Mem + Stack_Size)
+ LDR R2, = (Heap_Mem + Heap_Size)
+ LDR R3, = Stack_Mem
+ ENDIF
+ END
@@ -0,0 +1,249 @@
+ * (c) Copyright 2015 Microsemi SoC Products Group. All rights reserved.
+ * file name : debug-in-microsemi-smartfusion2-envm.ld
+ * SmartFusion2 Cortex-M3 linker script for creating a SoftConsole downloadable
+ * debug image executing in SmartFusion2 internal eNVM.
+ * Some current (April 2015) dev kit memory map possibilities are
+ * --Type-------Device-----------address start---address end----size---Dbus--RAM IC-------SF2--Comment---------------
+ * --eNVM-------M2S010-----------0x60000000------0x6007FFFF-----256KB---------------------010------------------------
+ * --eNVM-------M2S090-----------0x60000000------0x6007FFFF-----512KB---------------------090------------------------
+ * --eSRAM------M2Sxxx-----------0x20000000------0x2000FFFF-----64KB----------------------xxx--All have same amount--
+ * --eSRAM------M2Sxxx-----------0x20000000------0x20013FFF-----80KB----------------------xxx--If ECC/SECDED not used
+ * --Fabric-----M2S010-----------0x30000000------0x6007FFFF-----400Kb---------------------010--note-K bits-----------
+ * --Fabric-----M2S090-----------0x30000000------0x6007FFFF-----2074Kb--------------------090--note-K bits-----------
+ * --LPDDR------STARTER-KIT------0xA0000000------0xA3FFFFFF-----64MB---16--MT46H32M16-----050------------------------
+ * --LPDDR------484-STARTER-KIT--0xA0000000------0xA3FFFFFF-----64MB---16--MT46H32M16-----010------------------------
+ * --LPDDR------SEC-EVAL-KIT-----0xA0000000------0xA3FFFFFF-----64MB---16--MT46H32M16LF---090--Security eval kit-----
+ * --DDR3-------ADevKit----------0xA0000000------0xBFFFFFFF-----1GB----32--MT41K256M8DA---150------------------------
+ * --Some older physical memory map possibilities are
+ * --Type-------location---------address start---address end----size---Dbus---RAM IC------SF2--Comment--------------
+ * --LPDDR------EVAL KIT---------0xA0000000------0xA3FFFFFF-----64MB-=-16--MT46H32M16LF---025--Eval Kit--------------
+ * --DDR3-------DevKit-----------0xA0000000------0xAFFFFFFF-----512MB--16--MT41K256M8DA---050------------------------
+ * Example linker scripts use lowest practicl values so will work accross dev kits
+ * eNVM=256KB eRAM=64KB External memory = 64MB
+ * On reset, the eNVM region is mapped to 0x00000000
+ * This is changed below by setting the __smartfusion2_memory_remap variable as required.
+ * Options are detailed below.
+ * SVN $Revision: 7419 $
+ * SVN $Date: 2015-05-15 21:20:21 +0530 (Fri, 15 May 2015) $
+OUTPUT_FORMAT("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
+GROUP(-lc -lgcc -lm)
+OUTPUT_ARCH(arm)
+ENTRY(Reset_Handler)
+SEARCH_DIR(.)
+__DYNAMIC = 0;
+ * Start of board customization.
+ *******************************************************************************/
+MEMORY
+ * In general, example LD scripts use lowest common memory footprint
+ * so will work with all devices.
+ * WARNING: The words "SOFTCONSOLE", "FLASH", and "USE", the colon ":", and
+ * the name of the type of flash memory are all in a specific order.
+ * Please do not modify that comment line, in order to ensure
+ * debugging of your application will use the flash memory correctly.
+ /* SOFTCONSOLE FLASH USE: microsemi-smartfusion2-envm */
+ rom (rx) : ORIGIN = 0x60000000, LENGTH = 256k
+ /* SmartFusion2 internal eNVM mirrored to 0x00000000 */
+ romMirror (rx) : ORIGIN = 0x00000000, LENGTH = 256k
+ /* SmartFusion2 internal eSRAM */
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64k
+RAM_START_ADDRESS = 0x20000000; /* Must be the same value MEMORY region ram ORIGIN above. */
+RAM_SIZE = 64k; /* Must be the same value MEMORY region ram LENGTH above. */
+MAIN_STACK_SIZE = 4k; /* Cortex main stack size. */
+MIN_SIZE_HEAP = 4k; /* needs to be calculated for your application */
+ * End of board customization.
+PROVIDE (__main_stack_start = RAM_START_ADDRESS + RAM_SIZE);
+PROVIDE (_estack = __main_stack_start);
+PROVIDE (__mirrored_nvm = 1); /* Indicate to startup code that NVM is mirrored to VMA address and no text copy is required. */
+ * Remap instruction for startup code and debugger.
+ * set __smartfusion2_memory_remap to one of the following:
+ * 0: remap eNVM to address 0x00000000 Production mode or debugging from eNVM
+ * 1: remap eSRAM to address 0x00000000 Debugging from eSRAM
+ * 2: remap external DDR memory to address 0x00000000 Debugging from DDR memory
+PROVIDE (__smartfusion2_memory_remap = 0);
+SECTIONS
+ .vector_table : ALIGN(0x10)
+ __vector_table_load = LOADADDR(.vector_table);
+ __vector_table_start = .;
+ __vector_table_vma_base_address = .; /* required by debugger for start address */
+ KEEP(*(.isr_vector))
+ . = ALIGN(0x10);
+ _evector_table = .;
+ } >romMirror AT>rom
+ /* all data and code run/used before reloaction must be located here */
+ /* When all code in NVRAM, no requirement for this section- but adds clarity when looking at .lst file */
+ .boot_code : ALIGN(0x10)
+ *(.boot_code) /* reset handler */
+ *system_m2sxxx.o(.text*) /* SystemInit() - called before relocation to RAM so keep in ROM */
+ *sys_config.o(.rodata*)
+ .text : ALIGN(0x10)
+ CREATE_OBJECT_SYMBOLS
+ __text_load = LOADADDR(.text); /* required when copying to RAM */
+ __text_start = .; /* required when copying to RAM */
+ *(.text .text.* .gnu.linkonce.t.*)
+ *(.plt)
+ *(.gnu.warning)
+ *(.glue_7t) *(.glue_7) *(.vfp11_veneer)
+ . = ALIGN(4);
+ /* These are for running static constructors and destructors under ELF. */
+ KEEP (*crtbegin.o(.ctors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
+ KEEP (*(SORT(.ctors.*)))
+ KEEP (*crtend.o(.ctors))
+ KEEP (*crtbegin.o(.dtors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
+ KEEP (*(SORT(.dtors.*)))
+ KEEP (*crtend.o(.dtors))
+ *(.rodata .rodata.* .gnu.linkonce.r.*)
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ *(.gcc_except_table)
+ *(.eh_frame_hdr)
+ *(.eh_frame)
+ KEEP (*(.vector_table))
+ KEEP (*(.init))
+ KEEP (*(.fini))
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(.fini_array))
+ KEEP (*(SORT(.fini_array.*)))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ /* .ARM.exidx is sorted, so has to go in its own output section. */
+ __exidx_start = .;
+ .ARM.exidx :
+ *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+ } >ram AT>rom
+ __exidx_end = .;
+ _etext = .; /* required when copying to RAM */
+ .data : ALIGN(0x10)
+ __data_load = LOADADDR(.data); /* used when copying to RAM */
+ _sidata = LOADADDR (.data);
+ __data_start = .; /* used when copying to RAM */
+ _sdata = .;
+ KEEP(*(.jcr))
+ *(.got.plt) *(.got)
+ *(.shdata)
+ *(.data .data.* .gnu.linkonce.d.*)
+ . = ALIGN (0x10);
+ _edata = .; /* used when copying to RAM */
+ .bss : ALIGN(0x10)
+ __bss_start__ = . ;
+ _sbss = .;
+ *(.shbss)
+ *(.bss .bss.* .gnu.linkonce.b.*)
+ *(COMMON)
+ __bss_end__ = .;
+ _end = .;
+ __end = _end;
+ _ebss = .;
+ PROVIDE(end = .);
+ .heap : ALIGN(0x10)
+ __heap_start__ = .;
+ . += MIN_SIZE_HEAP; /* will generate error if this minimum size not available */
+ . += ((ABSOLUTE(RAM_START_ADDRESS) + RAM_SIZE - MAIN_STACK_SIZE) - .); /* assumes stack starts after heap */
+ _eheap = .;
+ } >ram
+ .stack : ALIGN(0x10)
+ __stack_start__ = .;
+ . += MAIN_STACK_SIZE;
+ _estack = .;
+ .stab 0 (NOLOAD) :
+ *(.stab)
+ .stabstr 0 (NOLOAD) :
+ *(.stabstr)
+ /* DWARF debug sections.
+ Symbols in the DWARF debugging sections are relative to the beginning
+ of the section so we begin them at 0. */
+ /* DWARF 1 */
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+ /* GNU DWARF 1 extensions */
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+ /* DWARF 1.1 and DWARF 2 */
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ /* DWARF 2 */
+ .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+ /* SGI/MIPS DWARF 2 extensions */
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+ .note.gnu.arm.ident 0 : { KEEP (*(.note.gnu.arm.ident)) }
+ .ARM.attributes 0 : { KEEP (*(.ARM.attributes)) }
+ /DISCARD/ : { *(.note.GNU-stack) }
@@ -0,0 +1,248 @@
+ * file name : debug-in-microsemi-smartfusion2-esram.ld
+ * debug image executing in SmartFusion2 internal eSRAM.
+ * SVN $Revision: 7478 $
+ * SVN $Date: 2015-06-18 21:48:18 +0530 (Thu, 18 Jun 2015) $
+/* Please note that unassigned RAM will be allocated to the .heap section. */
+PROVIDE (__mirrored_nvm = 0); /* Indicate to startup code that NVM is not mirrored to VMA address .text copy is required. */
+ * Remap instruction for start-up code and debugger.
+ * 1: remap eSRAM to address 0x00000000 See note 1 below.
+ * 2: remap external DDR memory to address 0x00000000 Debugging from or production relocate to DDR memory
+ * note 1: This option should only be used in production mode if required. When debugging using eSRAM, code is not
+ * relocated and __smartfusion2_memory_remap should be set to option 0. In revision 7419 and below of
+ * this file, __smartfusion2_memory_remap was set to option 1. This remap was not required and could lead to an issue
+ * when displaying some invalid memory locations in the debugger using some Libero designs.
+ __vector_table_vma_base_address = .;
+ .boot_code : ALIGN(0x10) /* When all code in RAM, no requirement for this section- but adds clarity when looking at .lst file */
+ *(.boot_code)
+ .text :
+ ALIGN(0x10)
+ __text_load = LOADADDR(.text);
+ __text_start = .;
+ . = ALIGN(0x4);
+ _etext = .;
+ PROVIDE(__text_end = .);
+ .data :
+ __data_load = LOADADDR (.data);
+ __data_start = .;
+ _edata = .;
+ /DISCARD/ : { *(.note.GNU-stack) *(.isr_vector) }
@@ -0,0 +1,238 @@
+ * file name : debug-in-microsemi-smartfusion2-external-ram.ld
+ * debug image executing in external eRAM.
+ * Example linker scripts use lowest practical values so will work accross dev kits
+ * accross dev boards so will work with all devices. Currently this is 64MB
+ * Program and data space is split evenly in this example 32MB each
+ esram (rwx) : ORIGIN = 0x20000000, LENGTH = 64k
+ /* SmartFusion2 development board external RAM */
+ external_ram (rwx) : ORIGIN = 0x00000000, LENGTH = 32m
+ /* External MDDR RAM used for data section. */
+ /* Must be enough room allocated for data section between 0xA0000000 and data_external_ram */
+ data_external_ram (rw) : ORIGIN = 0xA2000000, LENGTH = 32m
+ESRAM_START_ADDRESS = 0x20000000; /* Must be the same value MEMORY region ram ORIGIN above. */
+ESRAM_SIZE = 64k; /* Must be the same value MEMORY region ram LENGTH above. */
+MAIN_STACK_SIZE = 64k; /* Cortex main stack size. */
+MIN_SIZE_HEAP = 64k; /* needs to be calculated for your application */
+TOP_OF_MDDR = 0xA4000000; /* Top address of the external MDDR memory. */
+/*PROVIDE (__main_ram_size = ESRAM_SIZE); */
+PROVIDE (__main_stack_start = ESRAM_START_ADDRESS + ESRAM_SIZE);
+PROVIDE (__process_stack_start = __main_stack_start - MAIN_STACK_SIZE);
+PROVIDE (__smartfusion2_memory_remap = 2);
+ } >external_ram
+ } >data_external_ram
+ . += (ABSOLUTE(TOP_OF_MDDR) - . );
+ } >esram
@@ -0,0 +1,241 @@
+ * file name : production-smartfusion2-execute-in-place.ld
+ * image executing in SmartFusion2 internal eNVM.
+ * SVN $Revision: 7454 $
+ * SVN $Date: 2015-06-08 20:28:07 +0530 (Mon, 08 Jun 2015) $
+ rom (rx) : ORIGIN = 0x00000000, LENGTH = 256k
+ * Remap instruction for startup code and debugger:
+ * 0: remap eNVM to address 0x00000000
+ * 1: remap eSRAM to address 0x00000000
+ * 2: remap external DDR memory to address 0x00000000
+ .vector_table :
+ } >rom
+ .boot_code : ALIGN(0x10) /* When all code in NVRAM, no requirement for this section- but adds clarity when looking at .lst file */
+ __data_load = LOADADDR(.data);
@@ -0,0 +1,260 @@
+ * file name : production-smartfusion2-relocate-to-external-ram.ld
+ * image which is copied from internal eNVM to external RAM during boot-up.
+ /* 0xA0000000 where external memory starts */
+ /* first 0x00FFFFF reserved for relocated progam */
+ /* Locate external RX data above reserved program area */
+ /* !!! This must not overlap with external_ram when MDDR is remapped to 0x00000000.!!! */
+ESRAM_START_ADDRESS = 0x20000000; /* Must be the same value as MEMORY region esram ORIGIN above. */
+ESRAM_SIZE = 64k; /* Must be the same value as MEMORY region esram LENGTH above. */
+ } >external_ram AT>rom
+ *sys_config_SERDESIF_?.o(.rodata*) /* data- used to configure external memeory before use */
+ /* note ? is a wildcard, can be upto 4 instances */
+ *mscc_post_hw_cfg_init.o /* used on startup */
+ *ecc_error_handler.o(.text*) /* do we need this???? */
+ } >data_external_ram AT>rom
@@ -0,0 +1,1297 @@
+ * (c) Copyright 2012-2015 Microsemi SoC Products Group. All rights reserved.
+ * @file startup_m2sxxx.S
+ * @author Microsemi SoC Products Group
+ * @brief SmartFusion2 vector table and startup code for CodeSourcery G++.
+ * SVN $Revision: 7424 $
+ * SVN $Date: 2015-05-19 21:16:09 +0530 (Tue, 19 May 2015) $
+ .syntax unified
+ .cpu cortex-m3
+ .thumb
+/* #define UNIT_TEST_FILL_MEMORY only uncommented if carring out unit test */
+ * Vector table
+ .global g_pfnVectors
+ .section .isr_vector,"ax",%progbits /* added "x" so appears in .lst file even though not executable code- to help in debug process */
+ .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 SVC_Handler
+ .word DebugMon_Handler
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WdogWakeup_IRQHandler
+ .word RTC_Wakeup_IRQHandler
+ .word SPI0_IRQHandler
+ .word SPI1_IRQHandler
+ .word I2C0_IRQHandler
+ .word I2C0_SMBAlert_IRQHandler
+ .word I2C0_SMBus_IRQHandler
+ .word I2C1_IRQHandler
+ .word I2C1_SMBAlert_IRQHandler
+ .word I2C1_SMBus_IRQHandler
+ .word UART0_IRQHandler
+ .word UART1_IRQHandler
+ .word EthernetMAC_IRQHandler
+ .word DMA_IRQHandler
+ .word Timer1_IRQHandler
+ .word Timer2_IRQHandler
+ .word CAN_IRQHandler
+ .word ENVM0_IRQHandler
+ .word ENVM1_IRQHandler
+ .word ComBlk_IRQHandler
+ .word USB_IRQHandler
+ .word USB_DMA_IRQHandler
+ .word PLL_Lock_IRQHandler
+ .word PLL_LockLost_IRQHandler
+ .word CommSwitchError_IRQHandler
+ .word CacheError_IRQHandler
+ .word DDR_IRQHandler
+ .word HPDMA_Complete_IRQHandler
+ .word HPDMA_Error_IRQHandler
+ .word ECC_Error_IRQHandler
+ .word MDDR_IOCalib_IRQHandler
+ .word FAB_PLL_Lock_IRQHandler
+ .word FAB_PLL_LockLost_IRQHandler
+ .word FIC64_IRQHandler
+ .word FabricIrq0_IRQHandler
+ .word FabricIrq1_IRQHandler
+ .word FabricIrq2_IRQHandler
+ .word FabricIrq3_IRQHandler
+ .word FabricIrq4_IRQHandler
+ .word FabricIrq5_IRQHandler
+ .word FabricIrq6_IRQHandler
+ .word FabricIrq7_IRQHandler
+ .word FabricIrq8_IRQHandler
+ .word FabricIrq9_IRQHandler
+ .word FabricIrq10_IRQHandler
+ .word FabricIrq11_IRQHandler
+ .word FabricIrq12_IRQHandler
+ .word FabricIrq13_IRQHandler
+ .word FabricIrq14_IRQHandler
+ .word FabricIrq15_IRQHandler
+ .word GPIO0_IRQHandler
+ .word GPIO1_IRQHandler
+ .word GPIO2_IRQHandler
+ .word GPIO3_IRQHandler
+ .word GPIO4_IRQHandler
+ .word GPIO5_IRQHandler
+ .word GPIO6_IRQHandler
+ .word GPIO7_IRQHandler
+ .word GPIO8_IRQHandler
+ .word GPIO9_IRQHandler
+ .word GPIO10_IRQHandler
+ .word GPIO11_IRQHandler
+ .word GPIO12_IRQHandler
+ .word GPIO13_IRQHandler
+ .word GPIO14_IRQHandler
+ .word GPIO15_IRQHandler
+ .word GPIO16_IRQHandler
+ .word GPIO17_IRQHandler
+ .word GPIO18_IRQHandler
+ .word GPIO19_IRQHandler
+ .word GPIO20_IRQHandler
+ .word GPIO21_IRQHandler
+ .word GPIO22_IRQHandler
+ .word GPIO23_IRQHandler
+ .word GPIO24_IRQHandler
+ .word GPIO25_IRQHandler
+ .word GPIO26_IRQHandler
+ .word GPIO27_IRQHandler
+ .word GPIO28_IRQHandler
+ .word GPIO29_IRQHandler
+ .word GPIO30_IRQHandler
+ .word GPIO31_IRQHandler
+ * Reset_Handler
+ * Register r11 is used to keep track of whether we need to initialize RAMs
+ * because ECC/ SECDED is enabled.
+ .global Reset_Handler
+ .section .boot_code,"ax",%progbits
+ .type Reset_Handler, %function
+Reset_Handler:
+_start:
+ * Initialize stack RAM content to initialize the error detection and correction
+ * (EDAC). This is done if EDAC is enabled for the eSRAM blocks or the
+ * ECC/SECDED is enabled for the MDDR.
+ * Register r11 is used to keep track of the RAM intialization decision outcome
+ * for later use for heap RAM initialization at the end of the startup code.
+ * Please note that the stack has to be located in eSRAM at this point and
+ * cannot be located in MDDR since MDDR is not available at this point.
+ * The bits of the content of register r11 have the following meaning:
+ * reg11[0]: eSRAM EDAC enabled
+ * reg11[1]: MDDR ECC/SECDED enabled
+ mov r11, #0
+ ldr r0, SF2_MDDR_MODE_CR
+ ldr r0, [r0]
+ ldr r1, SF2_EDAC_CR
+ ldr r1, [r1]
+ and r1, r1, #3
+ and r0, r0, #0x1C
+ cmp r0, #0x14
+ bne check_esram_edac
+ orr r11, r11, #2
+check_esram_edac:
+ cmp r1, #0
+ beq check_stack_init
+ orr r11, r11, #1
+check_stack_init:
+ cmp r11, #0
+ beq system_init
+clear_stack:
+ ldr r0, = __stack_start__
+ ldr r1, =_estack
+ ldr r2, RAM_INIT_PATTERN
+ bl fill_memory /* ; fill_memory takes r0 - r2 as arguments uses r4, r5, r6, r7, r8, r9, and does not preserve contents */
+ * Call CMSIS system init function.
+ system_init:
+ ldr r0, =SystemInit
+ blx r0
+ * Modify MDDR configuration if ECC/SECDED is enabled for MDDR.
+ * Enable write combining on MDDR bridge, disable non-bufferable regions.
+ and r10, r11, 0x2
+ cmp r10, #0
+ beq remap_memory
+ ldr r0, SF2_DDRB_NB_SIZE
+ ldr r1, SF2_DDRB_CR
+ ldr r2, [r0]
+ ldr r3, [r1]
+ push {r0, r1, r2, r3}
+ mov r2, #0
+ mov r3, #0xFF
+ str r2, [r0]
+ str r3, [r1]
+ * Perform memory remapping based on the value of __smartfusion2_memory_remap
+ * set in the linker script.
+remap_memory:
+ ldr r0, =__smartfusion2_memory_remap
+ ldr r2, =0
+ ldr r3, =1
+ cmp r0, #2
+ bne check_esram_remap
+ * Remap external RAM to address 0x00000000
+ ldr r1, SF2_ESRAM_CR
+ str r2, [r1]
+ ldr r1, SF2_ENVM_REMAP_CR
+ ldr r1, SF2_DDR_CR
+check_esram_remap:
+ cmp r0, #1
+ bne check_mirrored_nvm
+ * Remap internal eSRAM to address 0x00000000
+ * Check if the executable is built for NVM LMA mirrored to VMA address.
+ * This is done for debugging executables running out of eNVM with SoftConsole.
+ * The .text section should not be copied in this case since both the LMA and
+ * VMA point at the eNVM despite the LMA and VMa having different values.
+ check_mirrored_nvm:
+ ldr r0, =__mirrored_nvm
+ cmp r0, #0
+ bne copy_data
+ * Copy vector table.
+ ldr r0, =__vector_table_load
+ ldr r1, =__vector_table_start
+ ldr r2, =_evector_table
+ bl block_copy
+ * Copy code section.
+copy_text:
+ ldr r0, =__text_load
+ ldr r1, =__text_start
+ ldr r2, =_etext
+ * Copy data section.
+ copy_data:
+ ldr r0, =__data_load
+ ldr r1, =__data_start
+ ldr r2, =_edata
+ * Clear .bss
+clear_bss:
+ ldr r0, =__bss_start__
+ ldr r1, =__bss_end__
+#ifdef UNIT_TEST_FILL_MEMORY
+ bl unit_test_fill_memory
+ * Initialize heap RAM content to initialize the error detection and correction
+ * (EDAC). We use the decision made earlier in the startup code of whether or
+ * not the stack RAM should be initialized. This decision is held in register
+ * r11. A non-zero value indicates that the RAM content should be initialized.
+clear_heap:
+ beq call_glob_ctor
+ ldr r0, =__heap_start__
+ ldr r1, =_eheap
+ ldr r2, HEAP_INIT_PATTERN
+ * Restore MDDR configuration.
+ pop {r0, r1, r2, r3}
+ * Call global constructors
+ * Align to word and use 32-bits LDR instruction to ensure the ADD instruction
+ * taking PC as argument is aligned on a word boundary.
+ .align 4
+call_glob_ctor:
+ ldr.w r0, =__libc_init_array
+ add lr, pc, #3
+ bx r0
+ * branch to main.
+branch_to_main:
+ mov r0, #0 /* ; no arguments */
+ mov r1, #0 /* ; no argv either */
+ ldr pc, =main
+ExitLoop:
+ B ExitLoop
+ * block copy.
+ * r0: source address
+ * r1: target address
+ * r2: end target address
+ * note: Most efficient if memory aligned. Linker ALIGN(16) command
+ * should be used as per example linker scripts.
+ * Note 1: If the memory address in r0 or r1, byte copy routine is used
+ * Note 2: If r1 < r2, will loop indefinetley to highlight linker issue.
+block_copy:
+ push {r3, r4, r5, r6, r7, r8, lr}
+ beq block_copy_exit /* ; Exit early if source and destination the same */
+ subs.w r2, r2, r1 /* ; Calculate number of bytes to move */
+ bpl block_copy_address_ok /* ; check (end target address) > (target address) => continue */
+ b . /* ; halt as critical error- memory map not OK- make it easy to catch in debugger */
+block_copy_address_ok:
+ /* ; detect if source or target memory addresses unaligned. If so use byte copy routine */
+ orr.w r3, r0, r1
+ ands.w r3, r3, #3
+ beq block_copy_continue
+block_copy_byte_copy:
+ bl block_copy_byte
+ b block_copy_exit
+block_copy_continue:
+ mov r3, #0
+ mov r8,r2 /* ; Save copy of byte count */
+ asrs r2,r2, #4 /* ; Div by 16 to get number of chunks to move */
+ beq block_copy_byte_copy /* ; need to use byte copy if less than 16 bytes */
+block_copy_loop:
+ cmp r2, r3
+ itt ne
+ ldmne r0!, {r4, r5, r6, r7}
+ stmne r1!, {r4, r5, r6, r7}
+ add.w r3, r3, #1 /* ; use Thumb2- make sure condition code reg. not updated */
+ bne block_copy_loop
+ /* ; copy spare bytes at the end if any */
+ and r8, #15 /* ; get spare bytes --check can you do an ands? */
+ cmp r8, #0 /* ; no spare bytes at end- end now */
+ beq block_copy_exit
+copy_spare_bytes: /* ; From above, R0 contains source address, R1 contains destination address */
+ ldrb r4, [r0]
+ strb r4, [r1]
+ add r0, #1
+ add r1, #1
+ subs r8, r8, #1
+ bne copy_spare_bytes
+block_copy_exit:
+ pop {r3, r4, r5, r6, r7, r8, pc}
+ * block_copy_byte: used if memory not aligned
+ * r2: number of bytes
+block_copy_byte:
+ push {r3, lr}
+block_copy_byte_loop: /* ; From above, R0 contains source address, R1 contains destination address */
+ ldrb r3, [r0]
+ strb r3, [r1]
+ subs r2, r2, #1
+ bne block_copy_byte_loop
+ pop {r3, pc}
+/*;------------------------------------------------------------------------------
+fill_memory:
+ /* ;push {r4, r5, r6, r7, r8, r9, lr} We will not use stack as may be not available */
+ beq fill_memory_exit /* ; Exit early if source and destination the same */
+/* ; copy non-aligned bytes at the start */
+ and.w r6, r0, #3 /* ; see if non-alaigned bytes at the start */
+ beq fill_memory_end_start /* ; no spare bytes at start, continue */
+ sub.w r4, r5, r6 /* ; now have number of non-aligned bytes in r4 */
+ mul r8, r7, r6 /* ; calculate number of shifts required to initalise pattern for non-aligned bytes */
+ mov r9, r2 /* ; copy pattern */
+ ror r9, r9, r8 /* ; Rotate right to keep pattern consistent */
+fill_memory_spare_bytes_start: /* ; From above, R0 contains source address, R1 contains destination address */
+ cmp r4, #0 /* ; no spare bytes at end- end now */
+ strb r9, [r0] /* ; fill byte */
+ ror.w r9, r9, r7 /* ; Rotate right by one byte for the next time, to keep pattern consistent */
+ add r0, r0, #1 /* ; add one to address */
+ subs r4, r4, #1 /* ; subtract one from byte count 1 */
+fill_memory_end_start:
+ mov r7, r1 /* ; save end address */
+ subs r1, r1, r0 /* ; Calculate number of bytes to fill */
+ mov r8,r1 /* ; Save copy of byte count */
+ asrs r1,r1, #4 /* ; Div by 16 to get number of chunks to move */
+ mov r4, r2 /* ; copy pattern */
+ mov r5, r2 /* ; copy pattern */
+ cmp r1, r6 /* ; compare to see if all chunks copied */
+fill_memory_loop:
+ stmne r0!, {r2, r4, r5, r9} /* ; copy pattern- note: stmne instruction must me word aligned (address in r0) */
+ add.w r6, r6, #1 /* ; use Thumb2- make sure condition code reg. not updated */
+fill_memory_spare_bytes_end: /* ; copy spare bytes at the end if any */
+ and.w r8, r8, #15 /* ; get spare bytes --check can you do an ands? */
+fill_memory_spare_end_loop: /* ; From above, R0 contains source address, R1 contains destination address */
+ ror.w r2, r2, #8 /* ; Rotate right by one byte for the next time, to keep pattern consistent */
+ subs r8, r8, #1 /* ; subtract one from byte count 1 */
+fill_memory_exit:
+ bx lr /*; We will not use pop as stack may be not available */
+ * unit_test_fill_memory
+ * calls fills_memory function with various paramaters
+ * r0: start address
+ * r1: end address
+ * r2: FILL PATTETN
+ * Debugger used to check filled memeory is as expected.
+ * Note: Last instruction in this routine deliberatly halts code to prevent accidentle enabeling in
+ * release code.
+ MEM_TEST_PATTERN: .word 0x12345678
+unit_test_fill_memory:
+ push {r0, r1, r2, lr}
+ ldr r0, = 0x20000100
+ ldr r1, = 0x20000200
+ ldr r2, MEM_TEST_PATTERN
+ bl fill_memory /* ; fill_memory takes r0 - r2 as arguments */
+ ldr r0, = 0x20000300 /* ; source address */
+ ldr r1, = 0x20000400 /* ; dest address */
+ ldr r2, = 0x200004FF /* ; end address */
+ bl block_copy /* ; copy above */
+ /* second test */
+ ldr r0, = 0x20003300
+ ldr r1, = 0x20003403
+ bl fill_memory
+ ldr r1, = 0x20003500
+ ldr r2, = 0x20003603
+ /* third test */
+ ldr r0, = 0x20000702
+ ldr r1, = 0x20000803
+ ldr r1, = 0x20000902
+ ldr r2, = 0x20000A03
+ /* fourth test */
+ ldr r0, = 0x20000B01
+ ldr r1, = 0x20000C03
+ ldr r1, = 0x20000D01
+ ldr r2, = 0x20000E03
+ /* fith test */
+ ldr r0, = 0x20002D01
+ ldr r1, = 0x20002E01
+ ldr r1, = 0x20002F01
+ ldr r2, = 0x20003001
+ /* sixth test */
+ ldr r0, = 0x20001903
+ ldr r1, = 0x20001904
+ ldr r1, = 0x20001A03
+ ldr r2, = 0x20001A04
+ /* ; final test, note: This one will cause a halt in copy function- as designed */
+ ldr r2, = 0x20000A04 /* ; end address < start address */
+ unit_test_fill_memory_debug: /* ; delibrately wait here, this function only to be used when carrying out test */
+ b . /* ; stop debugger here and verify memory as expected in debugger */
+ pop {r0, r1, r2, pc}
+ * NMI_Handler
+ .weak NMI_Handler
+ .type NMI_Handler, %function
+NMI_Handler:
+ * HardFault_Handler
+ .weak HardFault_Handler
+ .type HardFault_Handler, %function
+HardFault_Handler:
+ * MemManage_Handler
+ .weak MemManage_Handler
+ .type MemManage_Handler, %function
+MemManage_Handler:
+ * BusFault_Handler
+ .weak BusFault_Handler
+ .type BusFault_Handler, %function
+BusFault_Handler:
+ * UsageFault_Handler
+ .weak UsageFault_Handler
+ .type UsageFault_Handler, %function
+UsageFault_Handler:
+ * SVC_Handler
+ .weak SVC_Handler
+ .type SVC_Handler, %function
+SVC_Handler:
+ * DebugMon_Handler
+ .weak DebugMon_Handler
+ .type DebugMon_Handler, %function
+DebugMon_Handler:
+ * PendSV_Handler
+ .weak PendSV_Handler
+ .type PendSV_Handler, %function
+PendSV_Handler:
+ * SysTick_Handler
+ .weak SysTick_Handler
+ .type SysTick_Handler, %function
+SysTick_Handler:
+ * WdogWakeup_IRQHandler
+ .weak WdogWakeup_IRQHandler
+ .type WdogWakeup_IRQHandler, %function
+WdogWakeup_IRQHandler:
+ * RTC_Wakeup_IRQHandler
+ .weak RTC_Wakeup_IRQHandler
+ .type RTC_Wakeup_IRQHandler, %function
+RTC_Wakeup_IRQHandler:
+ * SPI0_IRQHandler
+ .weak SPI0_IRQHandler
+ .type SPI0_IRQHandler, %function
+SPI0_IRQHandler:
+ * SPI1_IRQHandler
+ .weak SPI1_IRQHandler
+ .type SPI1_IRQHandler, %function
+SPI1_IRQHandler:
+ * I2C0_IRQHandler
+ .weak I2C0_IRQHandler
+ .type I2C0_IRQHandler, %function
+I2C0_IRQHandler:
+ * I2C0_SMBAlert_IRQHandler
+ .weak I2C0_SMBAlert_IRQHandler
+ .type I2C0_SMBAlert_IRQHandler, %function
+I2C0_SMBAlert_IRQHandler:
+ * I2C0_SMBus_IRQHandler
+ .weak I2C0_SMBus_IRQHandler
+ .type I2C0_SMBus_IRQHandler, %function
+I2C0_SMBus_IRQHandler:
+ * I2C1_IRQHandler
+ .weak I2C1_IRQHandler
+ .type I2C1_IRQHandler, %function
+I2C1_IRQHandler:
+ * I2C1_SMBAlert_IRQHandler
+ .weak I2C1_SMBAlert_IRQHandler
+ .type I2C1_SMBAlert_IRQHandler, %function
+I2C1_SMBAlert_IRQHandler:
+ * I2C1_SMBus_IRQHandler
+ .weak I2C1_SMBus_IRQHandler
+ .type I2C1_SMBus_IRQHandler, %function
+I2C1_SMBus_IRQHandler:
+ * UART0_IRQHandler
+ .weak UART0_IRQHandler
+ .type UART0_IRQHandler, %function
+UART0_IRQHandler:
+ * UART1_IRQHandler
+ .weak UART1_IRQHandler
+ .type UART1_IRQHandler, %function
+UART1_IRQHandler:
+ * EthernetMAC_IRQHandler
+ .weak EthernetMAC_IRQHandler
+ .type EthernetMAC_IRQHandler, %function
+EthernetMAC_IRQHandler:
+ * DMA_IRQHandler
+ .weak DMA_IRQHandler
+ .type DMA_IRQHandler, %function
+DMA_IRQHandler:
+ * Timer1_IRQHandler
+ .weak Timer1_IRQHandler
+ .type Timer1_IRQHandler, %function
+Timer1_IRQHandler:
+ * Timer2_IRQHandler
+ .weak Timer2_IRQHandler
+ .type Timer2_IRQHandler, %function
+Timer2_IRQHandler:
+ * CAN_IRQHandler
+ .weak CAN_IRQHandler
+ .type CAN_IRQHandler, %function
+CAN_IRQHandler:
+ * ENVM0_IRQHandler
+ .weak ENVM0_IRQHandler
+ .type ENVM0_IRQHandler, %function
+ENVM0_IRQHandler:
+ * ENVM1_IRQHandler
+ .weak ENVM1_IRQHandler
+ .type ENVM1_IRQHandler, %function
+ENVM1_IRQHandler:
+ * ComBlk_IRQHandler
+ .weak ComBlk_IRQHandler
+ .type ComBlk_IRQHandler, %function
+ComBlk_IRQHandler:
+ * USB_IRQHandler
+ .weak USB_IRQHandler
+ .type USB_IRQHandler, %function
+USB_IRQHandler:
+ * USB_DMA_IRQHandler
+ .weak USB_DMA_IRQHandler
+ .type USB_DMA_IRQHandler, %function
+USB_DMA_IRQHandler:
+ * PLL_Lock_IRQHandler
+ .weak PLL_Lock_IRQHandler
+ .type PLL_Lock_IRQHandler, %function
+PLL_Lock_IRQHandler:
+ * PLL_LockLost_IRQHandler
+ .weak PLL_LockLost_IRQHandler
+ .type PLL_LockLost_IRQHandler, %function
+PLL_LockLost_IRQHandler:
+ * CommSwitchError_IRQHandler
+ .weak CommSwitchError_IRQHandler
+ .type CommSwitchError_IRQHandler, %function
+CommSwitchError_IRQHandler:
+ * CacheError_IRQHandler
+ .weak CacheError_IRQHandler
+ .type CacheError_IRQHandler, %function
+CacheError_IRQHandler:
+ * DDR_IRQHandler
+ .weak DDR_IRQHandler
+ .type DDR_IRQHandler, %function
+DDR_IRQHandler:
+ * HPDMA_Complete_IRQHandler
+ .weak HPDMA_Complete_IRQHandler
+ .type HPDMA_Complete_IRQHandler, %function
+HPDMA_Complete_IRQHandler:
+ * HPDMA_Error_IRQHandler
+ .weak HPDMA_Error_IRQHandler
+ .type HPDMA_Error_IRQHandler, %function
+HPDMA_Error_IRQHandler:
+ * ECC_Error_IRQHandler
+ .weak ECC_Error_IRQHandler
+ .type ECC_Error_IRQHandler, %function
+ECC_Error_IRQHandler:
+ * MDDR_IOCalib_IRQHandler
+ .weak MDDR_IOCalib_IRQHandler
+ .type MDDR_IOCalib_IRQHandler, %function
+MDDR_IOCalib_IRQHandler:
+ * FAB_PLL_Lock_IRQHandler
+ .weak FAB_PLL_Lock_IRQHandler
+ .type FAB_PLL_Lock_IRQHandler, %function
+FAB_PLL_Lock_IRQHandler:
+ * FAB_PLL_LockLost_IRQHandler
+ .weak FAB_PLL_LockLost_IRQHandler
+ .type FAB_PLL_LockLost_IRQHandler, %function
+FAB_PLL_LockLost_IRQHandler:
+ * FIC64_IRQHandler
+ .weak FIC64_IRQHandler
+ .type FIC64_IRQHandler, %function
+FIC64_IRQHandler:
+ * FabricIrq0_IRQHandler
+ .weak FabricIrq0_IRQHandler
+ .type FabricIrq0_IRQHandler, %function
+FabricIrq0_IRQHandler:
+ * FabricIrq1_IRQHandler
+ .weak FabricIrq1_IRQHandler
+ .type FabricIrq1_IRQHandler, %function
+FabricIrq1_IRQHandler:
+ * FabricIrq2_IRQHandler
+ .weak FabricIrq2_IRQHandler
+ .type FabricIrq2_IRQHandler, %function
+FabricIrq2_IRQHandler:
+ * FabricIrq3_IRQHandler
+ .weak FabricIrq3_IRQHandler
+ .type FabricIrq3_IRQHandler, %function
+FabricIrq3_IRQHandler:
+ * FabricIrq4_IRQHandler
+ .weak FabricIrq4_IRQHandler
+ .type FabricIrq4_IRQHandler, %function
+FabricIrq4_IRQHandler:
+ * FabricIrq5_IRQHandler
+ .weak FabricIrq5_IRQHandler
+ .type FabricIrq5_IRQHandler, %function
+FabricIrq5_IRQHandler:
+ * FabricIrq6_IRQHandler
+ .weak FabricIrq6_IRQHandler
+ .type FabricIrq6_IRQHandler, %function
+FabricIrq6_IRQHandler:
+ * FabricIrq7_IRQHandler
+ .weak FabricIrq7_IRQHandler
+ .type FabricIrq7_IRQHandler, %function
+FabricIrq7_IRQHandler:
+ * FabricIrq8_IRQHandler
+ .weak FabricIrq8_IRQHandler
+ .type FabricIrq8_IRQHandler, %function
+FabricIrq8_IRQHandler:
+ * FabricIrq9_IRQHandler
+ .weak FabricIrq9_IRQHandler
+ .type FabricIrq9_IRQHandler, %function
+FabricIrq9_IRQHandler:
+ * FabricIrq10_IRQHandler
+ .weak FabricIrq10_IRQHandler
+ .type FabricIrq10_IRQHandler, %function
+FabricIrq10_IRQHandler:
+ * FabricIrq11_IRQHandler
+ .weak FabricIrq11_IRQHandler
+ .type FabricIrq11_IRQHandler, %function
+FabricIrq11_IRQHandler:
+ * FabricIrq12_IRQHandler
+ .weak FabricIrq12_IRQHandler
+ .type FabricIrq12_IRQHandler, %function
+FabricIrq12_IRQHandler:
+ * FabricIrq13_IRQHandler
+ .weak FabricIrq13_IRQHandler
+ .type FabricIrq13_IRQHandler, %function
+FabricIrq13_IRQHandler:
+ * FabricIrq14_IRQHandler
+ .weak FabricIrq14_IRQHandler
+ .type FabricIrq14_IRQHandler, %function
+FabricIrq14_IRQHandler:
+ * FabricIrq15_IRQHandler
+ .weak FabricIrq15_IRQHandler
+ .type FabricIrq15_IRQHandler, %function
+FabricIrq15_IRQHandler:
+ * GPIO0_IRQHandler
+ .weak GPIO0_IRQHandler
+ .type GPIO0_IRQHandler, %function
+GPIO0_IRQHandler:
+ * GPIO1_IRQHandler
+ .weak GPIO1_IRQHandler
+ .type GPIO1_IRQHandler, %function
+GPIO1_IRQHandler:
+ * GPIO2_IRQHandler
+ .weak GPIO2_IRQHandler
+ .type GPIO2_IRQHandler, %function
+GPIO2_IRQHandler:
+ * GPIO3_IRQHandler
+ .weak GPIO3_IRQHandler
+ .type GPIO3_IRQHandler, %function
+GPIO3_IRQHandler:
+ * GPIO4_IRQHandler
+ .weak GPIO4_IRQHandler
+ .type GPIO4_IRQHandler, %function
+GPIO4_IRQHandler:
+ * GPIO5_IRQHandler
+ .weak GPIO5_IRQHandler
+ .type GPIO5_IRQHandler, %function
+GPIO5_IRQHandler:
+ * GPIO6_IRQHandler
+ .weak GPIO6_IRQHandler
+ .type GPIO6_IRQHandler, %function
+GPIO6_IRQHandler:
+ * GPIO7_IRQHandler
+ .weak GPIO7_IRQHandler
+ .type GPIO7_IRQHandler, %function
+GPIO7_IRQHandler:
+ * GPIO8_IRQHandler
+ .weak GPIO8_IRQHandler
+ .type GPIO8_IRQHandler, %function
+GPIO8_IRQHandler:
+ * GPIO9_IRQHandler
+ .weak GPIO9_IRQHandler
+ .type GPIO9_IRQHandler, %function
+GPIO9_IRQHandler:
+ * GPIO10_IRQHandler
+ .weak GPIO10_IRQHandler
+ .type GPIO10_IRQHandler, %function
+GPIO10_IRQHandler:
+ * GPIO11_IRQHandler
+ .weak GPIO11_IRQHandler
+ .type GPIO11_IRQHandler, %function
+GPIO11_IRQHandler:
+ * GPIO12_IRQHandler
+ .weak GPIO12_IRQHandler
+ .type GPIO12_IRQHandler, %function
+GPIO12_IRQHandler:
+ * GPIO13_IRQHandler
+ .weak GPIO13_IRQHandler
+ .type GPIO13_IRQHandler, %function
+GPIO13_IRQHandler:
+ * GPIO14_IRQHandler
+ .weak GPIO14_IRQHandler
+ .type GPIO14_IRQHandler, %function
+GPIO14_IRQHandler:
+ * GPIO15_IRQHandler
+ .weak GPIO15_IRQHandler
+ .type GPIO15_IRQHandler, %function
+GPIO15_IRQHandler:
+ * GPIO16_IRQHandler
+ .weak GPIO16_IRQHandler
+ .type GPIO16_IRQHandler, %function
+GPIO16_IRQHandler:
+ * GPIO17_IRQHandler
+ .weak GPIO17_IRQHandler
+ .type GPIO17_IRQHandler, %function
+GPIO17_IRQHandler:
+ * GPIO18_IRQHandler
+ .weak GPIO18_IRQHandler
+ .type GPIO18_IRQHandler, %function
+GPIO18_IRQHandler:
+ * GPIO19_IRQHandler
+ .weak GPIO19_IRQHandler
+ .type GPIO19_IRQHandler, %function
+GPIO19_IRQHandler:
+ * GPIO20_IRQHandler
+ .weak GPIO20_IRQHandler
+ .type GPIO20_IRQHandler, %function
+GPIO20_IRQHandler:
+ * GPIO21_IRQHandler
+ .weak GPIO21_IRQHandler
+ .type GPIO21_IRQHandler, %function
+GPIO21_IRQHandler:
+ * GPIO22_IRQHandler
+ .weak GPIO22_IRQHandler
+ .type GPIO22_IRQHandler, %function
+GPIO22_IRQHandler:
+ * GPIO23_IRQHandler
+ .weak GPIO23_IRQHandler
+ .type GPIO23_IRQHandler, %function
+GPIO23_IRQHandler:
+ * GPIO24_IRQHandler
+ .weak GPIO24_IRQHandler
+ .type GPIO24_IRQHandler, %function
+GPIO24_IRQHandler:
+ * GPIO25_IRQHandler
+ .weak GPIO25_IRQHandler
+ .type GPIO25_IRQHandler, %function
+GPIO25_IRQHandler:
+ * GPIO26_IRQHandler
+ .weak GPIO26_IRQHandler
+ .type GPIO26_IRQHandler, %function
+GPIO26_IRQHandler:
+ * GPIO27_IRQHandler
+ .weak GPIO27_IRQHandler
+ .type GPIO27_IRQHandler, %function
+GPIO27_IRQHandler:
+ * GPIO28_IRQHandler
+ .weak GPIO28_IRQHandler
+ .type GPIO28_IRQHandler, %function
+GPIO28_IRQHandler:
+ * GPIO29_IRQHandler
+ .weak GPIO29_IRQHandler
+ .type GPIO29_IRQHandler, %function
+GPIO29_IRQHandler:
+ * GPIO30_IRQHandler
+ .weak GPIO30_IRQHandler
+ .type GPIO30_IRQHandler, %function
+GPIO30_IRQHandler:
+ * GPIO31_IRQHandler
+ .weak GPIO31_IRQHandler
+ .type GPIO31_IRQHandler, %function
+GPIO31_IRQHandler:
+ * mscc_post_hw_cfg_init
+ .weak mscc_post_hw_cfg_init
+ .type mscc_post_hw_cfg_init, %function
+mscc_post_hw_cfg_init:
+ * Constants:
+RAM_INIT_PATTERN: .word 0x00000000
+HEAP_INIT_PATTERN: .word 0xA2A2A2A2
+SF2_ESRAM_CR: .word 0x40038000
+SF2_DDR_CR: .word 0x40038008
+SF2_ENVM_REMAP_CR: .word 0x40038010
+SF2_DDRB_NB_SIZE: .word 0x40038030
+SF2_DDRB_CR: .word 0x40038034
+SF2_EDAC_CR: .word 0x40038038
+SF2_MDDR_MODE_CR: .word 0x40020818
+.end
@@ -0,0 +1,212 @@
+ * (c) Copyright 2012 Microsemi SoC Products Group. All rights reserved.
+ * SVN $Revision: 4410 $
+ * SVN $Date: 2012-07-16 14:36:17 +0100 (Mon, 16 Jul 2012) $
+#ifndef SYSTEM_INIT_CFG_TYPES_H_
+#define SYSTEM_INIT_CFG_TYPES_H_
+/*============================================================================*/
+/* DDR Configuration */
+ uint16_t DYN_SOFT_RESET_CR;
+ uint16_t RESERVED0;
+ uint16_t DYN_REFRESH_1_CR;
+ uint16_t DYN_REFRESH_2_CR;
+ uint16_t DYN_POWERDOWN_CR;
+ uint16_t DYN_DEBUG_CR;
+ uint16_t MODE_CR;
+ uint16_t ADDR_MAP_BANK_CR;
+ uint16_t ECC_DATA_MASK_CR;
+ uint16_t ADDR_MAP_COL_1_CR;
+ uint16_t ADDR_MAP_COL_2_CR;
+ uint16_t ADDR_MAP_ROW_1_CR;
+ uint16_t ADDR_MAP_ROW_2_CR;
+ uint16_t INIT_1_CR;
+ uint16_t CKE_RSTN_CYCLES_1_CR;
+ uint16_t CKE_RSTN_CYCLES_2_CR;
+ uint16_t INIT_MR_CR;
+ uint16_t INIT_EMR_CR;
+ uint16_t INIT_EMR2_CR;
+ uint16_t INIT_EMR3_CR;
+ uint16_t DRAM_BANK_TIMING_PARAM_CR;
+ uint16_t DRAM_RD_WR_LATENCY_CR;
+ uint16_t DRAM_RD_WR_PRE_CR;
+ uint16_t DRAM_MR_TIMING_PARAM_CR;
+ uint16_t DRAM_RAS_TIMING_CR;
+ uint16_t DRAM_RD_WR_TRNARND_TIME_CR;
+ uint16_t DRAM_T_PD_CR;
+ uint16_t DRAM_BANK_ACT_TIMING_CR;
+ uint16_t ODT_PARAM_1_CR;
+ uint16_t ODT_PARAM_2_CR;
+ uint16_t ADDR_MAP_COL_3_CR;
+ uint16_t MODE_REG_RD_WR_CR;
+ uint16_t MODE_REG_DATA_CR;
+ uint16_t PWR_SAVE_1_CR;
+ uint16_t PWR_SAVE_2_CR;
+ uint16_t ZQ_LONG_TIME_CR;
+ uint16_t ZQ_SHORT_TIME_CR;
+ uint16_t ZQ_SHORT_INT_REFRESH_MARGIN_1_CR;
+ uint16_t ZQ_SHORT_INT_REFRESH_MARGIN_2_CR;
+ uint16_t PERF_PARAM_1_CR;
+ uint16_t HPR_QUEUE_PARAM_1_CR;
+ uint16_t HPR_QUEUE_PARAM_2_CR;
+ uint16_t LPR_QUEUE_PARAM_1_CR;
+ uint16_t LPR_QUEUE_PARAM_2_CR;
+ uint16_t WR_QUEUE_PARAM_CR;
+ uint16_t PERF_PARAM_2_CR;
+ uint16_t PERF_PARAM_3_CR;
+ uint16_t DFI_RDDATA_EN_CR;
+ uint16_t DFI_MIN_CTRLUPD_TIMING_CR;
+ uint16_t DFI_MAX_CTRLUPD_TIMING_CR;
+ uint16_t DFI_WR_LVL_CONTROL_1_CR;
+ uint16_t DFI_WR_LVL_CONTROL_2_CR;
+ uint16_t DFI_RD_LVL_CONTROL_1_CR;
+ uint16_t DFI_RD_LVL_CONTROL_2_CR;
+ uint16_t DFI_CTRLUPD_TIME_INTERVAL_CR;
+ uint16_t DYN_SOFT_RESET_CR2;
+ uint16_t AXI_FABRIC_PRI_ID_CR;
+ uint16_t LOOPBACK_TEST_CR;
+ uint16_t BOARD_LOOPBACK_CR;
+ uint16_t CTRL_SLAVE_RATIO_CR;
+ uint16_t CTRL_SLAVE_FORCE_CR;
+ uint16_t CTRL_SLAVE_DELAY_CR;
+ uint16_t DATA_SLICE_IN_USE_CR;
+ uint16_t LVL_NUM_OF_DQ0_CR;
+ uint16_t DQ_OFFSET_1_CR;
+ uint16_t DQ_OFFSET_2_CR;
+ uint16_t DQ_OFFSET_3_CR;
+ uint16_t DIS_CALIB_RST_CR;
+ uint16_t DLL_LOCK_DIFF_CR;
+ uint16_t FIFO_WE_IN_DELAY_1_CR;
+ uint16_t FIFO_WE_IN_DELAY_2_CR;
+ uint16_t FIFO_WE_IN_DELAY_3_CR;
+ uint16_t FIFO_WE_IN_FORCE_CR;
+ uint16_t FIFO_WE_SLAVE_RATIO_1_CR;
+ uint16_t FIFO_WE_SLAVE_RATIO_2_CR;
+ uint16_t FIFO_WE_SLAVE_RATIO_3_CR;
+ uint16_t FIFO_WE_SLAVE_RATIO_4_CR;
+ uint16_t GATELVL_INIT_MODE_CR;
+ uint16_t GATELVL_INIT_RATIO_1_CR;
+ uint16_t GATELVL_INIT_RATIO_2_CR;
+ uint16_t GATELVL_INIT_RATIO_3_CR;
+ uint16_t GATELVL_INIT_RATIO_4_CR;
+ uint16_t LOCAL_ODT_CR;
+ uint16_t INVERT_CLKOUT_CR;
+ uint16_t RD_DQS_SLAVE_DELAY_1_CR;
+ uint16_t RD_DQS_SLAVE_DELAY_2_CR;
+ uint16_t RD_DQS_SLAVE_DELAY_3_CR;
+ uint16_t RD_DQS_SLAVE_FORCE_CR;
+ uint16_t RD_DQS_SLAVE_RATIO_1_CR;
+ uint16_t RD_DQS_SLAVE_RATIO_2_CR;
+ uint16_t RD_DQS_SLAVE_RATIO_3_CR;
+ uint16_t RD_DQS_SLAVE_RATIO_4_CR;
+ uint16_t WR_DQS_SLAVE_DELAY_1_CR;
+ uint16_t WR_DQS_SLAVE_DELAY_2_CR;
+ uint16_t WR_DQS_SLAVE_DELAY_3_CR;
+ uint16_t WR_DQS_SLAVE_FORCE_CR;
+ uint16_t WR_DQS_SLAVE_RATIO_1_CR;
+ uint16_t WR_DQS_SLAVE_RATIO_2_CR;
+ uint16_t WR_DQS_SLAVE_RATIO_3_CR;
+ uint16_t WR_DQS_SLAVE_RATIO_4_CR;
+ uint16_t WR_DATA_SLAVE_DELAY_1_CR;
+ uint16_t WR_DATA_SLAVE_DELAY_2_CR;
+ uint16_t WR_DATA_SLAVE_DELAY_3_CR;
+ uint16_t WR_DATA_SLAVE_FORCE_CR;
+ uint16_t WR_DATA_SLAVE_RATIO_1_CR;
+ uint16_t WR_DATA_SLAVE_RATIO_2_CR;
+ uint16_t WR_DATA_SLAVE_RATIO_3_CR;
+ uint16_t WR_DATA_SLAVE_RATIO_4_CR;
+ uint16_t WRLVL_INIT_MODE_CR;
+ uint16_t WRLVL_INIT_RATIO_1_CR;
+ uint16_t WRLVL_INIT_RATIO_2_CR;
+ uint16_t WRLVL_INIT_RATIO_3_CR;
+ uint16_t WRLVL_INIT_RATIO_4_CR;
+ uint16_t WR_RD_RL_CR;
+ uint16_t RDC_FIFO_RST_ERRCNTCLR_CR;
+ uint16_t RDC_WE_TO_RE_DELAY_CR;
+ uint16_t USE_FIXED_RE_CR;
+ uint16_t USE_RANK0_DELAYS_CR;
+ uint16_t USE_LVL_TRNG_LEVEL_CR;
+ uint16_t CONFIG_CR;
+ uint16_t RD_WR_GATE_LVL_CR;
+ uint16_t DYN_RESET_CR;
+ uint16_t NB_ADDR_CR;
+ uint16_t NBRWB_SIZE_CR;
+ uint16_t WB_TIMEOUT_CR;
+ uint16_t HPD_SW_RW_EN_CR;
+ uint16_t HPD_SW_RW_INVAL_CR;
+ uint16_t SW_WR_ERCLR_CR;
+ uint16_t ERR_INT_ENABLE_CR;
+ uint16_t NUM_AHB_MASTERS_CR;
+ uint16_t LOCK_TIMEOUTVAL_1_CR;
+ uint16_t LOCK_TIMEOUTVAL_2_CR;
+ uint16_t LOCK_TIMEOUT_EN_CR;
+} ddr_subsys_cfg_t;
+/* FDDR Configuration */
+ uint16_t PLL_CONFIG_LOW_1;
+ uint16_t PLL_CONFIG_LOW_2;
+ uint16_t PLL_CONFIG_HIGH;
+ uint16_t FACC_CLK_EN;
+ uint16_t FACC_MUX_CONFIG;
+ uint16_t FACC_DIVISOR_RATIO;
+ uint16_t PLL_DELAY_LINE_SEL;
+ uint16_t SOFT_RESET;
+ uint16_t IO_CALIB;
+ uint16_t INTERRUPT_ENABLE;
+ uint16_t AXI_AHB_MODE_SEL;
+ uint16_t PHY_SELF_REF_EN;
+} fddr_sysreg_t;
+/* PCI Express Bridge IP Core configuration. */
+ uint32_t * p_reg;
+ uint32_t value;
+} cfg_addr_value_pair_t;
+#endif /* SYSTEM_INIT_CFG_TYPES_H_ */
@@ -0,0 +1,1005 @@
+ * (c) Copyright 2012-2013 Microsemi SoC Products Group. All rights reserved.
+ * SmartFusion2 CMSIS system initialization.
+#if MSCC_NO_RELATIVE_PATHS
+#include "sys_config.h"
+#include "sys_init_cfg_types.h"
+ Silicon revisions.
+#define UNKNOWN_SILICON_REV 0
+#define M2S050_REV_A_SILICON 1
+#define M2S050_REV_B_SILICON 2
+ * CoreConfigP IP block version.
+#define CORE_CONFIGP_V7_0 0x00070000u
+void mscc_post_hw_cfg_init(void);
+ * CoreConfigP/CoreConfigP register bits
+#define CONFIG_1_DONE 1u
+#define CONFIG_2_DONE 2u
+#define INIT_DONE_MASK 0x00000001u
+#define SDIF_RELEASED_MASK 0x00000002u
+ * System registers of interest.
+ * MSSDDR_FACC1_CR register masks:
+#define DDR_CLK_EN_SHIFT 8u
+#define FACC_GLMUX_SEL_MASK 0x00001000u
+#define CONTROLLER_PLL_INIT_MASK 0x04000000u
+#define RCOSC_DIV2_MASK 0x00000004u
+ * MSSDDR_PLL_STATUS register masks:
+#define FAB_PLL_LOCK_MASK 0x00000001u
+#define MPLL_LOCK_MASK 0x00000002u
+ * MSSDDR_PLL_STATUS_HIGH_CR register masks:
+#define FACC_PLL_BYPASS_MASK 0x00000001u
+ * Standard CMSIS global variables.
+uint32_t SystemCoreClock = MSS_SYS_M3_CLK_FREQ; /*!< System Clock Frequency (Core Clock) */
+ * SmartFusion2 specific clocks.
+uint32_t g_FrequencyPCLK0 = MSS_SYS_APB_0_CLK_FREQ; /*!< Clock frequency of APB bus 0. */
+uint32_t g_FrequencyPCLK1 = MSS_SYS_APB_1_CLK_FREQ; /*!< Clock frequency of APB bus 1. */
+uint32_t g_FrequencyPCLK2 = MSS_SYS_APB_2_CLK_FREQ; /*!< Clock frequency of APB bus 2. */
+uint32_t g_FrequencyFIC0 = MSS_SYS_FIC_0_CLK_FREQ; /*!< Clock frequecny of FPGA fabric interface controller 1. */
+uint32_t g_FrequencyFIC1 = MSS_SYS_FIC_1_CLK_FREQ; /*!< Clock frequecny of FPGA fabric inteface controller 2. */
+uint32_t g_FrequencyFIC64 = MSS_SYS_FIC64_CLK_FREQ; /*!< Clock frequecny of 64-bit FPGA fabric interface controller. */
+ * System configuration tables generated by Libero.
+#if MSS_SYS_MDDR_CONFIG_BY_CORTEX
+extern MDDR_TypeDef * const g_m2s_mddr_addr;
+extern const ddr_subsys_cfg_t g_m2s_mddr_subsys_config;
+#if MSS_SYS_FDDR_CONFIG_BY_CORTEX
+extern FDDR_TypeDef * const g_m2s_fddr_addr;
+extern const ddr_subsys_cfg_t g_m2s_fddr_subsys_config;
+#define MSS_SYS_SERDES_CONFIG_BY_CORTEX (MSS_SYS_SERDES_0_CONFIG_BY_CORTEX || MSS_SYS_SERDES_1_CONFIG_BY_CORTEX || MSS_SYS_SERDES_2_CONFIG_BY_CORTEX || MSS_SYS_SERDES_3_CONFIG_BY_CORTEX)
+#if MSS_SYS_SERDES_0_CONFIG_BY_CORTEX
+extern const cfg_addr_value_pair_t g_m2s_serdes_0_config[SERDES_0_CFG_NB_OF_PAIRS];
+#if MSS_SYS_SERDES_1_CONFIG_BY_CORTEX
+extern const cfg_addr_value_pair_t g_m2s_serdes_1_config[SERDES_1_CFG_NB_OF_PAIRS];
+#if MSS_SYS_SERDES_2_CONFIG_BY_CORTEX
+extern const cfg_addr_value_pair_t g_m2s_serdes_2_config[SERDES_2_CFG_NB_OF_PAIRS];
+#if MSS_SYS_SERDES_3_CONFIG_BY_CORTEX
+extern const cfg_addr_value_pair_t g_m2s_serdes_3_config[SERDES_3_CFG_NB_OF_PAIRS];
+#define MSS_SYS_CORESF2RESET_USED (MSS_SYS_MDDR_CONFIG_BY_CORTEX || MSS_SYS_FDDR_CONFIG_BY_CORTEX || MSS_SYS_SERDES_CONFIG_BY_CORTEX)
+ * List of PCIe lanes on which PMA_READY must be polled. Allows only polling PMA
+ * READY on the first lane of a PCIe link regardless of the number of lanes used
+ * or whether lane reversal is used.
+#if MSS_SYS_SERDES_CONFIG_BY_CORTEX
+#define CONFIG_REG_LANE_SEL_LANE_0 0x00000100U
+#define CONFIG_REG_LANE_SEL_LANE_1 0x00000200U
+#define CONFIG_REG_LANE_SEL_LANE_2 0x00000400U
+#define CONFIG_REG_LANE_SEL_LANE_3 0x00000800U
+#define CONFIG_REG_LANE_SEL_MASK (CONFIG_REG_LANE_SEL_LANE_0 | \
+ CONFIG_REG_LANE_SEL_LANE_1 | \
+ CONFIG_REG_LANE_SEL_LANE_2 | \
+ CONFIG_REG_LANE_SEL_LANE_3)
+#define FIRST_PCIE_CTRL 1U
+#define SECOND_PCIE_CTRL 2U
+typedef struct pma_poll_info
+ SERDESIF_TypeDef * serdes;
+ SERDES_TypeDef * const lane;
+ uint16_t config_reg_lane_sel;
+ uint16_t pcie_ctrl_id; /* distinguish between first and second PCIe controller on M2S090. */
+} pma_poll_info_t;
+ * SERDES0: list of PMA to poll as part of PCIe configuration. This list only
+ * handles the first PCIe controller of SERDES0.
+static const pma_poll_info_t g_serdes0_pcie_lane_cfg_lut[] =
+ #if defined(SERDESIF_0_PCIE_LANE_PMA_STATUS_LANE_0)
+ SERDES0, /* SERDESIF_TypeDef * serdes */
+ &SERDES0->lane[0], /* SERDES_TypeDef * const lane */
+ CONFIG_REG_LANE_SEL_LANE_0, /* uint16_t config_reg_lane_sel */
+ FIRST_PCIE_CTRL /* uint16_t pcie_ctrl_id */
+ },
+ #endif
+ #if defined(SERDESIF_0_PCIE_LANE_PMA_STATUS_LANE_1)
+ &SERDES0->lane[1], /* SERDES_TypeDef * const lane */
+ CONFIG_REG_LANE_SEL_LANE_1, /* uint16_t config_reg_lane_sel */
+ #if defined(SERDESIF_0_PCIE_LANE_PMA_STATUS_LANE_2)
+ &SERDES0->lane[2], /* SERDES_TypeDef * const lane */
+ CONFIG_REG_LANE_SEL_LANE_2, /* uint16_t config_reg_lane_sel */
+ #if defined(SERDESIF_0_PCIE_LANE_PMA_STATUS_LANE_3)
+ &SERDES0->lane[3], /* SERDES_TypeDef * const lane */
+ CONFIG_REG_LANE_SEL_LANE_3, /* uint16_t config_reg_lane_sel */
+ (SERDESIF_TypeDef *)0, /* SERDESIF_TypeDef * serdes */
+ (SERDES_TypeDef *)0, /* SERDES_TypeDef * const lane */
+ 0, /* uint16_t config_reg_lane_sel */
+ 0 /* uint16_t pcie_ctrl_id */
+ * SERDES1: list of PMA to poll as part of PCIe configuration. This list handles
+ * both SERDES1 first PCIe controller and the M2S090 SERDES0 second PCIe
+ * controller.
+static const pma_poll_info_t g_serdes1_pcie_lane_cfg_lut[] =
+ #if defined(SERDESIF_1_PCIE_LANE_PMA_STATUS_LANE_0)
+ SERDES1, /* SERDESIF_TypeDef * serdes */
+ &SERDES1->lane[0], /* SERDES_TypeDef * const lane */
+ #if defined(SERDESIF_1_PCIE_LANE_PMA_STATUS_LANE_1)
+ &SERDES1->lane[1], /* SERDES_TypeDef * const lane */
+ #if defined(SERDESIF_1_PCIE_LANE_PMA_STATUS_LANE_2)
+ &SERDES1->lane[2], /* SERDES_TypeDef * const lane */
+ #if defined(SERDESIF_1_PCIE_LANE_PMA_STATUS_LANE_3)
+ &SERDES1->lane[3], /* SERDES_TypeDef * const lane */
+ #if defined(SERDESIF_0_PCIE_1_LANE_PMA_STATUS_LANE_0)
+ SECOND_PCIE_CTRL /* uint16_t pcie_ctrl_id */
+ #if defined(SERDESIF_0_PCIE_1_LANE_PMA_STATUS_LANE_1)
+ #if defined(SERDESIF_0_PCIE_1_LANE_PMA_STATUS_LANE_2)
+ #if defined(SERDESIF_0_PCIE_1_LANE_PMA_STATUS_LANE_3)
+ * SERDES2: list of PMA to poll as part of PCIe configuration.
+static const pma_poll_info_t g_serdes2_pcie_lane_cfg_lut[] =
+ #if defined(SERDESIF_2_PCIE_LANE_PMA_STATUS_LANE_0)
+ SERDES2, /* SERDESIF_TypeDef * serdes */
+ &SERDES2->lane[0], /* SERDES_TypeDef * const lane */
+ #if defined(SERDESIF_2_PCIE_LANE_PMA_STATUS_LANE_1)
+ &SERDES2->lane[1], /* SERDES_TypeDef * const lane */
+ #if defined(SERDESIF_2_PCIE_LANE_PMA_STATUS_LANE_2)
+ &SERDES2->lane[2], /* SERDES_TypeDef * const lane */
+ #if defined(SERDESIF_2_PCIE_LANE_PMA_STATUS_LANE_3)
+ &SERDES2->lane[3], /* SERDES_TypeDef * const lane */
+ * SERDES3: list of PMA to poll as part of PCIe configuration.
+static const pma_poll_info_t g_serdes3_pcie_lane_cfg_lut[] =
+ #if defined(SERDESIF_3_PCIE_LANE_PMA_STATUS_LANE_0)
+ SERDES3, /* SERDESIF_TypeDef * serdes */
+ &SERDES3->lane[0], /* SERDES_TypeDef * const lane */
+ #if defined(SERDESIF_3_PCIE_LANE_PMA_STATUS_LANE_1)
+ &SERDES3->lane[1], /* SERDES_TypeDef * const lane */
+ #if defined(SERDESIF_3_PCIE_LANE_PMA_STATUS_LANE_2)
+ &SERDES3->lane[2], /* SERDES_TypeDef * const lane */
+ #if defined(SERDESIF_3_PCIE_LANE_PMA_STATUS_LANE_3)
+ &SERDES3->lane[3], /* SERDES_TypeDef * const lane */
+ * Master lookup table for all SERDES PCIe configuration.
+static const pma_poll_info_t * const g_pcie_lane_cfg_lut[] =
+ g_serdes0_pcie_lane_cfg_lut,
+ g_serdes1_pcie_lane_cfg_lut,
+ g_serdes2_pcie_lane_cfg_lut,
+ g_serdes3_pcie_lane_cfg_lut
+ * Local functions:
+static uint32_t get_silicon_revision(void);
+static void silicon_workarounds(void);
+static void m2s050_rev_a_workarounds(void);
+#if (MSS_SYS_FACC_INIT_BY_CORTEX == 1)
+static void complete_clock_config(void);
+static void configure_serdes_intf(void);
+static void configure_pcie_intf(void);
+static void configure_pcie_block
+(
+ const cfg_addr_value_pair_t * p_addr_value_pair,
+ uint32_t nb_of_cfg_pairs,
+ uint32_t serdes_id
+);
+#if (MSS_SYS_MDDR_CONFIG_BY_CORTEX || MSS_SYS_FDDR_CONFIG_BY_CORTEX)
+static void config_ddr_subsys
+ const ddr_subsys_cfg_t * p_ddr_subsys_cfg,
+ DDRCore_TypeDef * p_ddr_subsys_regs
+static void config_by_addr_value
+ uint32_t nb_of_cfg_pairs
+static uint32_t get_rcosc_25_50mhz_frequency(void);
+static void set_clock_frequency_globals(uint32_t fclk);
+/***************************************************************************//**
+ * See system_m2sxxx.h for details.
+void SystemInit(void)
+ uint32_t sdif_released;
+#if MSS_SYS_CORESF2RESET_USED
+ uint32_t init_done;
+ uint32_t core_cfg_version;
+ core_cfg_version = CORE_SF2_CFG->IP_VERSION_SR;
+ * Do not make use of global variables or make any asumptions regarding
+ * memory content if modifying this function. The memory content has not been
+ * initialised by the time this function is called by the start-up code.
+ complete_clock_config();
+ silicon_workarounds();
+ * Set STKALIGN to ensure exception stacking starts on 8 bytes address
+ * boundary. This ensures compliance with the "Procedure Call Standards for
+ * the ARM Architecture" (AAPCS).
+ SCB->CCR |= SCB_CCR_STKALIGN_Msk;
+ * MDDR configuration
+ if(0u == SYSREG->DDR_CR)
+ * We only configure the MDDR memory controller if MDDR is not remapped
+ * to address 0x00000000. If MDDR is remapped to 0x00000000 then we are
+ * probably executing this code from MDDR in a debugging session and
+ * attempting to reconfigure the MDDR memory controller will cause the
+ * Cortex-M3 to crash.
+ config_ddr_subsys(&g_m2s_mddr_subsys_config, &g_m2s_mddr_addr->core);
+ * FDDR configuration
+ config_ddr_subsys(&g_m2s_fddr_subsys_config, &g_m2s_fddr_addr->core);
+ * Call user defined configuration function.
+ mscc_post_hw_cfg_init();
+ * SERDES interfaces configuration.
+ configure_serdes_intf();
+ if(core_cfg_version >= CORE_CONFIGP_V7_0)
+ CORE_SF2_CFG->CONFIG_DONE = CONFIG_1_DONE;
+ /* Poll for SDIF_RELEASED. */
+ do
+ sdif_released = CORE_SF2_CFG->INIT_DONE & SDIF_RELEASED_MASK;
+ } while (0u == sdif_released);
+ configure_pcie_intf();
+ * Synchronize with CoreSF2Reset controlling resets from the fabric.
+ * Negate FPGA_SOFTRESET to de-assert MSS_RESET_N_M2F in the fabric. We must
+ * do this here because this signal is only deasserted by the System
+ * Controller on a power-on reset. Other types of reset such as a watchdog
+ * reset would result in the FPGA fabric being held in reset and getting
+ * stuck waiting for the CoreSF2Config INIT_DONE to become asserted.
+ SYSREG->SOFT_RST_CR &= ~SYSREG_FPGA_SOFTRESET_MASK;
+ * Signal to CoreSF2Reset that peripheral configuration registers have been
+ * written.
+ CORE_SF2_CFG->CONFIG_DONE |= (CONFIG_1_DONE | CONFIG_2_DONE);
+ /* Wait for INIT_DONE from CoreSF2Reset. */
+ init_done = CORE_SF2_CFG->INIT_DONE & INIT_DONE_MASK;
+ } while (0u == init_done);
+ * SystemCoreClockUpdate()
+#define RCOSC_25_50MHZ_CLK_SRC 0u
+#define CLK_XTAL_CLK_SRC 1u
+#define RCOSC_1_MHZ_CLK_SRC 2u
+#define CCC2ASCI_CLK_SRC 3u
+#define FACC_STANDBY_SHIFT 6u
+#define FACC_STANDBY_SEL_MASK 0x00000007u
+#define FREQ_32KHZ 32768u
+#define FREQ_1MHZ 1000000u
+#define FREQ_25MHZ 25000000u
+#define FREQ_50MHZ 50000000u
+void SystemCoreClockUpdate(void)
+ uint32_t controller_pll_init;
+ uint32_t clk_src;
+ controller_pll_init = SYSREG->MSSDDR_FACC1_CR & CONTROLLER_PLL_INIT_MASK;
+ if(0u == controller_pll_init)
+ /* Normal operations. */
+ uint32_t global_mux_sel;
+ global_mux_sel = SYSREG->MSSDDR_FACC1_CR & FACC_GLMUX_SEL_MASK;
+ if(0u == global_mux_sel)
+ /* MSS clocked from MSS PLL. Use Libero flow defines. */
+ SystemCoreClock = MSS_SYS_M3_CLK_FREQ;
+ g_FrequencyPCLK0 = MSS_SYS_APB_0_CLK_FREQ;
+ g_FrequencyPCLK1 = MSS_SYS_APB_1_CLK_FREQ;
+ g_FrequencyPCLK2 = MSS_SYS_APB_2_CLK_FREQ;
+ g_FrequencyFIC0 = MSS_SYS_FIC_0_CLK_FREQ;
+ g_FrequencyFIC1 = MSS_SYS_FIC_1_CLK_FREQ;
+ g_FrequencyFIC64 = MSS_SYS_FIC64_CLK_FREQ;
+ else
+ /* MSS clocked from standby clock. */
+ const uint8_t standby_clock_lut[8] = { RCOSC_25_50MHZ_CLK_SRC,
+ CLK_XTAL_CLK_SRC,
+ RCOSC_25_50MHZ_CLK_SRC,
+ RCOSC_1_MHZ_CLK_SRC,
+ CCC2ASCI_CLK_SRC,
+ CCC2ASCI_CLK_SRC };
+ uint32_t standby_sel;
+ uint8_t clock_source;
+ standby_sel = (SYSREG->MSSDDR_FACC2_CR >> FACC_STANDBY_SHIFT) & FACC_STANDBY_SEL_MASK;
+ clock_source = standby_clock_lut[standby_sel];
+ switch(clock_source)
+ case RCOSC_25_50MHZ_CLK_SRC:
+ clk_src = get_rcosc_25_50mhz_frequency();
+ set_clock_frequency_globals(clk_src);
+ case CLK_XTAL_CLK_SRC:
+ set_clock_frequency_globals(FREQ_32KHZ);
+ case RCOSC_1_MHZ_CLK_SRC:
+ set_clock_frequency_globals(FREQ_1MHZ);
+ case CCC2ASCI_CLK_SRC:
+ /* Fall through. */
+ /* PLL initialization mode. Running from 25/50MHZ RC oscillator. */
+ * Find out frequency generated by the 25_50mhz RC osciallator.
+static uint32_t get_rcosc_25_50mhz_frequency(void)
+ uint32_t rcosc_div2;
+ uint32_t rcosc_frequency;
+ rcosc_div2 = SYSREG->MSSDDR_PLL_STATUS & RCOSC_DIV2_MASK;
+ if(0u == rcosc_div2)
+ /* 25_50mhz oscillator is configured for 25 MHz operations. */
+ rcosc_frequency = FREQ_25MHZ;
+ /* 25_50mhz oscillator is configured for 50 MHz operations. */
+ rcosc_frequency = FREQ_50MHZ;
+ return rcosc_frequency;
+ Set the value of the clock frequency global variables based on the value of
+ standby_clk passed as parameter.
+ The following global variables are set by this function:
+ - SystemCoreClock
+ - g_FrequencyPCLK0
+ - g_FrequencyPCLK1
+ - g_FrequencyPCLK2
+ - g_FrequencyFIC0
+ - g_FrequencyFIC1
+ - g_FrequencyFIC64
+static void set_clock_frequency_globals(uint32_t standby_clk)
+ SystemCoreClock = standby_clk;
+ g_FrequencyPCLK0 = standby_clk;
+ g_FrequencyPCLK1 = standby_clk;
+ g_FrequencyFIC0 = standby_clk;
+ g_FrequencyFIC1 = standby_clk;
+ g_FrequencyFIC64 = standby_clk;
+ * Write 16-bit configuration values into 32-bit word aligned registers.
+static void copy_cfg16_to_regs
+ volatile uint32_t * p_regs,
+ const uint16_t * p_cfg,
+ uint32_t nb_16bit_words
+)
+ uint32_t inc;
+ for(inc = 0u; inc < nb_16bit_words; ++inc)
+ p_regs[inc] = p_cfg[inc];
+ * Configure peripheral using register address and register value pairs.
+ for(inc = 0u; inc < nb_of_cfg_pairs; ++inc)
+ *p_addr_value_pair[inc].p_reg = p_addr_value_pair[inc].value;
+ * DDR subsystem configuration.
+#define NB_OF_DDRC_REGS_TO_CONFIG 57u
+#define NB_OF_DDR_PHY_REGS_TO_CONFIG 65u
+ volatile uint32_t * p_regs;
+ const uint16_t * p_cfg;
+ * Configure DDR controller part of the MDDR subsystem.
+ p_cfg = &p_ddr_subsys_cfg->ddrc.DYN_SOFT_RESET_CR;
+ p_regs = &p_ddr_subsys_regs->ddrc.DYN_SOFT_RESET_CR;
+ copy_cfg16_to_regs(p_regs, p_cfg, NB_OF_DDRC_REGS_TO_CONFIG);
+ * Configure DDR PHY.
+ p_cfg = &p_ddr_subsys_cfg->phy.LOOPBACK_TEST_CR;
+ p_regs = &p_ddr_subsys_regs->phy.LOOPBACK_TEST_CR;
+ copy_cfg16_to_regs(p_regs, p_cfg, NB_OF_DDR_PHY_REGS_TO_CONFIG);
+ * Configure DDR FIC.
+ p_ddr_subsys_regs->fic.NB_ADDR_CR = p_ddr_subsys_cfg->fic.NB_ADDR_CR;
+ p_ddr_subsys_regs->fic.NBRWB_SIZE_CR = p_ddr_subsys_cfg->fic.NBRWB_SIZE_CR;
+ p_ddr_subsys_regs->fic.WB_TIMEOUT_CR = p_ddr_subsys_cfg->fic.WB_TIMEOUT_CR;
+ p_ddr_subsys_regs->fic.HPD_SW_RW_EN_CR = p_ddr_subsys_cfg->fic.HPD_SW_RW_EN_CR;
+ p_ddr_subsys_regs->fic.HPD_SW_RW_INVAL_CR = p_ddr_subsys_cfg->fic.HPD_SW_RW_INVAL_CR;
+ p_ddr_subsys_regs->fic.SW_WR_ERCLR_CR = p_ddr_subsys_cfg->fic.SW_WR_ERCLR_CR;
+ p_ddr_subsys_regs->fic.ERR_INT_ENABLE_CR = p_ddr_subsys_cfg->fic.ERR_INT_ENABLE_CR;
+ p_ddr_subsys_regs->fic.NUM_AHB_MASTERS_CR = p_ddr_subsys_cfg->fic.NUM_AHB_MASTERS_CR;
+ p_ddr_subsys_regs->fic.LOCK_TIMEOUTVAL_CR[0] = p_ddr_subsys_cfg->fic.LOCK_TIMEOUTVAL_1_CR;
+ p_ddr_subsys_regs->fic.LOCK_TIMEOUTVAL_CR[1] = p_ddr_subsys_cfg->fic.LOCK_TIMEOUTVAL_2_CR;
+ p_ddr_subsys_regs->fic.LOCK_TIMEOUT_EN_CR = p_ddr_subsys_cfg->fic.LOCK_TIMEOUT_EN_CR;
+ * Enable DDR.
+ p_ddr_subsys_regs->ddrc.DYN_SOFT_RESET_CR = 0x01u;
+ while(0x0000u == p_ddr_subsys_regs->ddrc.DDRC_SR)
+ * Configure SERDES interfaces.
+static void configure_serdes_intf(void)
+ #if MSS_SYS_SERDES_0_CONFIG_BY_CORTEX
+ config_by_addr_value(g_m2s_serdes_0_config, SERDES_0_CFG_NB_OF_PAIRS);
+ #if MSS_SYS_SERDES_1_CONFIG_BY_CORTEX
+ config_by_addr_value(g_m2s_serdes_1_config, SERDES_1_CFG_NB_OF_PAIRS);
+ #if MSS_SYS_SERDES_2_CONFIG_BY_CORTEX
+ config_by_addr_value(g_m2s_serdes_2_config, SERDES_2_CFG_NB_OF_PAIRS);
+ #if MSS_SYS_SERDES_3_CONFIG_BY_CORTEX
+ config_by_addr_value(g_m2s_serdes_3_config, SERDES_3_CFG_NB_OF_PAIRS);
+ * Configure PCIe interfaces.
+static void configure_pcie_intf(void)
+ configure_pcie_block(g_m2s_serdes_0_config, SERDES_0_CFG_NB_OF_PAIRS, 0u);
+ configure_pcie_block(g_m2s_serdes_1_config, SERDES_1_CFG_NB_OF_PAIRS, 1u);
+ configure_pcie_block(g_m2s_serdes_2_config, SERDES_2_CFG_NB_OF_PAIRS, 2u);
+ configure_pcie_block(g_m2s_serdes_3_config, SERDES_3_CFG_NB_OF_PAIRS, 3u);
+ Configure one individual PCIe block.
+ const uint32_t PMA_READY_MASK = 0x00000080u;
+ const uint32_t PCIE_CTRL_REG_LENGTH = 0x1000u;
+ const uint32_t PCIE_CTLR_SOFTRESET_MASK = 0x00000001;
+ const uint32_t PCIE2_CTLR_SOFTRESET_MASK = 0x00000040;
+ SERDESIF_TypeDef * const serdes_lut[4] =
+ SERDES0, SERDES1, SERDES2, SERDES3
+ const uint32_t pcie_ctrl_top_addr_lut[4] =
+ SERDES0_CFG_BASE + PCIE_CTRL_REG_LENGTH,
+ SERDES1_CFG_BASE + PCIE_CTRL_REG_LENGTH,
+ SERDES2_CFG_BASE + PCIE_CTRL_REG_LENGTH,
+ SERDES3_CFG_BASE + PCIE_CTRL_REG_LENGTH
+ * Poll for PMA_READY.
+ inc = 0U;
+ while(g_pcie_lane_cfg_lut[serdes_id][inc].config_reg_lane_sel != 0)
+ uint32_t pma_ready;
+ uint32_t config_phy_mode_1;
+ /* select lane */
+ config_phy_mode_1 = g_pcie_lane_cfg_lut[serdes_id][inc].serdes->sys_regs.CONFIG_PHY_MODE_1;
+ config_phy_mode_1 &= ~CONFIG_REG_LANE_SEL_MASK;
+ config_phy_mode_1 |= (uint32_t)g_pcie_lane_cfg_lut[serdes_id][inc].config_reg_lane_sel;
+ g_pcie_lane_cfg_lut[serdes_id][inc].serdes->sys_regs.CONFIG_PHY_MODE_1 = config_phy_mode_1;
+ /* Wait for PMA to become ready. */
+ pma_ready = g_pcie_lane_cfg_lut[serdes_id][inc].lane->PMA_STATUS & PMA_READY_MASK;
+ while (0u == pma_ready);
+ ++inc;
+ * Configure the PCIe controller registers.
+ uint32_t reg_addr;
+ reg_addr = (uint32_t)p_addr_value_pair[inc].p_reg;
+ if(reg_addr < pcie_ctrl_top_addr_lut[serdes_id])
+ * Issue a soft-reset to the PCIe controller
+ if(FIRST_PCIE_CTRL == g_pcie_lane_cfg_lut[serdes_id][inc].pcie_ctrl_id)
+ serdes_lut[serdes_id]->sys_regs.SERDESIF_SOFT_RESET &= ~PCIE_CTLR_SOFTRESET_MASK;
+ serdes_lut[serdes_id]->sys_regs.SERDESIF_SOFT_RESET |= PCIE_CTLR_SOFTRESET_MASK;
+ serdes_lut[serdes_id]->sys_regs.SERDESIF_SOFT_RESET &= ~PCIE2_CTLR_SOFTRESET_MASK;
+ serdes_lut[serdes_id]->sys_regs.SERDESIF_SOFT_RESET |= PCIE2_CTLR_SOFTRESET_MASK;
+ Retrieve silicon revision from system registers.
+static uint32_t get_silicon_revision(void)
+ uint32_t silicon_revision;
+ uint32_t device_version;
+ device_version = SYSREG->DEVICE_VERSION;
+ switch(device_version)
+ case 0x0000F802:
+ silicon_revision = M2S050_REV_A_SILICON;
+ case 0x0001F802:
+ silicon_revision = M2S050_REV_B_SILICON;
+ silicon_revision = UNKNOWN_SILICON_REV;
+ return silicon_revision;
+ Workarounds for various silicon versions.
+static void silicon_workarounds(void)
+ silicon_revision = get_silicon_revision();
+ switch(silicon_revision)
+ case M2S050_REV_A_SILICON:
+ m2s050_rev_a_workarounds();
+ case M2S050_REV_B_SILICON:
+ case UNKNOWN_SILICON_REV:
+ Silicon workarounds for M2S050 rev A.
+static void m2s050_rev_a_workarounds(void)
+ * Work around a couple of silicon issues:
+ /* DDR_CLK_EN <- 1 */
+ SYSREG->MSSDDR_FACC1_CR |= (uint32_t)1 << DDR_CLK_EN_SHIFT;
+ /* CONTROLLER_PLL_INIT <- 0 */
+ SYSREG->MSSDDR_FACC1_CR = SYSREG->MSSDDR_FACC1_CR & ~CONTROLLER_PLL_INIT_MASK;
+ Complete clock configuration if requested by Libero.
+static void complete_clock_config(void)
+ uint32_t pll_locked;
+ /* Wait for fabric PLL to lock. */
+ pll_locked = SYSREG->MSSDDR_PLL_STATUS & FAB_PLL_LOCK_MASK;
+ } while(!pll_locked);
+ /* Negate MPLL bypass. */
+ SYSREG->MSSDDR_PLL_STATUS_HIGH_CR &= ~FACC_PLL_BYPASS_MASK;
+ /* Wait for MPLL to lock. */
+ pll_locked = SYSREG->MSSDDR_PLL_STATUS & MPLL_LOCK_MASK;
+ /* Switch FACC from standby to run mode. */
+ SYSREG->MSSDDR_FACC1_CR &= ~FACC_GLMUX_SEL_MASK;
+ /* Negate FPGA_SOFTRESET to de-assert MSS_RESET_N_M2F in the fabric */
+ * SVN $Revision: 5280 $
+ * SVN $Date: 2013-03-22 20:51:50 +0000 (Fri, 22 Mar 2013) $
+#ifndef SYSTEM_M2SXXX_H
+#define SYSTEM_M2SXXX_H
+/* Standard CMSIS global variables. */
+extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
+/* SmartFusion2 specific clocks. */
+extern uint32_t g_FrequencyPCLK0; /*!< Clock frequency of APB bus 0. */
+extern uint32_t g_FrequencyPCLK1; /*!< Clock frequency of APB bus 1. */
+extern uint32_t g_FrequencyPCLK2; /*!< Clock frequency of APB bus 2. */
+extern uint32_t g_FrequencyFIC0; /*!< Clock frequecny of FPGA fabric interface controller 1. */
+extern uint32_t g_FrequencyFIC1; /*!< Clock frequecny of FPGA fabric inteface controller 2. */
+extern uint32_t g_FrequencyFIC64; /*!< Clock frequecny of 64-bit FPGA fabric interface controller. */
+ * The SystemInit() is a standard CMSIS function called during system startup.
+ * It is meant to perform low level hardware setup such as configuring DDR and
+ * SERDES controllers.
+void SystemInit(void);
+ * The SystemCoreClockUpdate() is a standard CMSIS function which can be called
+ * by the application in order to ensure that the SystemCoreClock global
+ * variable contains the up to date Cortex-M3 core frequency. Calling this
+ * function also updates the global variables containing the frequencies of the
+ * APB busses connecting the peripherals.
+void SystemCoreClockUpdate(void);
@@ -0,0 +1,26 @@
+mainmenu "RT-Thread Configuration"
+config BSP_DIR
+ string
+ option env="BSP_ROOT"
+ default "."
+config RTT_DIR
+ option env="RTT_ROOT"
+ default "../.."
+config PKGS_DIR
+ option env="PKGS_ROOT"
+ default "packages"
+source "$RTT_DIR/Kconfig"
+source "$PKGS_DIR/Kconfig"
+source "drivers/Kconfig"
+config SOC_SF2_M2S010
+ bool
+ select RT_USING_COMPONENTS_INIT
+ select RT_USING_USER_MAIN
+ default y
@@ -0,0 +1,102 @@
+## 移植RT-Thread到Microsemi SmartFusion2系列FPGA芯片
+### 1. BSP简介
+移植 RT-Thread 操作系统到一款 **FPGA 芯片——M2S010** ,该芯片属于 [Microsemi](https://www.microsemi.com/)(现Microchip)SmartFusion2系列,是一款**智能混合型FPGA**,片上除了 FPGA Fabric 逻辑部分,还包括一个 **ARM® Cortex™-M3 内核的 MCU**,主频最高 166MHz ,256KB eNVM,64KB eSRAM,集成GPIO、UART、I2C、SPI、CAN、USB等基本外设。
+> 关于 Microsemi,第三大 FPGA 厂商,原 Actel 半导体,2010 年,Microsemi 收购 Actel,2018 年, Microchip 收购 Microsemi。
+SmartFusion2 内部框图
+
+### 2. 外设支持
+移植了 RT-Thread 内核,支持线程调度、线程间同步和通信等,目前已经完成了PIN、Serial设备驱动,FinSH组件默认使用uart0设备。
+| **片上外设** | **支持情况** |
+| :----------------- | :----------: |
+| GPIO | 支持 |
+| UART | 支持 |
+| SPI | 暂不支持 |
+| I2C | 暂不支持 |
+| RTC | 暂不支持 |
+| USB | 暂不支持 |
+### 3. scons构建系统
+通过加入`rtconfig.py`,`SConstruct`,`SConscript`文件,可支持scons构建系统,可以输入`scons`调用env工具中包含的arm-gcc编译器构建工程,支持以下scons命令:
+- `scons`:使用arm-gcc编译BSP
+- `scons -c`:清除执行 scons 时生成的临时文件和目标文件。
+- `scons --target=mdk4`:重新生成Keil MDK4环境下的工程。
+- `scons --target=mdk5`:重新生成Keil MDK5环境下的工程。
+- `scons --dist`:打包BSP工程,包括RT-Thread源码及BSP相关工程文件。
+添加Kconfig文件,用于生成rtconfig.h。
+### 4. 使用说明
+#### 4.1 FPGA 工程设计
+FPGA 部分使用 SmartDesign 图形化设计,不需要写 HDL 代码,时钟来自外部 50M 晶体输入,PLL 倍频 100M 提供给 MCU 使用,顶层配置如下图所示:
+
+MSS 部分仅使用到了GPIO 和UART,GPIO_0配置成输出输出模式用于驱动LED。
+配置完成的 FPGA 工程文件下载:[sf2_fpga_prj.rar](https://wcc-blog.oss-cn-beijing.aliyuncs.com/Libero/RT-Thread/sf2_fpga_prj.rar)
+#### 4.2 ARM 程序设计
+ARM 程序使用 Keil MDK 5.26 开发,需要安装 M2S 系列芯片支持包:[Microsemi.M2Sxxx.1.0.64.pack](http://www.actel-ip.com/repositories/CMSIS-Pack/Microsemi.M2Sxxx.1.0.64.pack)
+如果官网下载失败,可以到以下地址下载:[Microsemi.M2Sxxx.1.0.64.pack](https://wcc-blog.oss-cn-beijing.aliyuncs.com/Libero/RT-Thread/Microsemi.M2Sxxx.1.0.64.pack)
+在官方生成的示例工程目录下,添加 RT-Thread 相关组件,并实现一些对接函数,最终的文件结构:
+
+### 5. 下载和运行
+为了能使用 ARM 调试器连接到 ARM 内核,而不是 FPGA,需要把 JTAG_SEL 引脚置为低电平。使用 ARM 调试器,如 JLink,对应连接 JTAG 口的 TMS、TCK、GND 引脚,如果连接正常,可以检测到 ARM 芯片,如下图所示:
+
+配置对应的 Flash 编程算法:
+
+下载完成:
+
+如果编译 & 烧写无误,下载完成或者按下复位按键之后,会在串口上看到 RT-Thread 的启动 LOG 信息:
+```c
+ \ | /
+- RT - Thread Operating System
+ / | \ 4.0.3 build Jun 2 2020
+ 2006 - 2020 Copyright by rt-thread team
+msh >
+```
+
+### 6. 注意事项
+- FPGA 开发环境基于 Libero V11.8.2.4,向上兼容,不支持低版本 IDE。
+- ARM 开发环境基于 Keil MDK 5.26,如果使用SoftConsole IDE ,需要修改 `libcpu` 内的文件。
+- 调试内部 ARM 核,需要把 JTAG_SEL 拉低,否则调试器连接不上。
+- 使用 SoftConsole 开发环境可以直接使用官方的 Flash Pro 调试器进行 ARM 程序的调试。
+- 内核时钟需要和 FPGA 中 MSS 配置的对应,Libero 自动生成的时钟文件,可以直接替换`bsp\smartfusion2\libraries\sys_config`文件夹下的文件 。
+### 7. 参考资料
+- [学习路线 - RT-Thread 文档中心](https://www.rt-thread.org/document/site/)
+- [Microsemi Libero系列中文教程](https://blog.csdn.net/whik1194/article/details/102901710)
+### 8. 联系我
+- Github:[whik](https://github.com/whik)
+- E-Mail:wangchao149@foxmail.com
@@ -0,0 +1,15 @@
+# for module compiling
+import os
+Import('RTT_ROOT')
+objs = []
+list = os.listdir(cwd)
+for d in list:
+ path = os.path.join(cwd, d)
+ if os.path.isfile(os.path.join(path, 'SConscript')):
+ objs = objs + SConscript(os.path.join(d, 'SConscript'))
+Return('objs')
@@ -0,0 +1,35 @@
+import sys
+if os.getenv('RTT_ROOT'):
+ RTT_ROOT = os.getenv('RTT_ROOT')
+else:
+ RTT_ROOT = os.path.normpath(os.getcwd() + '/../..')
+sys.path = sys.path + [os.path.join(RTT_ROOT, 'tools')]
+try:
+ from building import *
+except:
+ print('Cannot found RT-Thread root directory, please check RTT_ROOT')
+ print(RTT_ROOT)
+ exit(-1)
+TARGET = 'rtthread.' + rtconfig.TARGET_EXT
+DefaultEnvironment(tools=[])
+env = Environment(tools = ['mingw'],
+ AS = rtconfig.AS, ASFLAGS = rtconfig.AFLAGS,
+ CC = rtconfig.CC, CCFLAGS = rtconfig.CFLAGS,
+ AR = rtconfig.AR, ARFLAGS = '-rc',
+ LINK = rtconfig.LINK, LINKFLAGS = rtconfig.LFLAGS)
+env.PrependENVPath('PATH', rtconfig.EXEC_PATH)
+Export('RTT_ROOT')
+Export('rtconfig')
+# prepare building environment
+objs = PrepareBuilding(env, RTT_ROOT, has_libcpu=False)
+# make a building
+DoBuilding(TARGET, objs)
@@ -0,0 +1,10 @@
+group = DefineGroup('Applications', src, depend = [''], CPPPATH = CPPPATH)
@@ -0,0 +1,16 @@
+; *************************************************************
+; *** Scatter-Loading Description File generated by uVision ***
+LR_IROM1 0x00000000 0x00040000 { ; load region size_region
+ ER_IROM1 0x00000000 0x00040000 { ; load address = execution address
+ .ANY (+XO)
+ RW_IRAM1 0x20000000 0x00010000 { ; RW data
@@ -0,0 +1,32 @@
+ * 2020-08-06 whik first version
+#include <rthw.h>
+#include <rtthread.h>
+#define LED_PIN 0
+int main(void)
+ int count = 1;
+ rt_pin_mode(LED_PIN, PIN_MODE_OUTPUT);
+ while(count++)
+ rt_pin_write(LED_PIN, PIN_HIGH);
+ rt_thread_mdelay(500);
+ rt_pin_write(LED_PIN, PIN_LOW);
@@ -0,0 +1,86 @@
+#define _SCB_BASE (0xE000E010UL)
+#define _SYSTICK_CTRL (*(rt_uint32_t *)(_SCB_BASE + 0x0))
+#define _SYSTICK_LOAD (*(rt_uint32_t *)(_SCB_BASE + 0x4))
+#define _SYSTICK_VAL (*(rt_uint32_t *)(_SCB_BASE + 0x8))
+#define _SYSTICK_CALIB (*(rt_uint32_t *)(_SCB_BASE + 0xC))
+#define _SYSTICK_PRI (*(rt_uint8_t *)(0xE000ED23UL))
+extern void SystemCoreClockUpdate(void);
+extern uint32_t SystemCoreClock;
+static uint32_t _SysTick_Config(rt_uint32_t ticks)
+ if ((ticks - 1) > 0xFFFFFF)
+ return 1;
+ _SYSTICK_LOAD = ticks - 1;
+ _SYSTICK_PRI = 0xFF;
+ _SYSTICK_VAL = 0;
+ _SYSTICK_CTRL = 0x07;
+ return 0;
+#if defined(RT_USING_USER_MAIN) && defined(RT_USING_HEAP)
+#define RT_HEAP_SIZE 1024
+static uint32_t rt_heap[RT_HEAP_SIZE]; // heap default size: 4K(1024 * 4)
+RT_WEAK void *rt_heap_begin_get(void)
+ return rt_heap;
+RT_WEAK void *rt_heap_end_get(void)
+ return rt_heap + RT_HEAP_SIZE;
+/* This function will initial your board. */
+void rt_hw_board_init()
+ /* System Clock Update */
+ SystemCoreClockUpdate();
+ /* System Tick Configuration */
+ _SysTick_Config(SystemCoreClock / RT_TICK_PER_SECOND);
+ /* Call components board initial (use INIT_BOARD_EXPORT()) */
+#ifdef RT_USING_COMPONENTS_INIT
+ rt_components_board_init();
+#ifdef RT_USING_CONSOLE
+ rt_console_set_device(RT_CONSOLE_DEVICE_NAME);
+ rt_system_heap_init(rt_heap_begin_get(), rt_heap_end_get());
+void SysTick_Handler(void)
+ /* enter interrupt */
+ rt_interrupt_enter();
+ rt_tick_increase();
+ /* leave interrupt */
+ rt_interrupt_leave();
@@ -0,0 +1,27 @@
+#include "config.h"
+/* hardware initialization */
+void boardInit(void)
+ /* disable watchdog timer */
+ SYSREG->WDOG_CR = 0;
+INIT_BOARD_EXPORT(boardInit);
+/* custom finish command */
+void sayHello(void)
+ rt_kprintf("Hello RT-Thread! By Microsemi SmartFusion2 Family FPGA-M2S010.\r\n");
+ rt_kprintf("MSS System Core Clock: %d Hz.\r\n", SystemCoreClock);
+MSH_CMD_EXPORT(sayHello, "say hello to console");
@@ -0,0 +1,24 @@
+#ifndef __CONFIG_H__
+#define __CONFIG_H__
+#include "mss_gpio.h"
+void sw0_isr(void *args);
+void sw1_isr(void *args);
+void boardInit(void);
+void sayHello(void);
+menu "Hardware Drivers Config"
+ menu "On-chip Peripheral Drivers"
+ menu "UART Drivers"
+ bool "Enable MSS_UART0"
+ select RT_USING_SERIAL
+ config MSS_UART0
+ config BSP_USING_UART1
+ bool "Enable MSS_UART1"
+ config MSS_UART1
+ config RT_CONSOLE_DEVICE_NAME
+ string "the device name for console"
+ default "uart0"
+ endmenu
+ menu "GPIO Drivers"
+ config BSP_USING_GPIO
+ bool "Enable MSS_GPIO"
+ select RT_USING_PIN
+ config MSS_GPIO
+endmenu
+src = []
+# add serial driver code
+if GetDepend('BSP_USING_UART0') or GetDepend('BSP_USING_UART1'):
+if GetDepend('BSP_USING_GPIO'):
+ src += ['drv_gpio.c']
+group = DefineGroup('Drivers', src, depend = [''], CPPPATH = CPPPATH)
@@ -0,0 +1,442 @@
+ * 2020-07-09 whik first version
+#include "drv_gpio.h"
+#ifdef BSP_USING_GPIO
+static struct rt_pin_irq_hdr sf2_pin_irq_hdr_tab[] =
+ /* pin, hdr, mode, args */
+ {-1, 0, RT_NULL, RT_NULL},
+/* configure an individual GPIO port */
+static void sf2_pin_mode(rt_device_t dev, rt_base_t pin, rt_base_t mode)
+ uint32_t config;
+ switch (mode)
+ case PIN_MODE_OUTPUT:
+ config = MSS_GPIO_OUTPUT_MODE;
+ case PIN_MODE_INPUT:
+ config = MSS_GPIO_INPUT_MODE;
+ config = MSS_GPIO_INOUT_MODE;
+ MSS_GPIO_config((mss_gpio_id_t )pin, config);
+static int sf2_pin_read(rt_device_t dev, rt_base_t pin)
+ value = MSS_GPIO_get_inputs() & (1<<pin);
+ return ((value) ? PIN_HIGH : PIN_LOW);
+static void sf2_pin_write(rt_device_t dev, rt_base_t pin, rt_base_t value)
+ if (value == PIN_HIGH)
+ MSS_GPIO_set_output((mss_gpio_id_t )pin, 1);
+ MSS_GPIO_set_output((mss_gpio_id_t )pin, 0);
+static rt_err_t sf2_pin_attach_irq(struct rt_device *device, rt_int32_t pin,
+ rt_uint32_t mode, void (*hdr)(void *args), void *args)
+ rt_base_t level;
+ level = rt_hw_interrupt_disable();
+ if (sf2_pin_irq_hdr_tab[pin].pin == pin &&
+ sf2_pin_irq_hdr_tab[pin].hdr == hdr &&
+ sf2_pin_irq_hdr_tab[pin].mode == mode &&
+ sf2_pin_irq_hdr_tab[pin].args == args)
+ rt_hw_interrupt_enable(level);
+ if (sf2_pin_irq_hdr_tab[pin].pin != -1)
+ return -RT_EBUSY;
+ sf2_pin_irq_hdr_tab[pin].pin = pin;
+ sf2_pin_irq_hdr_tab[pin].hdr = hdr;
+ sf2_pin_irq_hdr_tab[pin].mode = mode;
+ sf2_pin_irq_hdr_tab[pin].args = args;
+static rt_err_t sf2_pin_detach_irq(struct rt_device *device, rt_int32_t pin)
+ if (sf2_pin_irq_hdr_tab[pin].pin == -1)
+ sf2_pin_irq_hdr_tab[pin].pin = -1;
+ sf2_pin_irq_hdr_tab[pin].hdr = RT_NULL;
+ sf2_pin_irq_hdr_tab[pin].mode = 0;
+ sf2_pin_irq_hdr_tab[pin].args = RT_NULL;
+static rt_err_t sf2_pin_irq_enable(struct rt_device *device, rt_base_t pin, rt_uint32_t enabled)
+ uint32_t mode = 0;
+ if (enabled == PIN_IRQ_ENABLE)
+ return -RT_ENOSYS;
+ switch(sf2_pin_irq_hdr_tab[pin].mode)
+ case PIN_IRQ_MODE_RISING :
+ mode = MSS_GPIO_IRQ_EDGE_POSITIVE;
+ case PIN_IRQ_MODE_FALLING :
+ mode = MSS_GPIO_IRQ_EDGE_NEGATIVE;
+ case PIN_IRQ_MODE_RISING_FALLING:
+ mode = MSS_GPIO_IRQ_EDGE_BOTH;
+ case PIN_IRQ_MODE_HIGH_LEVEL :
+ mode = MSS_GPIO_IRQ_LEVEL_HIGH;
+ case PIN_IRQ_MODE_LOW_LEVEL:
+ mode = MSS_GPIO_IRQ_LEVEL_LOW;
+ MSS_GPIO_config((mss_gpio_id_t )pin, MSS_GPIO_INPUT_MODE | mode);
+ MSS_GPIO_enable_irq((mss_gpio_id_t )pin);
+ else if (enabled == PIN_IRQ_DISABLE)
+ MSS_GPIO_config((mss_gpio_id_t )pin, MSS_GPIO_INPUT_MODE);
+ MSS_GPIO_disable_irq((mss_gpio_id_t )pin);
+static const struct rt_pin_ops sf2_pin_ops =
+ sf2_pin_mode,
+ sf2_pin_write,
+ sf2_pin_read,
+ sf2_pin_attach_irq,
+ sf2_pin_detach_irq,
+ sf2_pin_irq_enable
+int rt_hw_pin_init(void)
+ rt_err_t result = RT_EOK;
+ MSS_GPIO_init();
+ result = rt_device_pin_register("pin", &sf2_pin_ops, RT_NULL);
+ RT_ASSERT(result == RT_EOK);
+ return result;
+INIT_BOARD_EXPORT(rt_hw_pin_init);
+rt_inline void pin_irq_hdr(int pin)
+ MSS_GPIO_clear_irq((mss_gpio_id_t )pin);
+ if (sf2_pin_irq_hdr_tab[pin].hdr)
+ sf2_pin_irq_hdr_tab[pin].hdr(sf2_pin_irq_hdr_tab[pin].args);
+void GPIO0_IRQHandler( void )
+ pin_irq_hdr(0);
+void GPIO1_IRQHandler( void )
+ pin_irq_hdr(1);
+void GPIO2_IRQHandler( void )
+ pin_irq_hdr(2);
+void GPIO3_IRQHandler( void )
+ pin_irq_hdr(3);
+void GPIO4_IRQHandler( void )
+ pin_irq_hdr(4);
+void GPIO5_IRQHandler( void )
+ pin_irq_hdr(5);
+void GPIO6_IRQHandler( void )
+ pin_irq_hdr(6);
+void GPIO7_IRQHandler( void )
+ pin_irq_hdr(7);
+void GPIO8_IRQHandler( void )
+ pin_irq_hdr(8);
+void GPIO9_IRQHandler( void )
+ pin_irq_hdr(9);
+void GPIO10_IRQHandler( void )
+ pin_irq_hdr(10);
+void GPIO11_IRQHandler( void )
+ pin_irq_hdr(11);
+void GPIO12_IRQHandler( void )
+ pin_irq_hdr(12);
+void GPIO13_IRQHandler( void )
+ pin_irq_hdr(13);
+void GPIO14_IRQHandler( void )
+ pin_irq_hdr(14);
+void GPIO15_IRQHandler( void )
+ pin_irq_hdr(15);
+void GPIO16_IRQHandler( void )
+ pin_irq_hdr(16);
+void GPIO17_IRQHandler( void )
+ pin_irq_hdr(17);
+void GPIO18_IRQHandler( void )
+ pin_irq_hdr(18);
+void GPIO19_IRQHandler( void )
+ pin_irq_hdr(19);
+void GPIO20_IRQHandler( void )
+ pin_irq_hdr(20);
+void GPIO21_IRQHandler( void )
+ pin_irq_hdr(21);
+void GPIO22_IRQHandler( void )
+ pin_irq_hdr(22);
+void GPIO23_IRQHandler( void )
+ pin_irq_hdr(23);
+void GPIO24_IRQHandler( void )
+ pin_irq_hdr(24);
+void GPIO25_IRQHandler( void )
+ pin_irq_hdr(25);
+void GPIO26_IRQHandler( void )
+ pin_irq_hdr(26);
+void GPIO27_IRQHandler( void )
+ pin_irq_hdr(27);
+void GPIO28_IRQHandler( void )
+ pin_irq_hdr(28);
+void GPIO29_IRQHandler( void )
+ pin_irq_hdr(29);
+void GPIO30_IRQHandler( void )
+ pin_irq_hdr(30);
+void GPIO31_IRQHandler( void )
+ pin_irq_hdr(31);
@@ -0,0 +1,19 @@
+#ifndef __DRV_GPIO_H__
+#define __DRV_GPIO_H__
+int rt_hw_pin_init(void);
@@ -0,0 +1,189 @@
+struct sf2_uart
+ mss_uart_instance_t *uart;
+ IRQn_Type irq;
+struct sf2_uart uart0=
+ &g_mss_uart0,
+ UART0_IRQn,
+struct rt_serial_device serial0;
+void uart0_rx_handler(mss_uart_instance_t *this_uart)
+ rt_hw_serial_isr(&serial0, RT_SERIAL_EVENT_RX_IND);
+struct sf2_uart uart1=
+ &g_mss_uart1,
+ UART1_IRQn,
+struct rt_serial_device serial1;
+void uart1_rx_handler(mss_uart_instance_t *this_uart)
+ rt_hw_serial_isr(&serial1, RT_SERIAL_EVENT_RX_IND);
+static rt_err_t sf2_uart_configure(struct rt_serial_device *serial,
+ struct serial_configure *cfg)
+ uint32_t baudRate;
+ uint8_t datBits, parity, stopBits;
+ uint8_t config;
+ struct sf2_uart *uart;
+ uart = (struct sf2_uart *)serial->parent.user_data;
+ switch(cfg->data_bits)
+ case DATA_BITS_5: datBits = MSS_UART_DATA_5_BITS; break;
+ case DATA_BITS_6: datBits = MSS_UART_DATA_6_BITS; break;
+ case DATA_BITS_7: datBits = MSS_UART_DATA_7_BITS; break;
+ case DATA_BITS_8: datBits = MSS_UART_DATA_8_BITS; break;
+ default: datBits = MSS_UART_DATA_8_BITS; break;
+ switch(cfg->parity)
+ case PARITY_NONE: parity = MSS_UART_NO_PARITY; break;
+ case PARITY_EVEN: parity = MSS_UART_EVEN_PARITY; break;
+ case PARITY_ODD : parity = MSS_UART_ODD_PARITY; break;
+ default : parity = MSS_UART_NO_PARITY; break;
+ switch(cfg->stop_bits)
+ case STOP_BITS_1: stopBits = MSS_UART_ONE_STOP_BIT; break;
+ case STOP_BITS_2: stopBits = MSS_UART_TWO_STOP_BITS; break;
+ case STOP_BITS_3: stopBits = MSS_UART_ONEHALF_STOP_BIT; break;
+ default : stopBits = MSS_UART_ONE_STOP_BIT;
+ baudRate = cfg->baud_rate;
+ config = datBits | parity | stopBits;
+ MSS_UART_init(uart->uart, baudRate, config);
+ if(uart->uart == &g_mss_uart0)
+ MSS_UART_set_rx_handler(uart->uart, uart0_rx_handler, MSS_UART_FIFO_SINGLE_BYTE);
+ MSS_UART_set_rx_handler(uart->uart, uart1_rx_handler, MSS_UART_FIFO_SINGLE_BYTE);
+static rt_err_t sf2_uart_control(struct rt_serial_device *serial,
+ int cmd, void *arg)
+ struct sf2_uart* uart;
+ uart = (struct sf2_uart*)serial->parent.user_data;
+ NVIC_DisableIRQ(uart->irq);
+ NVIC_EnableIRQ(uart->irq);
+static int sf2_uart_putc(struct rt_serial_device *serial, char c)
+ tx_ready = uart->uart->hw_reg->LSR & 0x20u;
+ uart->uart->hw_reg->THR = c;
+static int sf2_uart_getc(struct rt_serial_device *serial)
+ uint8_t err_status;
+ err_status = MSS_UART_get_rx_status(uart->uart);
+ if(MSS_UART_NO_ERROR == err_status)
+ MSS_UART_get_rx(uart->uart, (uint8_t *)&ch, 1);
+static const struct rt_uart_ops sf2_uart_ops =
+ sf2_uart_configure,
+ sf2_uart_control,
+ sf2_uart_putc,
+ sf2_uart_getc,
+int rt_hw_uart_init(void)
+ uart = &uart0;
+ serial0.ops = &sf2_uart_ops;
+ /* default config: 115200, 8, no, 1 */
+ serial0.config = config;
+ result = rt_hw_serial_register(&serial0, "uart0", RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, uart);
+ uart = &uart1;
+ serial1.ops = &sf2_uart_ops;
+ serial1.config = config;
+ result = rt_hw_serial_register(&serial1, "uart1", RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, uart);
+INIT_BOARD_EXPORT(rt_hw_uart_init);
@@ -0,0 +1,20 @@
+void uart_rx_handler(mss_uart_instance_t *this_uart);
+void uart0_rx_handler(mss_uart_instance_t * this_uart);
+void uart1_rx_handler(mss_uart_instance_t * this_uart);
+int rt_hw_uart_init(void);
+src = [cwd + '/sys_config/sys_config.c']
+src += [cwd + '/mss_gpio/mss_gpio.c']
+src += [cwd + '/mss_uart/mss_uart.c']
+CPPPATH = [cwd+'/sys_config']
+CPPPATH += [cwd+'/mss_gpio']
+CPPPATH += [cwd+'/mss_uart']
+group = DefineGroup('Libraries', src, depend = [''], CPPPATH = CPPPATH)
@@ -0,0 +1,298 @@
+ * (c) Copyright 2008-2015 Microsemi SoC Products Group. All rights reserved.
+ * SmartFusion2 microcontroller subsystem GPIO bare metal driver implementation.
+ * SVN $Revision: 7749 $
+ * SVN $Date: 2015-09-04 14:32:09 +0530 (Fri, 04 Sep 2015) $
+#include "../../CMSIS/mss_assert.h"
+ * Defines.
+#define GPIO_INT_ENABLE_MASK ((uint32_t)0x00000008uL)
+#define OUTPUT_BUFFER_ENABLE_MASK 0x00000004u
+#define NB_OF_GPIO ((uint32_t)32)
+ * Lookup table of GPIO configuration registers address indexed on GPIO ID.
+static uint32_t volatile * const g_config_reg_lut[NB_OF_GPIO] =
+ &(GPIO->GPIO_0_CFG),
+ &(GPIO->GPIO_1_CFG),
+ &(GPIO->GPIO_2_CFG),
+ &(GPIO->GPIO_3_CFG),
+ &(GPIO->GPIO_4_CFG),
+ &(GPIO->GPIO_5_CFG),
+ &(GPIO->GPIO_6_CFG),
+ &(GPIO->GPIO_7_CFG),
+ &(GPIO->GPIO_8_CFG),
+ &(GPIO->GPIO_9_CFG),
+ &(GPIO->GPIO_10_CFG),
+ &(GPIO->GPIO_11_CFG),
+ &(GPIO->GPIO_12_CFG),
+ &(GPIO->GPIO_13_CFG),
+ &(GPIO->GPIO_14_CFG),
+ &(GPIO->GPIO_15_CFG),
+ &(GPIO->GPIO_16_CFG),
+ &(GPIO->GPIO_17_CFG),
+ &(GPIO->GPIO_18_CFG),
+ &(GPIO->GPIO_19_CFG),
+ &(GPIO->GPIO_20_CFG),
+ &(GPIO->GPIO_21_CFG),
+ &(GPIO->GPIO_22_CFG),
+ &(GPIO->GPIO_23_CFG),
+ &(GPIO->GPIO_24_CFG),
+ &(GPIO->GPIO_25_CFG),
+ &(GPIO->GPIO_26_CFG),
+ &(GPIO->GPIO_27_CFG),
+ &(GPIO->GPIO_28_CFG),
+ &(GPIO->GPIO_29_CFG),
+ &(GPIO->GPIO_30_CFG),
+ &(GPIO->GPIO_31_CFG)
+ * Lookup table of Cortex-M3 GPIO interrupt number indexed on GPIO ID.
+static const IRQn_Type g_gpio_irqn_lut[NB_OF_GPIO] =
+ GPIO0_IRQn,
+ GPIO1_IRQn,
+ GPIO2_IRQn,
+ GPIO3_IRQn,
+ GPIO4_IRQn,
+ GPIO5_IRQn,
+ GPIO6_IRQn,
+ GPIO7_IRQn,
+ GPIO8_IRQn,
+ GPIO9_IRQn,
+ GPIO10_IRQn,
+ GPIO11_IRQn,
+ GPIO12_IRQn,
+ GPIO13_IRQn,
+ GPIO14_IRQn,
+ GPIO15_IRQn,
+ GPIO16_IRQn,
+ GPIO17_IRQn,
+ GPIO18_IRQn,
+ GPIO19_IRQn,
+ GPIO20_IRQn,
+ GPIO21_IRQn,
+ GPIO22_IRQn,
+ GPIO23_IRQn,
+ GPIO24_IRQn,
+ GPIO25_IRQn,
+ GPIO26_IRQn,
+ GPIO27_IRQn,
+ GPIO28_IRQn,
+ GPIO29_IRQn,
+ GPIO30_IRQn,
+ GPIO31_IRQn
+ * MSS_GPIO_init
+ * See "mss_gpio.h" for details of how to use this function.
+void MSS_GPIO_init( void )
+ /* reset MSS GPIO hardware */
+ SYSREG->SOFT_RST_CR |= SYSREG_GPIO_SOFTRESET_MASK;
+ SYSREG->SOFT_RST_CR |= (SYSREG_GPIO_7_0_SOFTRESET_MASK |
+ SYSREG_GPIO_15_8_SOFTRESET_MASK |
+ SYSREG_GPIO_23_16_SOFTRESET_MASK |
+ SYSREG_GPIO_31_24_SOFTRESET_MASK);
+ /* Clear any previously pended MSS GPIO interrupt */
+ for(inc = 0U; inc < NB_OF_GPIO; ++inc)
+ NVIC_DisableIRQ(g_gpio_irqn_lut[inc]);
+ NVIC_ClearPendingIRQ(g_gpio_irqn_lut[inc]);
+ /* Take MSS GPIO hardware out of reset. */
+ SYSREG->SOFT_RST_CR &= ~(SYSREG_GPIO_7_0_SOFTRESET_MASK |
+ SYSREG->SOFT_RST_CR &= ~SYSREG_GPIO_SOFTRESET_MASK;
+ * MSS_GPIO_config
+void MSS_GPIO_config
+ mss_gpio_id_t port_id,
+ uint32_t config
+ uint32_t gpio_idx = (uint32_t)port_id;
+ ASSERT(gpio_idx < NB_OF_GPIO);
+ if(gpio_idx < NB_OF_GPIO)
+ *(g_config_reg_lut[gpio_idx]) = config;
+ * MSS_GPIO_set_output
+void MSS_GPIO_set_output
+ uint8_t value
+ uint32_t gpio_setting;
+ gpio_setting = GPIO->GPIO_OUT;
+ gpio_setting &= ~((uint32_t)0x01u << gpio_idx);
+ gpio_setting |= ((uint32_t)value & 0x01u) << gpio_idx;
+ GPIO->GPIO_OUT = gpio_setting;
+ * MSS_GPIO_drive_inout
+void MSS_GPIO_drive_inout
+ mss_gpio_inout_state_t inout_state
+ uint32_t outputs_state;
+ switch(inout_state)
+ case MSS_GPIO_DRIVE_HIGH:
+ /* Set output high */
+ outputs_state = GPIO->GPIO_OUT;
+ outputs_state |= (uint32_t)1 << gpio_idx;
+ GPIO->GPIO_OUT = outputs_state;
+ /* Enable output buffer */
+ config = *(g_config_reg_lut[gpio_idx]);
+ config |= OUTPUT_BUFFER_ENABLE_MASK;
+ case MSS_GPIO_DRIVE_LOW:
+ /* Set output low */
+ outputs_state &= ~((uint32_t)((uint32_t)1 << gpio_idx));
+ case MSS_GPIO_HIGH_Z:
+ /* Disable output buffer */
+ config &= ~OUTPUT_BUFFER_ENABLE_MASK;
+ ASSERT(0);
+ * MSS_GPIO_enable_irq
+void MSS_GPIO_enable_irq
+ mss_gpio_id_t port_id
+ uint32_t cfg_value;
+ cfg_value = *(g_config_reg_lut[gpio_idx]);
+ *(g_config_reg_lut[gpio_idx]) = (cfg_value | GPIO_INT_ENABLE_MASK);
+ NVIC_EnableIRQ(g_gpio_irqn_lut[gpio_idx]);
+ * MSS_GPIO_disable_irq
+void MSS_GPIO_disable_irq
+ *(g_config_reg_lut[gpio_idx]) = (cfg_value & ~GPIO_INT_ENABLE_MASK);
+ * MSS_GPIO_clear_irq
+void MSS_GPIO_clear_irq
+ GPIO->GPIO_IRQ = ((uint32_t)1) << gpio_idx;
+ __ASM volatile ("dsb");
@@ -0,0 +1,507 @@
+ * SmartFusion2 Microcontroller Subsystem GPIO bare metal software driver public
+ * API.
+ * SVN $Revision: 7748 $
+ * SVN $Date: 2015-09-04 11:36:30 +0530 (Fri, 04 Sep 2015) $
+/*=========================================================================*//**
+ @mainpage SmartFusion2 MSS GPIO Bare Metal Driver.
+ @section intro_sec Introduction
+ The SmartFusion2 Microcontroller Subsystem (MSS) includes a block of 32 general
+ purpose input/outputs (GPIO).
+ This software driver provides a set of functions for controlling the MSS GPIO
+ block as part of a bare metal system where no operating system is available.
+ This driver can be adapted for use as part of an operating system but the
+ implementation of the adaptation layer between this driver and the operating
+ system's driver model is outside the scope of this driver.
+ @section hw_dependencies Hardware Flow Dependencies
+ The configuration of all features of the MSS GPIOs is covered by this driver
+ with the exception of the SmartFusion2 IOMUX configuration. SmartFusion2
+ allows multiple non-concurrent uses of some external pins through IOMUX
+ configuration. This feature allows optimization of external pin usage by
+ assigning external pins for use by either the microcontroller subsystem or the
+ FPGA fabric. The MSS GPIOs share SmartFusion2 device external pins with the
+ FPGA fabric and with other MSS peripherals via an IOMUX. The MSS GPIO ports
+ can alternatively be routed to the FPGA fabric through an IOMUX.
+ The IOMUXs are configured using the SmartFusion2 MSS configurator tool. You
+ must ensure that the MSS GPIOs are enabled and configured in the SmartFusion2
+ MSS configurator if you wish to use them. For more information on IOMUXs,
+ refer to the IOMUX section of the SmartFusion2 Microcontroller Subsystem (MSS)
+ User’s Guide.
+ The base address, register addresses and interrupt number assignment for the
+ MSS GPIO block are defined as constants in the SmartFusion2 CMSIS HAL. You
+ must ensure that the latest SmartFusion2 CMSIS HAL is included in the project
+ settings of the software tool chain used to build your project and that it is
+ generated into your project.
+ @section theory_op Theory of Operation
+ The MSS GPIO driver functions are grouped into the following categories:
+ - Initialization
+ - Configuration
+ - Reading and setting GPIO state
+ - Interrupt control
+ Initialization
+ The MSS GPIO driver is initialized through a call to the MSS_GPIO_init()
+ function. The MSS_GPIO_init() function must be called before any other MSS
+ GPIO driver functions can be called.
+ Configuration
+ Each GPIO port is individually configured through a call to the
+ MSS_GPIO_config() function. Configuration includes deciding if a GPIO port
+ will be used as an input, an output or both. GPIO ports configured as inputs
+ can be further configured to generate interrupts based on the input's state.
+ Interrupts can be level or edge sensitive.
+ Reading and Setting GPIO State
+ The state of the GPIO ports can be read and set using the following functions:
+ - MSS_GPIO_get_inputs()
+ - MSS_GPIO_get_outputs()
+ - MSS_GPIO_set_outputs()
+ - MSS_GPIO_set_output()
+ - MSS_GPIO_drive_inout()
+ Interrupt Control
+ Interrupts generated by GPIO ports configured as inputs are controlled using
+ the following functions:
+ - MSS_GPIO_enable_irq()
+ - MSS_GPIO_disable_irq()
+ - MSS_GPIO_clear_irq()
+ *//*=========================================================================*/
+#ifndef MSS_GPIO_H_
+#define MSS_GPIO_H_
+#include "../../CMSIS/m2sxxx.h"
+ The mss_gpio_id_t enumeration is used to identify individual GPIO ports as an
+ argument to functions:
+ - MSS_GPIO_config()
+ - MSS_GPIO_set_output() and MSS_GPIO_drive_inout()
+ - MSS_GPIO_enable_irq(), MSS_GPIO_disable_irq() and MSS_GPIO_clear_irq()
+typedef enum __mss_gpio_id_t
+ MSS_GPIO_0 = 0,
+ MSS_GPIO_1 = 1,
+ MSS_GPIO_2 = 2,
+ MSS_GPIO_3 = 3,
+ MSS_GPIO_4 = 4,
+ MSS_GPIO_5 = 5,
+ MSS_GPIO_6 = 6,
+ MSS_GPIO_7 = 7,
+ MSS_GPIO_8 = 8,
+ MSS_GPIO_9 = 9,
+ MSS_GPIO_10 = 10,
+ MSS_GPIO_11 = 11,
+ MSS_GPIO_12 = 12,
+ MSS_GPIO_13 = 13,
+ MSS_GPIO_14 = 14,
+ MSS_GPIO_15 = 15,
+ MSS_GPIO_16 = 16,
+ MSS_GPIO_17 = 17,
+ MSS_GPIO_18 = 18,
+ MSS_GPIO_19 = 19,
+ MSS_GPIO_20 = 20,
+ MSS_GPIO_21 = 21,
+ MSS_GPIO_22 = 22,
+ MSS_GPIO_23 = 23,
+ MSS_GPIO_24 = 24,
+ MSS_GPIO_25 = 25,
+ MSS_GPIO_26 = 26,
+ MSS_GPIO_27 = 27,
+ MSS_GPIO_28 = 28,
+ MSS_GPIO_29 = 29,
+ MSS_GPIO_30 = 30,
+ MSS_GPIO_31 = 31
+} mss_gpio_id_t;
+ These constant definitions are used as an argument to the
+ MSS_GPIO_set_outputs() function to identify GPIO ports. A logical OR of these
+ constants can be used to specify multiple GPIO ports.
+ These definitions can also be used to identify GPIO ports through logical
+ operations on the return value of the MSS_GPIO_get_inputs() function.
+#define MSS_GPIO_0_MASK 0x00000001uL
+#define MSS_GPIO_1_MASK 0x00000002uL
+#define MSS_GPIO_2_MASK 0x00000004uL
+#define MSS_GPIO_3_MASK 0x00000008uL
+#define MSS_GPIO_4_MASK 0x00000010uL
+#define MSS_GPIO_5_MASK 0x00000020uL
+#define MSS_GPIO_6_MASK 0x00000040uL
+#define MSS_GPIO_7_MASK 0x00000080uL
+#define MSS_GPIO_8_MASK 0x00000100uL
+#define MSS_GPIO_9_MASK 0x00000200uL
+#define MSS_GPIO_10_MASK 0x00000400uL
+#define MSS_GPIO_11_MASK 0x00000800uL
+#define MSS_GPIO_12_MASK 0x00001000uL
+#define MSS_GPIO_13_MASK 0x00002000uL
+#define MSS_GPIO_14_MASK 0x00004000uL
+#define MSS_GPIO_15_MASK 0x00008000uL
+#define MSS_GPIO_16_MASK 0x00010000uL
+#define MSS_GPIO_17_MASK 0x00020000uL
+#define MSS_GPIO_18_MASK 0x00040000uL
+#define MSS_GPIO_19_MASK 0x00080000uL
+#define MSS_GPIO_20_MASK 0x00100000uL
+#define MSS_GPIO_21_MASK 0x00200000uL
+#define MSS_GPIO_22_MASK 0x00400000uL
+#define MSS_GPIO_23_MASK 0x00800000uL
+#define MSS_GPIO_24_MASK 0x01000000uL
+#define MSS_GPIO_25_MASK 0x02000000uL
+#define MSS_GPIO_26_MASK 0x04000000uL
+#define MSS_GPIO_27_MASK 0x08000000uL
+#define MSS_GPIO_28_MASK 0x10000000uL
+#define MSS_GPIO_29_MASK 0x20000000uL
+#define MSS_GPIO_30_MASK 0x40000000uL
+#define MSS_GPIO_31_MASK 0x80000000uL
+ These constant definitions are used as an argument to the MSS_GPIO_config()
+ function to specify the I/O mode of each GPIO port.
+#define MSS_GPIO_INPUT_MODE 0x0000000002uL
+#define MSS_GPIO_OUTPUT_MODE 0x0000000005uL
+#define MSS_GPIO_INOUT_MODE 0x0000000003uL
+ function to specify the interrupt mode of each GPIO port.
+#define MSS_GPIO_IRQ_LEVEL_HIGH 0x0000000000uL
+#define MSS_GPIO_IRQ_LEVEL_LOW 0x0000000020uL
+#define MSS_GPIO_IRQ_EDGE_POSITIVE 0x0000000040uL
+#define MSS_GPIO_IRQ_EDGE_NEGATIVE 0x0000000060uL
+#define MSS_GPIO_IRQ_EDGE_BOTH 0x0000000080uL
+ The mss_gpio_inout_state_t enumeration is used to specify the output state of
+ an INOUT GPIO port as an argument to the MSS_GPIO_drive_inout() function.
+typedef enum mss_gpio_inout_state
+ MSS_GPIO_DRIVE_LOW = 0,
+ MSS_GPIO_DRIVE_HIGH,
+ MSS_GPIO_HIGH_Z
+} mss_gpio_inout_state_t;
+ The MSS_GPIO_init() function initializes the SmartFusion2 MSS GPIO block. It
+ resets the MSS GPIO hardware block and it also clears any pending MSS GPIO
+ interrupts in the ARM Cortex-M3 interrupt controller. When the function exits,
+ it takes the MSS GPIO block out of reset.
+ @param
+ This function has no parameters.
+ @return
+ This function does not return a value.
+void MSS_GPIO_init( void );
+ The MSS_GPIO_config() function is used to configure an individual GPIO port.
+ @param port_id
+ The port_id parameter identifies the GPIO port to be configured. An
+ enumeration item of the form MSS_GPIO_n, where n is the number of the GPIO
+ port, is used to identify the GPIO port. For example, MSS_GPIO_0 identifies
+ the first GPIO port and MSS_GPIO_31 is the last one.
+ @param config
+ The config parameter specifies the configuration to be applied to the GPIO
+ port identified by the port_id parameter. It is a logical OR of the required
+ I/O mode and the required interrupt mode. The interrupt mode is not relevant
+ if the GPIO is configured as an output only.
+ These I/O mode constants are allowed:
+ - MSS_GPIO_INPUT_MODE
+ - MSS_GPIO_OUTPUT_MODE
+ - MSS_GPIO_INOUT_MODE
+ These interrupt mode constants are allowed:
+ - MSS_GPIO_IRQ_LEVEL_HIGH
+ - MSS_GPIO_IRQ_LEVEL_LOW
+ - MSS_GPIO_IRQ_EDGE_POSITIVE
+ - MSS_GPIO_IRQ_EDGE_NEGATIVE
+ - MSS_GPIO_IRQ_EDGE_BOTH
+ none.
+ Example:
+ The following call will configure GPIO 4 as an input generating interrupts on
+ a Low to High transition of the input:
+ @code
+ MSS_GPIO_config( MSS_GPIO_4, MSS_GPIO_INPUT_MODE | MSS_GPIO_IRQ_EDGE_POSITIVE );
+ @endcode
+ The MSS_GPIO_set_outputs() function is used to set the state of all GPIO ports
+ configured as outputs.
+ @param value
+ The value parameter specifies the state of the GPIO ports configured as
+ outputs. It is a bit mask of the form (MSS_GPIO_n_MASK | MSS_GPIO_m_MASK)
+ where n and m are numbers identifying GPIOs. For example, (MSS_GPIO_0_MASK |
+ MSS_GPIO_1_MASK | MSS_GPIO_2_MASK ) specifies that the first, second and
+ third GPIO outputs must be set High and all other GPIO outputs set Low. The
+ driver provides 32 mask constants, MSS_GPIO_0_MASK to MSS_GPIO_31_MASK
+ inclusive, for this purpose.
+ Example 1:
+ Set GPIOs outputs 0 and 8 high and all other GPIO outputs low.
+ MSS_GPIO_set_outputs( MSS_GPIO_0_MASK | MSS_GPIO_8_MASK );
+ Example 2:
+ Set GPIOs outputs 2 and 4 low without affecting other GPIO outputs.
+ uint32_t gpio_outputs;
+ gpio_outputs = MSS_GPIO_get_outputs();
+ gpio_outputs &= ~( MSS_GPIO_2_MASK | MSS_GPIO_4_MASK );
+ MSS_GPIO_set_outputs( gpio_outputs );
+ @see MSS_GPIO_get_outputs()
+static __INLINE void
+MSS_GPIO_set_outputs
+ uint32_t value
+ GPIO->GPIO_OUT = value;
+ The MSS_GPIO_set_output() function is used to set the state of a single GPIO
+ port configured as an output.
+ Note: Using bit-band writes might be a better option than this function for
+ performance critical applications where the application code is not
+ intended to be ported to a processor other than the ARM Cortex-M3 in
+ SmartFusion2. The bit-band write equivalent to this function would be:
+ GPIO_BITBAND->GPIO_OUT[port_id] = (uint32_t)value;
+ The port_id parameter identifies the GPIO port that is to have its output
+ set. An enumeration item of the form MSS_GPIO_n, where n is the number of
+ the GPIO port, is used to identify the GPIO port. For example, MSS_GPIO_0
+ identifies the first GPIO port and MSS_GPIO_31 is the last one.
+ The value parameter specifies the desired state for the GPIO output. A value
+ of 0 will set the output Low and a value of 1 will set the output High.
+ The following call will set GPIO output 12 High, leaving all other GPIO
+ outputs unaffected:
+ _GPIO_set_output(MSS_GPIO_12, 1);
+ The MSS_GPIO_get_inputs() function is used to read the current state all GPIO
+ ports configured as inputs.
+ This function returns a 32-bit unsigned integer where each bit represents
+ the state of a GPIO input. The least significant bit represents the state of
+ GPIO input 0 and the most significant bit the state of GPIO input 31.
+ Read and assign the current state of the GPIO outputs to a variable.
+ uint32_t gpio_inputs;
+ gpio_inputs = MSS_GPIO_get_inputs();
+static __INLINE uint32_t
+MSS_GPIO_get_inputs( void )
+ return GPIO->GPIO_IN;
+ The MSS_GPIO_get_outputs() function is used to read the current state all GPIO
+ ports configured as outputs.
+ the state of a GPIO output. The least significant bit represents the state
+ of GPIO output 0 and the most significant bit the state of GPIO output 31.
+MSS_GPIO_get_outputs( void )
+ return GPIO->GPIO_OUT;
+ The MSS_GPIO_drive_inout() function is used to set the output state of a
+ single GPIO port configured as an INOUT. An INOUT GPIO can be in one of three
+ states:
+ - High
+ - Low
+ - High impedance
+ An INOUT output would typically be used where several devices can drive the
+ state of a shared signal line. The High and Low states are equivalent to the
+ High and Low states of a GPIO configured as an output. The High impedance
+ state is used to prevent the GPIO from driving its output state onto the
+ signal line, while at the same time allowing the input state of the GPIO to
+ be read.
+ The port_id parameter identifies the GPIO port for which you want to change
+ the output state. An enumeration item of the form MSS_GPIO_n, where n is the
+ number of the GPIO port, is used to identify the GPIO port. For example,
+ MSS_GPIO_0 identifies the first GPIO port and MSS_GPIO_31 is the last one.
+ @param inout_state
+ The inout_state parameter specifies the state of the GPIO port identified by
+ the port_id parameter. Allowed values of type mss_gpio_inout_state_t are as
+ follows:
+ - MSS_GPIO_DRIVE_HIGH
+ - MSS_GPIO_DRIVE_LOW
+ - MSS_GPIO_HIGH_Z (High impedance)
+ The call to MSS_GPIO_drive_inout() below will set the GPIO 7 output to the
+ high impedance state.
+ MSS_GPIO_drive_inout( MSS_GPIO_7, MSS_GPIO_HIGH_Z );
+ The MSS_GPIO_enable_irq() function is used to enable interrupt generation for
+ the specified GPIO input. Interrupts are generated based on the state of the
+ GPIO input and the interrupt mode configured for it by MSS_GPIO_config().
+ The port_id parameter identifies the GPIO port for which you want to enable
+ interrupt generation. An enumeration item of the form MSS_GPIO_n, where n is
+ the number of the GPIO port, is used to identify the GPIO port. For example,
+ The call to MSS_GPIO_enable_irq() below will allow GPIO 8 to generate
+ interrupts.
+ MSS_GPIO_enable_irq( MSS_GPIO_8 );
+ The MSS_GPIO_disable_irq() function is used to disable interrupt generation
+ for the specified GPIO input.
+ The port_id parameter identifies the GPIO port for which you want to disable
+ The call to MSS_GPIO_disable_irq() below will prevent GPIO 8 from generating
+ MSS_GPIO_disable_irq( MSS_GPIO_8 );
+ The MSS_GPIO_clear_irq() function is used to clear a pending interrupt from
+ the specified GPIO input.
+ Note: The MSS_GPIO_clear_irq() function must be called as part of any GPIO
+ interrupt service routine (ISR) in order to prevent the same interrupt
+ event retriggering a call to the GPIO ISR.
+ The port_id parameter identifies the GPIO port for which you want to clear
+ the interrupt. An enumeration item of the form MSS_GPIO_n, where n is the
+ The example below demonstrates the use of the MSS_GPIO_clear_irq() function
+ as part of the GPIO 9 interrupt service routine.
+ void GPIO9_IRQHandler( void )
+ do_interrupt_processing();
+ MSS_GPIO_clear_irq( MSS_GPIO_9 );
+#endif /* MSS_GPIO_H_ */
@@ -0,0 +1,1762 @@
+ * SmartFusion2 Microcontroller Subsystem MMUART bare metal software driver
+ * implementation.
+ * SVN $Revision: 5610 $
+ * SVN $Date: 2013-04-05 18:49:30 +0530 (Fri, 05 Apr 2013) $
+#include "mss_uart_regs.h"
+#include "../../CMSIS/hw_reg_io.h"
+#include "../../CMSIS/system_m2sxxx.h"
+ * Defines
+#define TX_COMPLETE 0u
+#define TX_FIFO_SIZE 16u
+#define FCR_TRIG_LEVEL_MASK 0xC0u
+#define IIRF_MASK 0x0Fu
+#define INVALID_INTERRUPT 0u
+#define INVALID_IRQ_HANDLER ((mss_uart_irq_handler_t) 0)
+#define NULL_HANDLER ((mss_uart_irq_handler_t) 0)
+#define MSS_UART_DATA_READY ((uint8_t) 0x01)
+#define SYNC_ASYNC_MODE_MASK (0x7u)
+ * Possible values for Interrupt Identification Register Field.
+#define IIRF_MODEM_STATUS 0x00u
+#define IIRF_THRE 0x02u
+#define IIRF_MMI 0x03u
+#define IIRF_RX_DATA 0x04u
+#define IIRF_RX_LINE_STATUS 0x06u
+#define IIRF_DATA_TIMEOUT 0x0Cu
+ * Receiver error status mask.
+#define STATUS_ERROR_MASK ( MSS_UART_OVERUN_ERROR | MSS_UART_PARITY_ERROR | \
+ MSS_UART_FRAMING_ERROR | MSS_UART_BREAK_ERROR | \
+ MSS_UART_FIFO_ERROR)
+ * Cortex-M3 interrupt handler functions implemented as part of the MSS UART
+ * driver.
+#if defined(__GNUC__)
+__attribute__((__interrupt__)) void UART0_IRQHandler(void);
+void UART0_IRQHandler(void);
+__attribute__((__interrupt__)) void UART1_IRQHandler(void);
+void UART1_IRQHandler(void);
+ * Local functions.
+static void global_init(mss_uart_instance_t * this_uart, uint32_t baud_rate,
+ uint8_t line_config);
+static void MSS_UART_isr(mss_uart_instance_t * this_uart);
+static void default_tx_handler(mss_uart_instance_t * this_uart);
+static void config_baud_divisors
+ mss_uart_instance_t * this_uart,
+ uint32_t baudrate
+ * Instance definitions
+mss_uart_instance_t g_mss_uart0;
+mss_uart_instance_t g_mss_uart1;
+ * Public Functions
+ * See mss_uart.h for details of how to use this function.
+void
+MSS_UART_init
+ mss_uart_instance_t* this_uart,
+ uint32_t baud_rate,
+ uint8_t line_config
+ /* The driver expects g_mss_uart0 and g_mss_uart1 to be the only
+ * mss_uart_instance_t instances used to identify UART0 and UART1. */
+ ASSERT((this_uart == &g_mss_uart0) || (this_uart == &g_mss_uart1));
+ /* Perform generic initialization */
+ global_init(this_uart, baud_rate, line_config);
+ /* Disable LIN mode */
+ clear_bit_reg8(&this_uart->hw_reg->MM0, ELIN);
+ /* Disable IrDA mode */
+ clear_bit_reg8(&this_uart->hw_reg->MM1, EIRD);
+ /* Disable SmartCard Mode */
+ clear_bit_reg8(&this_uart->hw_reg->MM2, EERR);
+ /* set default tx handler for automated TX using interrupt in USART mode */
+ this_uart->tx_handler = default_tx_handler;
+void MSS_UART_lin_init
+ /* Enable LIN mode */
+ set_bit_reg8(&this_uart->hw_reg->MM0, ELIN);
+MSS_UART_irda_init
+ uint8_t line_config,
+ mss_uart_rzi_polarity_t rxpol,
+ mss_uart_rzi_polarity_t txpol,
+ mss_uart_rzi_pulsewidth_t pw
+ set_bit_reg8(&this_uart->hw_reg->MM1, EIRD);
+ ((rxpol == MSS_UART_ACTIVE_LOW) ? clear_bit_reg8(&this_uart->hw_reg->MM1,EIRX) :
+ set_bit_reg8(&this_uart->hw_reg->MM1,EIRX));
+ ((txpol == MSS_UART_ACTIVE_LOW) ? clear_bit_reg8(&this_uart->hw_reg->MM1,EITX) :
+ set_bit_reg8(&this_uart->hw_reg->MM1,EITX));
+ ((pw == MSS_UART_3_BY_16) ? clear_bit_reg8(&this_uart->hw_reg->MM1,EITP) :
+ set_bit_reg8(&this_uart->hw_reg->MM1,EITP));
+MSS_UART_smartcard_init
+ /* Enable SmartCard Mode : Only when data is 8-bit and 2 stop bits*/
+ if( ( MSS_UART_DATA_8_BITS | MSS_UART_TWO_STOP_BITS) ==
+ (line_config & (MSS_UART_DATA_8_BITS | MSS_UART_TWO_STOP_BITS)))
+ set_bit_reg8(&this_uart->hw_reg->MM2, EERR);
+ /* Enable single wire half-duplex mode */
+ set_bit_reg8(&this_uart->hw_reg->MM2,ESWM);
+MSS_UART_polled_tx
+ const uint8_t * pbuff,
+ uint32_t tx_size
+ uint32_t char_idx = 0u;
+ uint32_t size_sent;
+ uint8_t status;
+ ASSERT(pbuff != ( (uint8_t *)0));
+ ASSERT(tx_size > 0u);
+ if(((this_uart == &g_mss_uart0) || (this_uart == &g_mss_uart1)) &&
+ (pbuff != ((uint8_t *)0)) && (tx_size > 0u))
+ /* Remain in this loop until the entire input buffer
+ * has been transferred to the UART.
+ /* Read the Line Status Register and update the sticky record */
+ status = this_uart->hw_reg->LSR;
+ this_uart->status |= status;
+ /* Check if TX FIFO is empty. */
+ if(status & MSS_UART_THRE)
+ uint32_t fill_size = TX_FIFO_SIZE;
+ /* Calculate the number of bytes to transmit. */
+ if(tx_size < TX_FIFO_SIZE)
+ fill_size = tx_size;
+ /* Fill the TX FIFO with the calculated the number of bytes. */
+ for(size_sent = 0u; size_sent < fill_size; ++size_sent)
+ /* Send next character in the buffer. */
+ this_uart->hw_reg->THR = pbuff[char_idx];
+ char_idx++;
+ /* Calculate the number of untransmitted bytes remaining. */
+ tx_size -= size_sent;
+ } while(tx_size);
+MSS_UART_polled_tx_string
+ const uint8_t * p_sz_string
+ uint32_t fill_size;
+ uint8_t data_byte;
+ ASSERT(p_sz_string != ((uint8_t *)0));
+ (p_sz_string != ((uint8_t *)0)))
+ /* Get the first data byte from the input buffer */
+ data_byte = p_sz_string[char_idx];
+ /* First check for the NULL terminator byte.
+ * Then remain in this loop until the entire string in the input buffer
+ while(0u != data_byte)
+ /* Wait until TX FIFO is empty. */
+ } while (0u == (status & MSS_UART_THRE));
+ /* Send bytes from the input buffer until the TX FIFO is full
+ * or we reach the NULL terminator byte.
+ fill_size = 0u;
+ while((0u != data_byte) && (fill_size < TX_FIFO_SIZE))
+ /* Send the data byte */
+ this_uart->hw_reg->THR = data_byte;
+ ++fill_size;
+ /* Get the next data byte from the input buffer */
+MSS_UART_irq_tx
+ ASSERT(pbuff != ((uint8_t *)0));
+ if((tx_size > 0u) && ( pbuff != ((uint8_t *)0)) &&
+ ((this_uart == &g_mss_uart0) || (this_uart == &g_mss_uart1)))
+ /*Initialise the transmit info for the UART instance with the arguments.*/
+ this_uart->tx_buffer = pbuff;
+ this_uart->tx_buff_size = tx_size;
+ this_uart->tx_idx = (uint16_t)0;
+ /* Clear any previously pended interrupts */
+ NVIC_ClearPendingIRQ(this_uart->irqn);
+ /* assign default handler for data transfer */
+ /* enables TX interrupt */
+ set_bit_reg8(&this_uart->hw_reg->IER,ETBEI);
+ /* Enable UART instance interrupt in Cortex-M3 NVIC. */
+ NVIC_EnableIRQ(this_uart->irqn);
+int8_t
+MSS_UART_tx_complete
+ mss_uart_instance_t * this_uart
+ int8_t ret_value = 0;
+ uint8_t status = 0u;
+ if((this_uart == &g_mss_uart0) || (this_uart == &g_mss_uart1))
+ /* Read the Line Status Register and update the sticky record. */
+ if((TX_COMPLETE == this_uart->tx_buff_size) &&
+ ((status & MSS_UART_TEMT) != 0u))
+ ret_value = (int8_t)1;
+ return ret_value;
+size_t
+MSS_UART_get_rx
+ uint8_t * rx_buff,
+ size_t buff_size
+ size_t rx_size = 0u;
+ ASSERT(rx_buff != ((uint8_t *)0));
+ ASSERT(buff_size > 0u);
+ (rx_buff != ((uint8_t *)0)) && (buff_size > 0u))
+ while(((status & MSS_UART_DATA_READY) != 0u) &&
+ (rx_size < buff_size))
+ rx_buff[rx_size] = this_uart->hw_reg->RBR;
+ ++rx_size;
+ return rx_size;
+MSS_UART_enable_irq
+ mss_uart_irq_t irq_mask
+ ASSERT(MSS_UART_INVALID_IRQ > irq_mask);
+ (MSS_UART_INVALID_IRQ > irq_mask))
+ /* irq_mask encoding: 1- enable
+ * bit 0 - Receive Data Available Interrupt
+ * bit 1 - Transmitter Holding Register Empty Interrupt
+ * bit 2 - Receiver Line Status Interrupt
+ * bit 3 - Modem Status Interrupt
+ this_uart->hw_reg->IER |= (uint8_t)irq_mask & IIRF_MASK;
+ * bit 4 - Receiver time-out interrupt
+ * bit 5 - NACK / ERR signal interrupt
+ * bit 6 - PID parity error interrupt
+ * bit 7 - LIN break detection interrupt
+ * bit 8 - LIN Sync detection interrupt
+ this_uart->hw_reg->IEM |= (uint8_t)(((uint32_t)irq_mask & ~((uint32_t)IIRF_MASK)) >> 4u);
+MSS_UART_disable_irq
+ /* irq_mask encoding: 1 - disable
+ this_uart->hw_reg->IER &= ((uint8_t)(~((uint32_t)irq_mask & (uint32_t)IIRF_MASK)));
+ this_uart->hw_reg->IEM |= (uint8_t)(~(((uint32_t)irq_mask & ~((uint32_t)IIRF_MASK)) >> 8u));
+ if(irq_mask == IIRF_MASK)
+ /* Disable UART instance interrupt in Cortex-M3 NVIC. */
+ NVIC_DisableIRQ(this_uart->irqn);
+MSS_UART_set_rx_handler
+ mss_uart_irq_handler_t handler,
+ mss_uart_rx_trig_level_t trigger_level
+ ASSERT(handler != INVALID_IRQ_HANDLER );
+ ASSERT(trigger_level < MSS_UART_FIFO_INVALID_TRIG_LEVEL);
+ (handler != INVALID_IRQ_HANDLER) &&
+ (trigger_level < MSS_UART_FIFO_INVALID_TRIG_LEVEL))
+ this_uart->rx_handler = handler;
+ /* Set the receive interrupt trigger level. */
+ this_uart->hw_reg->FCR = (this_uart->hw_reg->FCR &
+ (uint8_t)(~((uint8_t)FCR_TRIG_LEVEL_MASK))) |
+ (uint8_t)trigger_level;
+ /* Enable receive interrupt. */
+ set_bit_reg8(&this_uart->hw_reg->IER,ERBFI);
+MSS_UART_set_loopback
+ mss_uart_loopback_t loopback
+ ASSERT(MSS_UART_INVALID_LOOPBACK > loopback);
+ if(((this_uart == &g_mss_uart0) || (this_uart == &g_mss_uart1)) ||
+ (MSS_UART_INVALID_LOOPBACK > loopback))
+ switch(loopback)
+ case MSS_UART_LOCAL_LOOPBACK_OFF:
+ /* Disable local loopback */
+ clear_bit_reg8(&this_uart->hw_reg->MCR,LOOP);
+ case MSS_UART_LOCAL_LOOPBACK_ON:
+ /* Enable local loopback */
+ set_bit_reg8(&this_uart->hw_reg->MCR,LOOP);
+ case MSS_UART_REMOTE_LOOPBACK_OFF:
+ case MSS_UART_AUTO_ECHO_OFF:
+ /* Disable remote loopback & automatic echo*/
+ this_uart->hw_reg->MCR &= ~RLOOP_MASK;
+ case MSS_UART_REMOTE_LOOPBACK_ON:
+ /* Enable remote loopback */
+ this_uart->hw_reg->MCR |= (1u << RLOOP);
+ case MSS_UART_AUTO_ECHO_ON:
+ /* Enable automatic echo */
+ this_uart->hw_reg->MCR |= (1u << ECHO);
+ case MSS_UART_INVALID_LOOPBACK:
+ /* Fall through to default. */
+ * UART0 interrupt service routine.
+ * UART0_IRQHandler is included within the Cortex-M3 vector table as part of the
+ * Fusion 2 CMSIS.
+__attribute__((__interrupt__)) void UART0_IRQHandler(void)
+void UART0_IRQHandler(void)
+ MSS_UART_isr(&g_mss_uart0);
+ * UART1 interrupt service routine.
+ * UART2_IRQHandler is included within the Cortex-M3 vector table as part of the
+__attribute__((__interrupt__)) void UART1_IRQHandler(void)
+void UART1_IRQHandler(void)
+ MSS_UART_isr(&g_mss_uart1);
+MSS_UART_set_rxstatus_handler
+ mss_uart_irq_handler_t handler
+ ASSERT(handler != INVALID_IRQ_HANDLER);
+ (handler != INVALID_IRQ_HANDLER))
+ this_uart->linests_handler = handler;
+ /* Enable receiver line status interrupt. */
+ set_bit_reg8(&this_uart->hw_reg->IER,ELSI);
+MSS_UART_set_tx_handler
+ this_uart->tx_handler = handler;
+ /* Make TX buffer info invalid */
+ this_uart->tx_buffer = (const uint8_t *)0;
+ this_uart->tx_buff_size = 0u;
+ /* Enable transmitter holding register Empty interrupt. */
+MSS_UART_set_modemstatus_handler
+ this_uart->modemsts_handler = handler;
+ /* Enable modem status interrupt. */
+ set_bit_reg8(&this_uart->hw_reg->IER,EDSSI);
+MSS_UART_fill_tx_fifo
+ const uint8_t * tx_buffer,
+ size_t tx_size
+ size_t size_sent = 0u;
+ ASSERT(tx_buffer != ( (uint8_t *)0));
+ ASSERT(tx_size > 0);
+ /* Fill the UART's Tx FIFO until the FIFO is full or the complete input
+ * buffer has been written. */
+ (tx_buffer != ((uint8_t *)0)) &&
+ (tx_size > 0u))
+ /* Fill up FIFO */
+ this_uart->hw_reg->THR = tx_buffer[size_sent];
+ return size_sent;
+uint8_t
+MSS_UART_get_rx_status
+ uint8_t status = MSS_UART_INVALID_PARAM;
+ * Extract UART receive error status.
+ * Bit 1 - Overflow error status
+ * Bit 2 - Parity error status
+ * Bit 3 - Frame error status
+ * Bit 4 - Break interrupt indicator
+ * Bit 7 - FIFO data error status
+ this_uart->status |= (this_uart->hw_reg->LSR);
+ status = (this_uart->status & STATUS_ERROR_MASK);
+ /* Clear the sticky status after reading */
+ this_uart->status = 0u;
+ return status;
+MSS_UART_get_modem_status
+ * Extract UART modem status and place in lower bits of "status".
+ * Bit 0 - Delta Clear to Send Indicator
+ * Bit 1 - Delta Clear to Receive Indicator
+ * Bit 2 - Trailing edge of Ring Indicator detector
+ * Bit 3 - Delta Data Carrier Detect indicator
+ * Bit 4 - Clear To Send
+ * Bit 5 - Data Set Ready
+ * Bit 6 - Ring Indicator
+ * Bit 7 - Data Carrier Detect
+ status = this_uart->hw_reg->MSR;
+ * MSS_UART_get_tx_status.
+MSS_UART_get_tx_status
+ uint8_t status = MSS_UART_TX_BUSY;
+ * Extract the transmit status bits from the UART's Line Status Register.
+ * Bit 5 - Transmitter Holding Register/FIFO Empty (THRE) status. (If = 1, TX FIFO is empty)
+ * Bit 6 - Transmitter Empty (TEMT) status. (If = 1, both TX FIFO and shift register are empty)
+ status &= (MSS_UART_THRE | MSS_UART_TEMT);
+MSS_UART_set_break
+ /* set break charecter on Tx line */
+ set_bit_reg8(&this_uart->hw_reg->LCR,SB);
+MSS_UART_clear_break
+ /* remove break charecter from Tx line */
+ clear_bit_reg8(&this_uart->hw_reg->LCR,SB);
+MSS_UART_set_pidpei_handler
+ this_uart->pid_pei_handler = handler;
+ NVIC_ClearPendingIRQ( this_uart->irqn );
+ /* Enable PID parity error interrupt. */
+ set_bit_reg8(&this_uart->hw_reg->IEM,EPID_PEI);
+MSS_UART_set_linbreak_handler
+ this_uart->break_handler = handler;
+ /* Enable LIN break detection interrupt. */
+ set_bit_reg8(&this_uart->hw_reg->IEM,ELINBI);
+MSS_UART_set_linsync_handler
+ this_uart->sync_handler = handler;
+ /* Enable LIN sync detection interrupt. */
+ set_bit_reg8(&this_uart->hw_reg->IEM,ELINSI);
+MSS_UART_set_nack_handler
+ this_uart->nack_handler = handler;
+ set_bit_reg8(&this_uart->hw_reg->IEM,ENACKI);
+MSS_UART_set_rx_timeout_handler
+ this_uart->rto_handler = handler;
+ /* Enable receiver timeout interrupt. */
+ set_bit_reg8(&this_uart->hw_reg->IEM,ERTOI);
+MSS_UART_enable_half_duplex
+ /* enable single wire half-duplex mode */
+MSS_UART_disable_half_duplex
+ clear_bit_reg8(&this_uart->hw_reg->MM2,ESWM);
+MSS_UART_set_rx_endian
+ mss_uart_endian_t endian
+ ASSERT(MSS_UART_INVALID_ENDIAN > endian);
+ (MSS_UART_INVALID_ENDIAN > endian))
+ /* Configure MSB first / LSB first for receiver */
+ ((MSS_UART_LITTLEEND == endian) ? (clear_bit_reg8(&this_uart->hw_reg->MM1,E_MSB_RX)) :
+ (set_bit_reg8(&this_uart->hw_reg->MM1,E_MSB_RX)));
+MSS_UART_set_tx_endian
+ /* Configure MSB first / LSB first for transmitter */
+ ((MSS_UART_LITTLEEND == endian) ? (clear_bit_reg8(&this_uart->hw_reg->MM1,E_MSB_TX)) :
+ (set_bit_reg8(&this_uart->hw_reg->MM1,E_MSB_TX)) ) ;
+MSS_UART_set_filter_length
+ mss_uart_filter_length_t length
+ ASSERT(MSS_UART_INVALID_FILTER_LENGTH > length);
+ (MSS_UART_INVALID_FILTER_LENGTH > length))
+ /* Configure glitch filter length */
+ this_uart->hw_reg->GFR = (uint8_t)length;
+MSS_UART_enable_afm
+ /* Disable RX FIFO till address flag with correct address is received */
+ set_bit_reg8(&this_uart->hw_reg->MM2,EAFM);
+MSS_UART_disable_afm
+ /* Enable RX FIFO irrespective of address flag and
+ correct address is received */
+ clear_bit_reg8(&this_uart->hw_reg->MM2,EAFM);
+MSS_UART_enable_afclear
+ /* Enable address flag clearing */
+ /* Disable RX FIFO till another address flag with
+ set_bit_reg8(&this_uart->hw_reg->MM2,EAFC);
+MSS_UART_disable_afclear
+ /* Disable address flag clearing */
+ clear_bit_reg8(&this_uart->hw_reg->MM2,EAFC);
+MSS_UART_enable_rx_timeout
+ uint8_t timeout
+ /* Load the receive timeout value */
+ this_uart->hw_reg->RTO = timeout;
+ /*Enable receiver time-out */
+ set_bit_reg8(&this_uart->hw_reg->MM0,ERTO);
+MSS_UART_disable_rx_timeout
+ /*Disable receiver time-out */
+ clear_bit_reg8(&this_uart->hw_reg->MM0,ERTO);
+MSS_UART_enable_tx_time_guard
+ uint8_t timeguard
+ /* Load the transmitter time guard value */
+ this_uart->hw_reg->TTG = timeguard;
+ /*Enable transmitter time guard */
+ set_bit_reg8(&this_uart->hw_reg->MM0,ETTG);
+MSS_UART_disable_tx_time_guard
+ /*Disable transmitter time guard */
+ clear_bit_reg8(&this_uart->hw_reg->MM0,ETTG);
+MSS_UART_set_address
+ uint8_t address
+ this_uart->hw_reg->ADR = address;
+MSS_UART_set_ready_mode
+ mss_uart_ready_mode_t mode
+ ASSERT(MSS_UART_INVALID_READY_MODE > mode);
+ (MSS_UART_INVALID_READY_MODE > mode ) )
+ /* Configure mode 0 or mode 1 for TXRDY and RXRDY */
+ ((MSS_UART_READY_MODE0 == mode) ? clear_bit_reg8(&this_uart->hw_reg->FCR,RDYMODE) :
+ set_bit_reg8(&this_uart->hw_reg->FCR,RDYMODE) );
+ * Configure baud divisors using fractional baud rate if possible.
+static void
+config_baud_divisors
+ uint32_t baud_value;
+ uint32_t baud_value_by_64;
+ uint32_t baud_value_by_128;
+ uint32_t fractional_baud_value;
+ uint32_t pclk_freq;
+ this_uart->baudrate = baudrate;
+ /* Force the value of the CMSIS global variables holding the various system
+ * clock frequencies to be updated. */
+ if(this_uart == &g_mss_uart0)
+ pclk_freq = g_FrequencyPCLK0;
+ pclk_freq = g_FrequencyPCLK1;
+ * Compute baud value based on requested baud rate and PCLK frequency.
+ * The baud value is computed using the following equation:
+ * baud_value = PCLK_Frequency / (baud_rate * 16)
+ baud_value_by_128 = (8u * pclk_freq) / baudrate;
+ baud_value_by_64 = baud_value_by_128 / 2u;
+ baud_value = baud_value_by_64 / 64u;
+ fractional_baud_value = baud_value_by_64 - (baud_value * 64u);
+ fractional_baud_value += (baud_value_by_128 - (baud_value * 128u)) - (fractional_baud_value * 2u);
+ /* Assert if integer baud value fits in 16-bit. */
+ ASSERT(baud_value <= UINT16_MAX);
+ if(baud_value <= (uint32_t)UINT16_MAX)
+ if(baud_value > 1u)
+ * Use Frational baud rate divisors
+ /* set divisor latch */
+ set_bit_reg8(&this_uart->hw_reg->LCR,DLAB);
+ /* msb of baud value */
+ this_uart->hw_reg->DMR = (uint8_t)(baud_value >> 8);
+ /* lsb of baud value */
+ this_uart->hw_reg->DLR = (uint8_t)baud_value;
+ /* reset divisor latch */
+ clear_bit_reg8(&this_uart->hw_reg->LCR,DLAB);
+ /* Enable Fractional baud rate */
+ set_bit_reg8(&this_uart->hw_reg->MM0,EFBR);
+ /* Load the fractional baud rate register */
+ ASSERT(fractional_baud_value <= (uint32_t)UINT8_MAX);
+ this_uart->hw_reg->DFR = (uint8_t)fractional_baud_value;
+ * Do NOT use Frational baud rate divisors.
+ this_uart->hw_reg->DMR = (uint8_t)(baud_value >> 8u);
+ /* Disable Fractional baud rate */
+ clear_bit_reg8(&this_uart->hw_reg->MM0,EFBR);
+MSS_UART_set_usart_mode
+ mss_uart_usart_mode_t mode
+ ASSERT(MSS_UART_INVALID_SYNC_MODE > mode);
+ (MSS_UART_INVALID_SYNC_MODE > mode))
+ /* Nothing to do for the baudrate: operates at PCLK / 2 + glitch filter length */
+ /* Clear the ESYN bits 2:0 */
+ this_uart->hw_reg->MM0 &= ~SYNC_ASYNC_MODE_MASK;
+ this_uart->hw_reg->MM0 |= (uint8_t)mode;
+ * Local Functions
+ * Global initialization for all modes
+static void global_init
+ this_uart->hw_reg = UART0;
+ this_uart->irqn = UART0_IRQn;
+ /* reset UART0 */
+ SYSREG->SOFT_RST_CR |= SYSREG_MMUART0_SOFTRESET_MASK;
+ /* Clear any previously pended UART0 interrupt */
+ NVIC_ClearPendingIRQ(UART0_IRQn);
+ /* Take UART0 out of reset. */
+ SYSREG->SOFT_RST_CR &= ~SYSREG_MMUART0_SOFTRESET_MASK;
+ this_uart->hw_reg = UART1;
+ this_uart->irqn = UART1_IRQn;
+ /* Reset UART1 */
+ SYSREG->SOFT_RST_CR |= SYSREG_MMUART1_SOFTRESET_MASK;
+ /* Clear any previously pended UART1 interrupt */
+ NVIC_ClearPendingIRQ(UART1_IRQn);
+ /* Take UART1 out of reset. */
+ SYSREG->SOFT_RST_CR &= ~SYSREG_MMUART1_SOFTRESET_MASK;
+ /* disable interrupts */
+ this_uart->hw_reg->IER = 0u;
+ /* FIFO configuration */
+ this_uart->hw_reg->FCR = (uint8_t)MSS_UART_FIFO_SINGLE_BYTE;
+ /* clear receiver FIFO */
+ set_bit_reg8(&this_uart->hw_reg->FCR,CLEAR_RX_FIFO);
+ /* clear transmitter FIFO */
+ set_bit_reg8(&this_uart->hw_reg->FCR,CLEAR_TX_FIFO);
+ /* set default READY mode : Mode 0*/
+ /* enable RXRDYN and TXRDYN pins. The earlier FCR write to set the TX FIFO
+ * trigger level inadvertently disabled the FCR_RXRDY_TXRDYN_EN bit. */
+ set_bit_reg8(&this_uart->hw_reg->FCR,RXRDY_TXRDYN_EN);
+ /* disable loopback : local * remote */
+ clear_bit_reg8(&this_uart->hw_reg->MCR,RLOOP);
+ /* set default TX endian */
+ clear_bit_reg8(&this_uart->hw_reg->MM1,E_MSB_TX);
+ /* set default RX endian */
+ clear_bit_reg8(&this_uart->hw_reg->MM1,E_MSB_RX);
+ /* default AFM : disabled */
+ /* disable TX time gaurd */
+ /* set default RX timeout */
+ /* disable fractional baud-rate */
+ /* disable single wire mode */
+ /* set filter to minimum value */
+ this_uart->hw_reg->GFR = 0u;
+ /* set default TX time gaurd */
+ this_uart->hw_reg->TTG = 0u;
+ this_uart->hw_reg->RTO = 0u;
+ * Configure baud rate divisors. This uses the frational baud rate divisor
+ * where possible to provide the most accurate baud rat possible.
+ config_baud_divisors(this_uart, baud_rate);
+ /* set the line control register (bit length, stop bits, parity) */
+ this_uart->hw_reg->LCR = line_config;
+ /* Instance setup */
+ this_uart->baudrate = baud_rate;
+ this_uart->lineconfig = line_config;
+ this_uart->tx_buff_size = TX_COMPLETE;
+ this_uart->tx_idx = 0u;
+ /* Default handlers for MSS UART interrupts */
+ this_uart->rx_handler = NULL_HANDLER;
+ this_uart->tx_handler = NULL_HANDLER;
+ this_uart->linests_handler = NULL_HANDLER;
+ this_uart->modemsts_handler = NULL_HANDLER;
+ this_uart->rto_handler = NULL_HANDLER;
+ this_uart->nack_handler = NULL_HANDLER;
+ this_uart->pid_pei_handler = NULL_HANDLER;
+ this_uart->break_handler = NULL_HANDLER;
+ this_uart->sync_handler = NULL_HANDLER;
+ /* Initialize the sticky status */
+ * Interrupt service routine triggered by any MSS UART interrupt. This routine
+ * will call the handler function appropriate to the interrupt from the
+ * handlers previously registered with the driver through calls to the
+ * MSS_UART_set_*_handler() functions, or it will call the default_tx_handler()
+ * function in response to transmit interrupts if MSS_UART_irq_tx() is used to
+ * transmit data.
+MSS_UART_isr
+ uint8_t iirf;
+ iirf = this_uart->hw_reg->IIR & IIRF_MASK;
+ switch (iirf)
+ case IIRF_MODEM_STATUS: /* Modem status interrupt */
+ ASSERT(NULL_HANDLER != this_uart->modemsts_handler);
+ if(NULL_HANDLER != this_uart->modemsts_handler)
+ (*(this_uart->modemsts_handler))(this_uart);
+ case IIRF_THRE: /* Transmitter Holding Register Empty */
+ ASSERT(NULL_HANDLER != this_uart->tx_handler);
+ if(NULL_HANDLER != this_uart->tx_handler)
+ (*(this_uart->tx_handler))(this_uart);
+ case IIRF_RX_DATA: /* Received Data Available */
+ case IIRF_DATA_TIMEOUT: /* Received Data Timed-out */
+ ASSERT(NULL_HANDLER != this_uart->rx_handler);
+ if(NULL_HANDLER != this_uart->rx_handler)
+ (*(this_uart->rx_handler))(this_uart);
+ case IIRF_RX_LINE_STATUS: /* Line Status Interrupt */
+ ASSERT(NULL_HANDLER != this_uart->linests_handler);
+ if(NULL_HANDLER != this_uart->linests_handler)
+ (*(this_uart->linests_handler))(this_uart);
+ case IIRF_MMI:
+ /* Identify multimode interrupts and handle */
+ /* Receiver time-out interrupt */
+ if(read_bit_reg8(&this_uart->hw_reg->IIM,ERTOI))
+ ASSERT(NULL_HANDLER != this_uart->rto_handler);
+ if(NULL_HANDLER != this_uart->rto_handler)
+ (*(this_uart->rto_handler))(this_uart);
+ /* NACK interrupt */
+ if(read_bit_reg8(&this_uart->hw_reg->IIM,ENACKI))
+ ASSERT(NULL_HANDLER != this_uart->nack_handler);
+ if(NULL_HANDLER != this_uart->nack_handler)
+ (*(this_uart->nack_handler))(this_uart);
+ /* PID parity error interrupt */
+ if(read_bit_reg8(&this_uart->hw_reg->IIM,EPID_PEI))
+ ASSERT(NULL_HANDLER != this_uart->pid_pei_handler);
+ if(NULL_HANDLER != this_uart->pid_pei_handler)
+ (*(this_uart->pid_pei_handler))(this_uart);
+ /* LIN break detection interrupt */
+ if(read_bit_reg8(&this_uart->hw_reg->IIM,ELINBI))
+ ASSERT(NULL_HANDLER != this_uart->break_handler);
+ if(NULL_HANDLER != this_uart->break_handler)
+ (*(this_uart->break_handler))(this_uart);
+ /* LIN Sync detection interrupt */
+ if(read_bit_reg8(&this_uart->hw_reg->IIM,ELINSI))
+ ASSERT(NULL_HANDLER != this_uart->sync_handler);
+ if(NULL_HANDLER != this_uart->sync_handler)
+ (*(this_uart->sync_handler))(this_uart);
+ ASSERT(INVALID_INTERRUPT);
+default_tx_handler
+ ASSERT(( (uint8_t *)0 ) != this_uart->tx_buffer);
+ ASSERT(0u < this_uart->tx_buff_size);
+ (((uint8_t *)0 ) != this_uart->tx_buffer) &&
+ (0u < this_uart->tx_buff_size))
+ * This function should only be called as a result of a THRE interrupt.
+ * Verify that this is true before proceeding to transmit data.
+ uint32_t i;
+ uint32_t tx_remain = this_uart->tx_buff_size - this_uart->tx_idx;
+ if(tx_remain < TX_FIFO_SIZE)
+ fill_size = tx_remain;
+ for(i = 0u; i < fill_size; ++i)
+ this_uart->hw_reg->THR = this_uart->tx_buffer[this_uart->tx_idx];
+ ++this_uart->tx_idx;
+ /* Flag Tx as complete if all data has been pushed into the Tx FIFO. */
+ if(this_uart->tx_idx == this_uart->tx_buff_size)
+ /* disables TX interrupt */
+ clear_bit_reg8(&this_uart->hw_reg->IER,ETBEI);
@@ -0,0 +1,2639 @@
+ * public API.
+ @mainpage SmartFusion2 MSS UART Bare Metal Driver.
+ ==============================================================================
+ The SmartFusion2 microcontroller subsystem (MSS) includes two multi-mode UART
+ (MMUART) peripherals for serial communication. This driver provides a set of
+ functions for controlling the MSS MMUARTs as part of a bare metal system
+ where no operating system is available. These drivers can be adapted for use
+ as part of an operating system, but the implementation of the adaptation layer
+ between this driver and the operating system's driver model is outside the
+ scope of this driver.
+ Note: MSS UART is synonymous with MSS MMUART in this document.
+ The configuration of all features of the MSS MMUART peripherals is covered by
+ this driver with the exception of the SmartFusion2 IOMUX configuration.
+ SmartFusion2 allows multiple non-concurrent uses of some external pins through
+ IOMUX configuration. This feature allows optimization of external pin usage by
+ FPGA fabric. The MSS MMUART serial signals are routed through IOMUXs to the
+ SmartFusion2 device external pins. The MSS MMUART serial signals may also be
+ routed through IOMUXs to the SmartFusion2 FPGA fabric. For more information on
+ IOMUX, refer to the IOMUX section of the SmartFusion2 Microcontroller
+ Subsystem (MSS) User’s Guide.
+ must ensure that the MSS MMUART peripherals are enabled and configured in the
+ SmartFusion2 MSS configurator if you wish to use them. For more information on
+ IOMUXs, refer to the IOMUX section of the SmartFusion2 Microcontroller
+ MSS MMUART peripherals are defined as constants in the SmartFusion2 CMSIS HAL.
+ You must ensure that the latest SmartFusion2 CMSIS HAL is included in the
+ project settings of the software tool chain used to build your project and
+ that it is generated into your project.
+ The MSS MMUART driver functions are grouped into the following categories:
+ - Initialization and configuration functions
+ - Polled transmit and receive functions
+ - Interrupt driven transmit and receive functions
+ --------------------------------
+ Initialization and Configuration
+ The MSS MMUART supports the following four broad modes of operation:
+ - UART or USART mode
+ - LIN mode
+ - IrDA mode
+ - Smartcard or ISO 7816 mode
+ The MSS MMUART driver provides the MSS_UART_init(), MSS_UART_lin_init(),
+ MSS_UART_irda_init() and MSS_UART_smartcard_init() functions to initialize the
+ MSS MMUARTs for operation in one of these modes. One of these initialization
+ functions must be called before any other MSS MMUART driver functions can be
+ called. The MSS MMUART operating modes are mutually exclusive; therefore only
+ one of the initialization functions must be called. The first parameter of the
+ initialization functions is a pointer to one of two global data structures
+ used to store state information for each MSS MMUART. A pointer to these data
+ structures is also used as the first parameter to many of the driver functions
+ to identify which MSS MMUART will be used by the called function. The names of
+ these two data structures are g_mss_uart0 and g_mss_uart1. Therefore, any call
+ to an MSS MMUART function should be of the form
+ MSS_UART_function_name( &g_mss_uart0, ... ) or
+ MSS_UART_function_name( &g_mss_uart1, ... ).
+ UART or USART Mode
+ For the UART or USART modes of operation, the MSS MMUART driver is initialized
+ through a call to the MSS_UART_init() function. This function takes the UART’s
+ configuration as its parameters. The MSS_UART_init() function must be called
+ before any other MSS MMUART driver functions can be called.
+ The MSS_UART_init() function configures the baud rate based on the input baud
+ rate parameter and if possible uses a fractional baud rate for greater
+ precision. This function disables the LIN, IrDA and SmartCard modes.
+ LIN mode
+ For the LIN mode of operation, the MSS MMUART driver is initialized through a
+ call to the MSS_UART_lin_init() function. This function takes the LIN node’s
+ configuration as its parameters. The MSS_UART_lin_init() function must be
+ called before any other MSS MMUART driver functions can be called. The
+ MSS_UART_lin_init() function configures the baud rate based on the input baud
+ precision. This function disables the IrDA and SmartCard modes.
+ The driver also provides the following LIN mode configuration functions:
+ - MSS_UART_set_break()
+ - MSS_UART_clear_break()
+ - MSS_UART_set_pidpei_handler()
+ - MSS_UART_set_linbreak_handler()
+ - MSS_UART_set_linsync_handler()
+ Note: These LIN mode configuration functions can only be called after the
+ MSS_UART_lin_init() function is called.
+ IrDA mode
+ For the IrDA mode of operation, the driver is initialized through a call to
+ the MSS_UART_irda_init() function. This function takes the IrDA node’s
+ configuration as its parameters. The MSS_UART_irda_init() function must be
+ MSS_UART_irda_init() function configures the baud rate based on the input baud
+ precision. This function disables the LIN and SmartCard modes.
+ Smartcard or ISO 7816 mode
+ For the Smartcard or ISO 7816 mode of operation, the driver is initialized
+ through a call to the MSS_UART_smartcard_init() function. This function takes
+ the smartcard configuration as its parameters. The MSS_UART_smartcard_init()
+ function must be called before any other MSS MMUART driver functions can be
+ called. The MSS_UART_smartcard_init() function configures the baud rate based
+ on the input baud rate parameter and if possible uses a fractional baud rate
+ for greater precision. This function disables the LIN and IrDA modes.
+ The driver also provides the following Smartcard mode configuration functions:
+ - MSS_UART_enable_halfduplex()
+ - MSS_UART_disable_halfduplex()
+ - MSS_UART_set_nack_handler()
+ Note: These Smartcard mode configuration functions can only be called after
+ the MSS_UART_smartcard_init() function is called.
+ Common Configuration Functions
+ The driver also provides the configuration functions that can be used with all
+ MSS MMUART operating modes. These common configuration functions are as
+ - MSS_UART_set_rx_endian()
+ - MSS_UART_set_tx_endian()
+ - MSS_UART_enable_afclear()
+ - MSS_UART_disable_afclear()
+ - MSS_UART_enable_rx_timeout()
+ - MSS_UART_disable_rx_timeout()
+ - MSS_UART_enable_tx_time_guard()
+ - MSS_UART_disable_tx_time_guard()
+ - MSS_UART_set_address()
+ - MSS_UART_set_ready_mode()
+ - MSS_UART_set_usart_mode()
+ - MSS_UART_set_filter_length()
+ - MSS_UART_enable_afm()
+ - MSS_UART_disable_afm()
+ Note: These configuration functions can only be called after one of the
+ MSS_UART_init(), MSS_UART_lin_init(), MSS_UART_irda_init() or
+ MSS_UART_smartcard_init() functions is called.
+ --------------------------------------
+ Polled Transmit and Receive Operations
+ The driver can be used to transmit and receive data once initialized.
+ Data is transmitted using the MSS_UART_polled_tx() function. This function is
+ blocking, meaning that it will only return once the data passed to the
+ function has been sent to the MSS MMUART hardware transmitter. Data received
+ by the MSS MMUART hardware receiver can be read by the MSS_UART_get_rx()
+ function.
+ The MSS_UART_polled_tx_string() function is provided to transmit a NULL (‘\0’)
+ terminated string in polled mode. This function is blocking, meaning that it
+ will only return once the data passed to the function has been sent to the MSS
+ MMUART hardware transmitter.
+ The MSS_UART_fill_tx_fifo() function fills the MSS MMUART hardware transmit
+ FIFO with data from a buffer passed as a parameter and returns the number of
+ bytes transferred to the FIFO. If the transmit FIFO is not empty when the
+ MSS_UART_fill_tx_fifo() function is called it returns immediately without
+ transferring any data to the FIFO.
+ ---------------------------
+ Interrupt Driven Operations
+ The driver can also transmit or receive data under interrupt control, freeing
+ your application to perform other tasks until an interrupt occurs indicating
+ that the driver’s attention is required.
+ Interrupt Handlers
+ The MSS MMUART driver supports all types of interrupt triggered by the MSS
+ MMUART. The driver’s internal top level interrupt handler identifies the
+ source of the MSS MMUART interrupt and calls the corresponding lower level
+ handler function that you previously registered with the driver through calls
+ to the MSS_UART_set_rx_handler(), MSS_UART_set_tx_handler(),
+ MSS_UART_set_rxstatus_handler(), and MSS_UART_set_modemstatus_handler()
+ functions. You are responsible for creating these lower level interrupt
+ handlers as part of your application program and registering them with the
+ driver.
+ Note: The SmartFusion2 CMSIS-PAL defines the UART0_IRQHandler() and
+ UART1_IRQHandler() functions (with weak linkage) and assigns them as the
+ interrupt service routines (ISR) for the MSS MMUART interrupt inputs to
+ the Cortex-M3 NVIC. The MSS MMUART driver provides the implementation
+ functions for both of these ISRs from which it calls its own internal
+ top level, interrupt handler function.
+ The MSS_UART_enable_irq() and MSS_UART_disable_irq() functions are used to
+ enable or disable the received line status, received data available/character
+ timeout, transmit holding register empty and modem status interrupts at the
+ MSS MMUART level. The MSS_UART_enable_irq() function also enables the MSS
+ MMUART instance interrupt at the Cortex-M3 level.
+ Transmitting Data
+ Interrupt-driven transmit is initiated by a call to MSS_UART_irq_tx(),
+ specifying the block of data to transmit. Your application is then free to
+ perform other tasks and inquire later whether transmit has completed by
+ calling the MSS_UART_tx_complete() function. The MSS_UART_irq_tx() function
+ enables the UART’s transmit holding register empty (THRE) interrupt and then,
+ when the interrupt goes active, the driver’s default THRE interrupt handler
+ transfers the data block to the UART until the entire block is transmitted.
+ Note: You can use the MSS_UART_set_tx_handler() function to assign an
+ alternative handler to the THRE interrupt. In this case, you must not
+ use the MSS_UART_irq_tx() function to initiate the transmit, as this
+ will re-assign the driver’s default THRE interrupt handler to the THRE
+ interrupt. Instead, your alternative THRE interrupt handler must include
+ a call to the MSS_UART_fill_tx_fifo() function to transfer the data to
+ the UART.
+ Receiving Data
+ Interrupt-driven receive is performed by first calling
+ MSS_UART_set_rx_handler() to register a receive handler function that will be
+ called by the driver whenever receive data is available. You must provide this
+ receive handler function which must include a call to the MSS_UART_get_rx()
+ function to actually read the received data.
+ -----------
+ UART Status
+ The function MSS_UART_get_rx_status() is used to read the receiver error
+ status. This function returns the overrun, parity, framing, break, and FIFO
+ error status of the receiver.
+ The function MSS_UART_get_tx_status() is used to read the transmitter status.
+ This function returns the transmit empty (TEMT) and transmit holding register
+ empty (THRE) status of the transmitter.
+ The function MSS_UART_get_modem_status() is used to read the modem status
+ flags. This function returns the current value of the modem status register.
+ --------
+ Loopback
+ The MSS_UART_set_loopback() function can be used to locally loopback the Tx
+ and Rx lines of a UART. This is not to be confused with the loopback of UART0
+ to UART1, which can be achieved through the microcontroller subsystem’s system
+ registers.
+#ifndef __MSS_UART_H_
+#define __MSS_UART_H_ 1
+#include <stddef.h>
+ Baud rates
+ The following definitions are used to specify standard baud rates as a
+ parameter to the MSS_UART_init() function.
+#define MSS_UART_110_BAUD 110
+#define MSS_UART_300_BAUD 300
+#define MSS_UART_1200_BAUD 1200
+#define MSS_UART_2400_BAUD 2400
+#define MSS_UART_4800_BAUD 4800
+#define MSS_UART_9600_BAUD 9600
+#define MSS_UART_19200_BAUD 19200
+#define MSS_UART_38400_BAUD 38400
+#define MSS_UART_57600_BAUD 57600
+#define MSS_UART_115200_BAUD 115200
+#define MSS_UART_230400_BAUD 230400
+#define MSS_UART_460800_BAUD 460800
+#define MSS_UART_921600_BAUD 921600
+ Data Bits Length
+ The following defines are used to build the value of the MSS_UART_init()
+ function line_config parameter.
+#define MSS_UART_DATA_5_BITS ( (uint8_t) 0x00 )
+#define MSS_UART_DATA_6_BITS ( (uint8_t) 0x01 )
+#define MSS_UART_DATA_7_BITS ( (uint8_t) 0x02 )
+#define MSS_UART_DATA_8_BITS ( (uint8_t) 0x03 )
+ Parity
+#define MSS_UART_NO_PARITY ( (uint8_t) 0x00 )
+#define MSS_UART_ODD_PARITY ( (uint8_t) 0x08 )
+#define MSS_UART_EVEN_PARITY ( (uint8_t) 0x18 )
+#define MSS_UART_STICK_PARITY_0 ( (uint8_t) 0x38 )
+#define MSS_UART_STICK_PARITY_1 ( (uint8_t) 0x28 )
+ Number of Stop Bits
+#define MSS_UART_ONE_STOP_BIT ( (uint8_t) 0x00 )
+#define MSS_UART_ONEHALF_STOP_BIT ( (uint8_t) 0x04 )
+#define MSS_UART_TWO_STOP_BITS ( (uint8_t) 0x04 )
+ Receiver Error Status
+ The following defines are used to determine the UART receiver error type.
+ These bit mask constants are used with the return value of the
+ MSS_UART_get_rx_status() function to find out if any errors occurred while
+ receiving data.
+#define MSS_UART_INVALID_PARAM ( (uint8_t)0xFF )
+#define MSS_UART_NO_ERROR ( (uint8_t)0x00 )
+#define MSS_UART_OVERUN_ERROR ( (uint8_t)0x02 )
+#define MSS_UART_PARITY_ERROR ( (uint8_t)0x04 )
+#define MSS_UART_FRAMING_ERROR ( (uint8_t)0x08 )
+#define MSS_UART_BREAK_ERROR ( (uint8_t)0x10 )
+#define MSS_UART_FIFO_ERROR ( (uint8_t)0x80 )
+ Transmitter Status
+ The following definitions are used to determine the UART transmitter status.
+ MSS_UART_get_tx_status() function to find out the status of the transmitter.
+#define MSS_UART_TX_BUSY ( (uint8_t) 0x00 )
+#define MSS_UART_THRE ( (uint8_t) 0x20 )
+#define MSS_UART_TEMT ( (uint8_t) 0x40 )
+ Modem Status
+ The following defines are used to determine the modem status. These bit
+ mask constants are used with the return value of the
+ MSS_UART_get_modem_status() function to find out the modem status of
+#define MSS_UART_DCTS ( (uint8_t) 0x01 )
+#define MSS_UART_DDSR ( (uint8_t) 0x02 )
+#define MSS_UART_TERI ( (uint8_t) 0x04 )
+#define MSS_UART_DDCD ( (uint8_t) 0x08 )
+#define MSS_UART_CTS ( (uint8_t) 0x10 )
+#define MSS_UART_DSR ( (uint8_t) 0x20 )
+#define MSS_UART_RI ( (uint8_t) 0x40 )
+#define MSS_UART_DCD ( (uint8_t) 0x80 )
+ This typedef specifies the irq_mask parameter for the MSS_UART_enable_irq()
+ and MSS_UART_disable_irq() functions. The driver defines a set of bit masks
+ that are used to build the value of the irq_mask parameter. A bitwise OR of
+ these bit masks is used to enable or disable multiple MSS MMUART interrupts.
+typedef uint16_t mss_uart_irq_t;
+ The following defines specify the interrupt masks to enable and disable MSS
+ MMUART interrupts. They are used to build the value of the irq_mask parameter
+ for the MSS_UART_enable_irq() and MSS_UART_disable_irq() functions. A bitwise
+ OR of these constants is used to enable or disable multiple interrupts.
+#define MSS_UART_RBF_IRQ 0x001
+#define MSS_UART_TBE_IRQ 0x002
+#define MSS_UART_LS_IRQ 0x004
+#define MSS_UART_MS_IRQ 0x008
+#define MSS_UART_RTO_IRQ 0x010
+#define MSS_UART_NACK_IRQ 0x020
+#define MSS_UART_PIDPE_IRQ 0x040
+#define MSS_UART_LINB_IRQ 0x080
+#define MSS_UART_LINS_IRQ 0x100
+#define MSS_UART_INVALID_IRQ UINT16_MAX
+ This enumeration specifies the receiver FIFO trigger level. This is the number
+ of bytes that must be received before the UART generates a receive data
+ available interrupt. It provides the allowed values for the
+ MSS_UART_set_rx_handler() function trigger_level parameter.
+typedef enum {
+ MSS_UART_FIFO_SINGLE_BYTE = 0x00,
+ MSS_UART_FIFO_FOUR_BYTES = 0x40,
+ MSS_UART_FIFO_EIGHT_BYTES = 0x80,
+ MSS_UART_FIFO_FOURTEEN_BYTES = 0xC0,
+ MSS_UART_FIFO_INVALID_TRIG_LEVEL
+} mss_uart_rx_trig_level_t;
+ This enumeration specifies the loopback configuration of the UART. It provides
+ the allowed values for the MSS_UART_set_loopback() function’s loopback
+ parameter. Use MSS_UART_LOCAL_LOOPBACK_ON to set up the UART to locally
+ loopback its Tx and Rx lines. Use MSS_UART_REMOTE_LOOPBACK_ON to set up the
+ UART in remote loopback mode.
+ MSS_UART_LOCAL_LOOPBACK_OFF,
+ MSS_UART_LOCAL_LOOPBACK_ON,
+ MSS_UART_REMOTE_LOOPBACK_OFF,
+ MSS_UART_REMOTE_LOOPBACK_ON,
+ MSS_UART_AUTO_ECHO_OFF,
+ MSS_UART_AUTO_ECHO_ON,
+ MSS_UART_INVALID_LOOPBACK
+} mss_uart_loopback_t;
+ IrDA input / output polarity.
+ This enumeration specifies the RZI modem polarity for input and output signals.
+ This is passed as parameters in MSS_UART_irda_init() function.
+ MSS_UART_ACTIVE_LOW = 0u,
+ MSS_UART_ACTIVE_HIGH = 1u,
+ MSS_UART_INVALID_POLARITY
+} mss_uart_rzi_polarity_t;
+ IrDA input / output pulse width.
+ This enumeration specifies the RZI modem pulse width for input and output signals.
+ MSS_UART_3_BY_16 = 0u,
+ MSS_UART_1_BY_4 = 1u,
+ MSS_UART_INVALID_PW
+} mss_uart_rzi_pulsewidth_t;
+ Tx / Rx endianess.
+ This enumeration specifies the MSB first or LSB first for MSS UART transmitter
+ and receiver. The parameter of this type shall be passed in
+ MSS_UART_set_rx_endian()and MSS_UART_set_tx_endian() functions.
+ MSS_UART_LITTLEEND,
+ MSS_UART_BIGEND,
+ MSS_UART_INVALID_ENDIAN
+} mss_uart_endian_t;
+ Glitch filter length.
+ This enumeration specifies the glitch filter length. The function
+ MSS_UART_set_filter_length() accepts the parameter of this type.
+ MSS_UART_LEN0 = 0,
+ MSS_UART_LEN1 = 1,
+ MSS_UART_LEN2 = 2,
+ MSS_UART_LEN3 = 3,
+ MSS_UART_LEN4 = 4,
+ MSS_UART_LEN5 = 5,
+ MSS_UART_LEN6 = 6,
+ MSS_UART_LEN7 = 7,
+ MSS_UART_INVALID_FILTER_LENGTH = 8
+} mss_uart_filter_length_t;
+ TXRDY and RXRDY mode.
+ This enumeration specifies the TXRDY and RXRDY signal modes. The function
+ MSS_UART_set_ready_mode() accepts the parameter of this type.
+ MSS_UART_READY_MODE0,
+ MSS_UART_READY_MODE1,
+ MSS_UART_INVALID_READY_MODE
+} mss_uart_ready_mode_t;
+ USART mode of operation.
+ This enumeration specifies the mode of operation of MSS UART when operating
+ as USART. The function MSS_UART_set_usart_mode() accepts the parameter of this type.
+ MSS_UART_ASYNC_MODE = 0,
+ MSS_UART_SYNC_SLAVE_POS_EDGE_CLK = 1,
+ MSS_UART_SYNC_SLAVE_NEG_EDGE_CLK = 2,
+ MSS_UART_SYNC_MASTER_POS_EDGE_CLK = 3,
+ MSS_UART_SYNC_MASTER_NEG_EDGE_CLK = 4,
+ MSS_UART_INVALID_SYNC_MODE = 5
+} mss_uart_usart_mode_t;
+ MSS UART instance type.
+ This is type definition for MSS UART instance. You need to create and
+ maintain a record of this type. This holds all data regarding the MSS UART
+ instance
+typedef struct mss_uart_instance mss_uart_instance_t;
+ Interrupt handler prototype.
+ This typedef specifies the function prototype for MSS UART interrupt handlers.
+ All interrupt handlers registered with the MSS UART driver must be of this type.
+ The interrupt handlers are registered with the driver through the
+ MSS_UART_set_rx_handler(), MSS_UART_set_tx_handler(),
+ functions.
+ The this_uart parameter is a pointer to either g_mss_uart0 or g_mss_uart1 to
+ identify the MSS UART to associate with the handler function.
+typedef void (*mss_uart_irq_handler_t)( mss_uart_instance_t * this_uart );
+ mss_uart_instance.
+ There is one instance of this structure for each instance of the
+ microcontroller subsystem’s UARTs. Instances of this structure are used to
+ identify a specific UART. A pointer to an initialized instance of the
+ mss_uart_instance_t structure is passed as the first parameter to
+ MSS UART driver functions to identify which UART should perform the
+ requested operation.
+struct mss_uart_instance{
+ /* CMSIS related defines identifying the UART hardware. */
+ UART_TypeDef * hw_reg; /*!< Pointer to UART registers. */
+ IRQn_Type irqn; /*!< UART's Cortex-M3 NVIC interrupt number. */
+ uint32_t baudrate; /*!< Operating baud rate. */
+ uint8_t lineconfig; /*!< Line configuration parameters. */
+ uint8_t status; /*!< Sticky line status. */
+ /* transmit related info (used with interrupt driven transmit): */
+ const uint8_t * tx_buffer; /*!< Pointer to transmit buffer. */
+ uint32_t tx_buff_size; /*!< Transmit buffer size. */
+ uint32_t tx_idx; /*!< Index within transmit buffer of next byte to transmit.*/
+ /* line status interrupt handler:*/
+ mss_uart_irq_handler_t linests_handler; /*!< Pointer to user registered line status handler. */
+ /* receive interrupt handler:*/
+ mss_uart_irq_handler_t rx_handler; /*!< Pointer to user registered receiver handler. */
+ /* transmit interrupt handler:*/
+ mss_uart_irq_handler_t tx_handler; /*!< Pointer to user registered transmit handler. */
+ /* modem status interrupt handler:*/
+ mss_uart_irq_handler_t modemsts_handler; /*!< Pointer to user registered modem status handler. */
+ /* receiver timeout interrupt handler */
+ mss_uart_irq_handler_t rto_handler; /*!< Pointer to user registered receiver timeout handler. */
+ /* NACK interrupt handler */
+ mss_uart_irq_handler_t nack_handler; /*!< Pointer to user registered NACK handler. */
+ /* PID parity prror interrup handler */
+ mss_uart_irq_handler_t pid_pei_handler; /*!< Pointer to user registered PID parity error handler. */
+ /* LIN break interrupt handler */
+ mss_uart_irq_handler_t break_handler; /*!< Pointer to user registered LIN break handler. */
+ /* LIN sync detection interrupt handler */
+ mss_uart_irq_handler_t sync_handler; /*!< Pointer to user registered LIN sync dectection handler. */
+ This instance of mss_uart_instance_t holds all data related to the operations
+ performed by UART0. The function MSS_UART_init() initializes this structure.
+ A pointer to g_mss_uart0 is passed as the first parameter to MSS UART driver
+ functions to indicate that UART0 should perform the requested operation.
+extern mss_uart_instance_t g_mss_uart0;
+ performed by UART1. The function MSS_UART_init() initializes this structure.
+ A pointer to g_mss_uart1 is passed as the first parameter to MSS UART driver
+ functions to indicate that UART1 should perform the requested operation.
+extern mss_uart_instance_t g_mss_uart1;
+ The MSS_UART_init() function initializes and configures one of the SmartFusion2
+ MSS UARTs with the configuration passed as a parameter. The configuration
+ parameters are the baud_rate which is used to generate the baud value and the
+ line_config which is used to specify the line configuration (bit length,
+ stop bits and parity).
+ @param this_uart
+ The this_uart parameter is a pointer to an mss_uart_instance_t structure
+ identifying the MSS UART hardware block to be initialized. There are two
+ such data structures, g_mss_uart0 and g_mss_uart1, associated with MSS
+ UART0 and MSS UART1 respectively. This parameter must point to either
+ the g_mss_uart0 or g_mss_uart1 global data structure defined within
+ the UART driver..
+ @param baud_rate
+ The baud_rate parameter specifies the baud rate. It can be specified for
+ common baud rates’ using the following defines:
+ • MSS_UART_110_BAUD
+ • MSS_UART_300_BAUD
+ • MSS_UART_1200_BAUD
+ • MSS_UART_2400_BAUD
+ • MSS_UART_4800_BAUD
+ • MSS_UART_9600_BAUD
+ • MSS_UART_19200_BAUD
+ • MSS_UART_38400_BAUD
+ • MSS_UART_57600_BAUD
+ • MSS_UART_115200_BAUD
+ • MSS_UART_230400_BAUD
+ • MSS_UART_460800_BAUD
+ • MSS_UART_921600_BAUD
+ Alternatively, any nonstandard baud rate can be specified by simply passing
+ the actual required baud rate as the value for this parameter.
+ @param line_config
+ The line_config parameter is the line configuration specifying the bit length,
+ number of stop bits and parity settings. This is a bitwise OR of one value
+ from each of the following groups of allowed values:
+ • One of the following to specify the transmit/receive data bit length:
+ MSS_UART_DATA_5_BITS
+ MSS_UART_DATA_6_BITS,
+ MSS_UART_DATA_7_BITS
+ MSS_UART_DATA_8_BITS
+ • One of the following to specify the parity setting:
+ MSS_UART_NO_PARITY
+ MSS_UART_EVEN_PARITY
+ MSS_UART_ODD_PARITY
+ MSS_UART_STICK_PARITY_0
+ MSS_UART_STICK_PARITY_1
+ • One of the following to specify the number of stop bits:
+ MSS_UART_ONE_STOP_BIT
+ MSS_UART_ONEHALF_STOP_BIT
+ MSS_UART_TWO_STOP_BITS
+ #include "mss_uart.h"
+ int main(void)
+ MSS_UART_init(&g_mss_uart0,
+ MSS_UART_57600_BAUD,
+ MSS_UART_DATA_8_BITS | MSS_UART_NO_PARITY | MSS_UART_ONE_STOP_BIT);
+ return(0);
+ The MSS_UART_lin_init() function is used to initialize the MSS UART for
+ LIN mode of operation. The configuration parameters are the baud_rate which is
+ used to generate the baud value and the line_config which is used to specify
+ the line configuration (bit length, stop bits and parity).
+ The this_uart parameter is a pointer to an mss_uart_instance_t
+ structure identifying the MSS UART hardware block that will perform
+ the requested function. There are two such data structures,
+ g_mss_uart0 and g_mss_uart1, associated with MSS UART0 and MSS UART1.
+ This parameter must point to either the g_mss_uart0 or g_mss_uart1
+ global data structure defined within the UART driver.
+ MSS_UART_lin_init(&g_mss_uart0,
+MSS_UART_lin_init
+ The MSS_UART_irda_init() function is used to initialize the MSS UART instance
+ referenced by the parameter this_uart for IrDA mode of operation. This
+ function must be called before calling any other IrDA functionality specific
+ MSS_UART_irda_init(&g_mss_uart0,
+ MSS_UART_DATA_8_BITS | MSS_UART_NO_PARITY | MSS_UART_ONE_STOP_BIT,
+ MSS_UART_ACTIVE_LOW,
+ MSS_UART_3_BY_16);
+ The MSS_UART_smartcard_init() function is used to initialize the MSS UART
+ for ISO 7816 (smartcard) mode of operation. The configuration parameters are
+ the baud_rate which is used to generate the baud value and the line_config
+ which is used to specify the line configuration (bit length, stop bits and parity).
+ This function disables all other modes of the MSS UART instance pointed by
+ the parameter this_uart.
+ MSS_UART_smartcard_init(&g_mss_uart0,
+ The function MSS_UART_polled_tx() is used to transmit data. It transfers the
+ contents of the transmitter data buffer, passed as a function parameter, into
+ the UART’s hardware transmitter FIFO. It returns when the full content of the
+ transmit data buffer has been transferred to the UART’s transmit FIFO. It is
+ safe to release or reuse the memory used as the transmitter data buffer once
+ this function returns.
+ Note: This function reads the UART’s line status register (LSR) to poll
+ for the active state of the transmitter holding register empty (THRE) bit
+ before transferring data from the data buffer to the transmitter FIFO. It
+ transfers data to the transmitter FIFO in blocks of 16 bytes or less and
+ allows the FIFO to empty before transferring the next block of data.
+ Note: The actual transmission over the serial connection will still be
+ in progress when this function returns. Use the MSS_UART_get_tx_status()
+ function if you need to know when the transmitter is empty.
+ @param pbuff
+ The pbuff parameter is a pointer to a buffer containing the data to
+ be transmitted.
+ @param tx_size
+ The tx_size parameter specifies the size, in bytes, of the data to
+ uint8_t message[12] = "Hello World";
+ MSS_UART_polled_tx(&g_mss_uart0, message, sizeof(message));
+ The function MSS_UART_polled_tx_string() is used to transmit a NULL ('\0')
+ terminated string. It transfers the text string, from the buffer starting at
+ the address pointed to by p_sz_string into the UART’s hardware transmitter
+ FIFO. It returns when the complete string has been transferred to the UART's
+ transmit FIFO. It is safe to release or reuse the memory used as the string
+ buffer once this function returns.
+ @param p_sz_string
+ The p_sz_string parameter is a pointer to a buffer containing the NULL
+ ('\0') terminated string to be transmitted.
+ MSS_UART_polled_tx_string(&g_mss_uart0, message);
+ The function MSS_UART_irq_tx() is used to initiate an interrupt-driven
+ transmit. It returns immediately after making a note of the transmit buffer
+ location and enabling transmit interrupts both at the UART and Cortex-M3 NVIC
+ level. This function takes a pointer via the pbuff parameter to a memory
+ buffer containing the data to transmit. The memory buffer specified through
+ this pointer must remain allocated and contain the data to transmit until
+ the transmit completion has been detected through calls to function
+ MSS_UART_tx_complete(). The actual transmission over the serial connection
+ is still in progress until calls to the MSS_UART_tx_complete() function
+ indicate transmit completion.
+ Note: The MSS_UART_irq_tx() function enables both the transmit holding
+ register empty (THRE) interrupt in the UART and the MSS UART instance
+ interrupt in the Cortex-M3 NVIC as part of its implementation.
+ Note: The MSS_UART_irq_tx() function assigns an internal default transmit
+ interrupt handler function to the UART’s THRE interrupt. This interrupt
+ handler overrides any custom interrupt handler that you may have previously
+ registered using the MSS_UART_set_tx_handler() function.
+ Note: The MSS_UART_irq_tx() function’s default transmit interrupt
+ handler disables the UART’s THRE interrupt when all of the data has
+ been transferred to the UART's transmit FIFO.
+ The pbuff parameter is a pointer to a buffer containing the data
+ to be transmitted.
+ The tx_size parameter specifies the size, in bytes, of the data
+ uint8_t tx_buff[10] = "abcdefghi";
+ MSS_UART_irq_tx(&g_mss_uart0, tx_buff, sizeof(tx_buff));
+ while(0 == MSS_UART_tx_complete(&g_mss_uart0))
+ The MSS_UART_tx_complete() function is used to find out if the interrupt-driven
+ transmit previously initiated through a call to MSS_UART_irq_tx() is complete.
+ This is typically used to find out when it is safe to reuse or release the
+ memory buffer holding transmit data.
+ Note: The transfer of all of the data from the memory buffer to the UART’s
+ transmit FIFO and the actual transmission over the serial connection are both
+ complete when a call to the MSS_UART_tx_complete() function indicates transmit
+ completion.
+ This function return a non-zero value if transmit has completed, otherwise
+ it returns zero.
+ See the MSS_UART_irq_tx() function for an example that uses the
+ MSS_UART_tx_complete() function.
+ The MSS_UART_get_rx() function reads the content of the UART receiver’s FIFO
+ and stores it in the receive buffer that is passed via the rx_buff function
+ parameter. It copies either the full contents of the FIFO into the receive
+ buffer, or just enough data from the FIFO to fill the receive buffer,
+ dependent upon the size of the receive buffer passed by the buff_size
+ parameter. The MSS_UART_get_rx() function returns the number of bytes copied
+ into the receive buffer .This function is non-blocking and will return 0
+ immediately if no data has been received.
+ Note: The MSS_UART_get_rx() function reads and accumulates the receiver
+ status of the MSS UART instance before reading each byte from the receiver's
+ data register/FIFO. This allows the driver to maintain a sticky record of any
+ receiver errors that occur as the UART receives each data byte; receiver
+ errors would otherwise be lost after each read from the receiver's data register.
+ A call to the MSS_UART_get_rx_status() function returns any receiver errors
+ accumulated during the execution of the MSS_UART_get_rx() function.
+ Note: If you need to read the error status for each byte received, set
+ the buff_size to 1 and read the receive line error status for each byte
+ using the MSS_UART_get_rx_status() function.
+ The MSS_UART_get_rx() function can be used in polled mode, where it is called
+ at regular intervals to find out if any data has been received, or in interrupt
+ driven-mode, where it is called as part of a receive handler that is called
+ by the driver as a result of data being received.
+ Note: In interrupt driven mode you should call the MSS_UART_get_rx()
+ function as part of the receive handler function that you register with
+ the MSS UART driver through a call to MSS_UART_set_rx_handler().
+ @param rx_buff
+ The rx_buff parameter is a pointer to a buffer where the received
+ data is copied.
+ @param buff_size
+ The buff_size parameter specifies the size of the receive buffer in bytes.
+ This function returns the number of bytes that were copied into the
+ rx_buff buffer. It returns 0 if no data has been received.
+ Polled mode example:
+ int main( void )
+ uint8_t rx_buff[RX_BUFF_SIZE];
+ uint32_t rx_idx = 0;
+ while(1)
+ rx_size = MSS_UART_get_rx(&g_mss_uart0, rx_buff, sizeof(rx_buff));
+ if(rx_size > 0)
+ process_rx_data(rx_buff, rx_size);
+ task_a();
+ task_b();
+ Interrupt driven example:
+ MSS_UART_init(&g_mss_uart1,
+ MSS_UART_set_rx_handler(&g_mss_uart1,
+ uart1_rx_handler,
+ MSS_UART_FIFO_SINGLE_BYTE);
+ void uart1_rx_handler(mss_uart_instance_t * this_uart)
+ rx_size = MSS_UART_get_rx(this_uart, rx_buff, sizeof(rx_buff));
+ The MSS_UART_set_rx_handler() function is used to register a receive handler
+ function that is called by the driver when a UART receive data available (RDA)
+ interrupt occurs. You must create and register the receive handler function
+ to suit your application and it must include a call to the MSS_UART_get_rx()
+ Note: The MSS_UART_set_rx_handler() function enables both the RDA
+ interrupt in the UART and the MSS UART instance interrupt in the Cortex-M3
+ NVIC as part
+ of its implementation.
+ Note: You can disable the RDA interrupt once the data is received by
+ calling the MSS_UART_disable_irq() function. This is your choice and is
+ dependent upon your application.
+ @param handler
+ The handler parameter is a pointer to a receive interrupt handler function
+ provided by your application that will be called as a result of a UART RDA
+ interrupt. This handler function must be of type mss_uart_irq_handler_t.
+ @param trigger_level
+ The trigger_level parameter is the receive FIFO trigger level. This
+ specifies the number of bytes that must be received before the UART
+ triggers an RDA interrupt.
+ #define RX_BUFF_SIZE 64
+ uint8_t g_rx_buff[RX_BUFF_SIZE];
+ void uart0_rx_handler(mss_uart_instance_t * this_uart)
+ MSS_UART_get_rx(this_uart, &g_rx_buff[g_rx_idx], sizeof(g_rx_buff));
+ MSS_UART_set_rx_handler(&g_mss_uart0,
+ uart0_rx_handler,
+ The MSS_UART_set_loopback() function is used to locally loopback the Tx and
+ Rx lines of a UART. This is not to be confused with the loopback of UART0
+ to UART1, which can be achieved through the microcontroller subsystem’s
+ system registers.
+ @param loopback
+ The loopback parameter indicates whether or not the UART’s transmit
+ and receive lines should be looped back. Allowed values are as follows:
+ - MSS_UART_LOCAL_LOOPBACK_ON
+ - MSS_UART_LOCAL_LOOPBACK_OFF
+ - MSS_UART_REMOTE_LOOPBACK_ON
+ - MSS_UART_REMOTE_LOOPBACK_OFF
+ - MSS_UART_AUTO_ECHO_ON
+ - MSS_UART_AUTO_ECHO_OFF
+ MSS_UART_set_loopback(&g_mss_uart0, MSS_UART_LOCAL_LOOPBACK_OFF);
+ The MSS_UART_enable_irq() function enables the MSS UART interrupts specified
+ by the irq_mask parameter. The irq_mask parameter identifies the MSS UART
+ interrupts by bit position, as defined in the interrupt enable register (IER)
+ of MSS UART. The MSS UART interrupts and their identifying irq_mask bit
+ positions are as follows:
+ When an irq_mask bit position is set to 1, this function enables the
+ corresponding MSS UART interrupt in the IER register. When an irq_mask bit
+ position is set to 0, the corresponding interrupt’s state remains unchanged in
+ the IER register.
+ Note: The MSS_UART_enable_irq() function also enables the MSS UART instance
+ interrupt in the Cortex-M3 NVIC.
+ identifying the MSS UART hardware block that will perform the requested
+ function. There are two such data structures, g_mss_uart0 and g_mss_uart1,
+ associated with MSS UART0 and MSS UART1. This parameter must point to either
+ the g_mss_uart0 or g_mss_uart1 global data structure defined within the UART
+ @param irq_mask
+ The irq_mask parameter is used to select which of the MSS UART’s interrupts
+ you want to enable. The allowed value for the irq_mask parameter is one of
+ the following constants or a bitwise OR of more than one:
+ - MSS_UART_RBF_IRQ (bit mask = 0x001)
+ - MSS_UART_TBE_IRQ (bit mask = 0x002)
+ - MSS_UART_LS_IRQ (bit mask = 0x004)
+ - MSS_UART_MS_IRQ (bit mask = 0x008)
+ - MSS_UART_RTO_IRQ (bit mask = 0x010)
+ - MSS_UART_NACK_IRQ (bit mask = 0x020)
+ - MSS_UART_PIDPE_IRQ (bit mask = 0x040)
+ - MSS_UART_LINB_IRQ (bit mask = 0x080)
+ - MSS_UART_LINS_IRQ (bit mask = 0x100)
+ MSS_UART_enable_irq(&g_mss_uart0,(MSS_UART_RBF_IRQ | MSS_UART_TBE_IRQ));
+ The MSS_UART_disable_irq() function disables the MSS UART interrupts specified
+ of MSS UART. The MSS UART interrupts and their identifying bit positions are
+ as follows:
+ When an irq_mask bit position is set to 1, this function disables the
+ Note: If you disable all four of the UART’s interrupts, the
+ MSS_UART_disable_irq() function also disables the MSS UART instance
+ you want to disable. The allowed value for the irq_mask parameter is one of
+ MSS_UART_disable_irq(&g_mss_uart0, (MSS_UART_RBF_IRQ | MSS_UART_TBE_IRQ));
+ The MSS_UART_set_pidpei_handler() function is used assign a custom interrupt
+ handler for the PIDPEI (PID parity error interrupt) when the MSS UART is
+ operating in LIN mode.
+ The handler parameter is the pointer to the custom handler function.
+ This parameter is of type mss_uart_irq_handler_t.
+ MSS_UART_ set_pidpei_handler(&g_mss_uart0, my_pidpei_handler);
+ The MSS_UART_set_linbreak_handler () function is used assign a custom
+ interrupt handler for the LIN Break detection interrupt when the MSS UART
+ is operating in LIN mode.
+ MSS_UART_set_linbreak_handler(&g_mss_uart0, my_break_handler);
+ The MSS_UART_set_linsync_handler() function is used assign a custom interrupt
+ handler for the LIN Sync character detection interrupt when the MSS UART
+ MSS_UART_set_linsync_handler(&g_mss_uart0, my_linsync_handler);
+ The MSS_UART_set_nack_handler() function is used assign a custom interrupt
+ handler for the NACK character detection interrupt when the MSS UART
+ is operating in Smartcard mode.
+ MSS_UART_set_nack_handler(&g_mss_uart0, my_nack_handler);
+ The MSS_UART_set_rx_timeout_handler() function is used assign a custom
+ interrupt handler for the receiver timeout interrupt when the MSS UART is
+ operating in mode. It finds application in IrDA mode of operation.
+ MSS_UART_set_rx_timeout_handler(&g_mss_uart0, my_rxtimeout_handler);
+ The MSS_UART_set_rxstatus_handler() function is used to register a receiver
+ status handler function that is called by the driver when a UART receiver
+ line status (RLS) interrupt occurs. You must create and register the handler
+ function to suit your application.
+ Note: The MSS_UART_set_rxstatus_handler() function enables both the RLS
+ NVIC as part of its implementation.
+ Note: You can disable the RLS interrupt when required by calling the
+ MSS_UART_disable_irq() function. This is your choice and is dependent upon
+ your application.
+ The handler parameter is a pointer to a receiver line status interrupt
+ handler function provided by your application that will be called as a
+ result of a UART RLS interrupt. This handler function must be of type
+ mss_uart_irq_handler_t.
+ void uart_rxsts_handler(mss_uart_instance_t * this_uart)
+ status = MSS_UART_get_rx_status(this_uart);
+ if(status & MSS_UART_OVERUN_ERROR)
+ discard_rx_data();
+ MSS_UART_init( &g_mss_uart0,
+ MSS_UART_DATA_8_BITS | MSS_UART_NO_PARITY |
+ MSS_UART_ONE_STOP_BIT );
+ MSS_UART_set_rxstatus_handler(&g_mss_uart0, uart_rxsts_handler);
+ The MSS_UART_set_tx_handler() function is used to register a transmit handler
+ function that is called by the driver when a UART transmit holding register
+ empty (THRE) interrupt occurs. You must create and register the transmit
+ handler function to suit your application. You can use the
+ MSS_UART_fill_tx_fifo() function in your transmit handler function to
+ write data to the transmitter.
+ Note: The MSS_UART_set_tx_handler() function enables both the THRE
+ Note: You can disable the THRE interrupt when required by calling the
+ Note: The MSS_UART_irq_tx() function does not use the transmit handler
+ function that you register with the MSS_UART_set_tx_handler() function.
+ It uses its own internal THRE interrupt handler function that overrides
+ any custom interrupt handler that you register using the
+ MSS_UART_set_tx_handler() function.
+ The handler parameter is a pointer to a transmit interrupt handler
+ function provided by your application that will be called as a result
+ of a UART THRE interrupt. This handler function must be of type
+ uint8_t * g_tx_buffer;
+ size_t g_tx_size = 0;
+ void uart_tx_handler(mss_uart_instance_t * this_uart)
+ size_t size_in_fifo;
+ size_in_fifo = MSS_UART_fill_tx_fifo(this_uart,
+ (const uint8_t *)g_tx_buffer,
+ g_tx_size);
+ if(size_in_fifo == g_tx_size)
+ g_tx_size = 0;
+ MSS_UART_disable_irq(this_uart, MSS_UART_TBE_IRQ);
+ g_tx_buffer = &g_tx_buffer[size_in_fifo];
+ g_tx_size = g_tx_size - size_in_fifo;
+ uint8_t message[12] = "Hello world";
+ MSS_UART_ONE_STOP_BIT);
+ g_tx_buffer = message;
+ g_tx_size = sizeof(message);
+ MSS_UART_set_tx_handler(&g_mss_uart0, uart_tx_handler);
+ The MSS_UART_set_modemstatus_handler() function is used to register a modem
+ status handler function that is called by the driver when a UART modem status
+ (MS) interrupt occurs. You must create and register the handler function to
+ suit your application.
+ Note: The MSS_UART_set_modemstatus_handler() function enables both the MS
+ interrupt in the UART and the MSS UART instance interrupt in the Cortex-M3 NVIC
+ as part of its implementation.
+ Note: You can disable the MS interrupt when required by calling the
+ MSS_UART_disable_irq() function. This is your choice and is dependent
+ upon your application.
+ The handler parameter is a pointer to a modem status interrupt handler
+ of a UART MS interrupt. This handler function must be of type
+ void uart_modem_handler(mss_uart_instance_t * this_uart)
+ status = MSS_UART_get_modem_status(this_uart);
+ if(status & MSS_UART_CTS)
+ uart_cts_handler();
+ MSS_UART_set_modemstatus_handler(&g_mss_uart0, uart_modem_handler);
+ The MSS_UART_fill_tx_fifo() function fills the UART's hardware transmitter
+ FIFO with the data found in the transmitter buffer that is passed via the
+ tx_buffer function parameter. If the transmitter FIFO is not empty when
+ the function is called, the function returns immediately without transferring
+ any data to the FIFO; otherwise, the function transfers data from the
+ transmitter buffer to the FIFO until it is full or until the complete
+ contents of the transmitter buffer have been copied into the FIFO. The
+ function returns the number of bytes copied into the UART's transmitter FIFO.
+ Note: This function reads the UART’s line status register (LSR) to check
+ before transferring data from the data buffer to the transmitter FIFO. If
+ THRE is 0, the function returns immediately, without transferring any data
+ to the FIFO. If THRE is 1, the function transfers up to 16 bytes of data
+ to the FIFO and then returns.
+ @param tx_buffer
+ The tx_buffer parameter is a pointer to a buffer containing the data
+ The tx_size parameter is the size in bytes, of the data to be transmitted.
+ This function returns the number of bytes copied into the UART's
+ transmitter FIFO.
+ void send_using_interrupt(uint8_t * pbuff, size_t tx_size)
+ size_in_fifo = MSS_UART_fill_tx_fifo(&g_mss_uart0, pbuff, tx_size);
+ The MSS_UART_get_rx_status() function returns the receiver error status of the
+ MSS UART instance. It reads both the current error status of the receiver from
+ the UART’s line status register (LSR) and the accumulated error status from
+ preceding calls to the MSS_UART_get_rx() function, and it combines them using
+ a bitwise OR. It returns the cumulative overrun, parity, framing, break and
+ FIFO error status of the receiver, since the previous call to
+ MSS_UART_get_rx_status(), as an 8-bit encoded value.
+ status of the MSS UART instance before reading each byte from the receiver’s
+ data register/FIFO. The driver maintains a sticky record of the cumulative
+ receiver error status, which persists after the MSS_UART_get_rx() function
+ returns. The MSS_UART_get_rx_status() function clears the driver’s sticky
+ receiver error record before returning.
+ Note: The driver’s transmit functions also read the line status
+ register (LSR) as part of their implementation. When the driver reads the
+ LSR, the UART clears any active receiver error bits in the LSR. This could
+ result in the driver losing receiver errors. To avoid any loss of receiver
+ errors, the transmit functions also update the driver’s sticky record of the
+ cumulative receiver error status whenever they read the LSR.
+ This function returns the UART’s receiver error status as an 8-bit unsigned
+ integer. The returned value is 0 if no receiver errors occurred. The driver
+ provides a set of bit mask constants that should be compared with and/or
+ used to mask the returned value to determine the receiver error status.
+ When the return value is compared to the following bit masks, a non-zero
+ result indicates that the corresponding error occurred:
+ • MSS_UART_OVERRUN_ERROR (bit mask = 0x02)
+ • MSS_UART_PARITY_ERROR (bit mask = 0x04)
+ • MSS_UART_FRAMING_ERROR (bit mask = 0x08)
+ • MSS_UART_BREAK_ERROR (bit mask = 0x10)
+ • MSS_UART_FIFO_ERROR (bit mask = 0x80)
+ When the return value is compared to the following bit mask, a non-zero
+ result indicates that no error occurred:
+ • MSS_UART_NO_ERROR (bit mask = 0x00)
+ Upon unsuccessful execution, this function returns:
+ • MSS_UART_INVALID_PARAM (bit mask = 0xFF)
+ uint8_t rx_data[MAX_RX_DATA_SIZE];
+ err_status = MSS_UART_get_rx_status(&g_mss_uart0);
+ rx_size = MSS_UART_get_rx(&g_mss_uart0, rx_data, MAX_RX_DATA_SIZE);
+ The MSS_UART_get_modem_status() function returns the modem status of the
+ MSS UART instance. It reads the modem status register (MSR) and returns
+ the 8 bit value. The bit encoding of the returned value is exactly the
+ same as the definition of the bits in the MSR.
+ This function returns current state of the UART's MSR as an 8 bit
+ unsigned integer. The driver provides the following set of bit mask
+ constants that should be compared with and/or used to mask the
+ returned value to determine the modem status:
+ • MSS_UART_DCTS (bit mask = 0x01)
+ • MSS_UART_DDSR (bit mask = 0x02)
+ • MSS_UART_TERI (bit mask = 0x04)
+ • MSS_UART_DDCD (bit mask = 0x08)
+ • MSS_UART_CTS (bit mask = 0x10)
+ • MSS_UART_DSR (bit mask = 0x20)
+ • MSS_UART_RI (bit mask = 0x40)
+ • MSS_UART_DCD (bit mask = 0x80)
+ void uart_modem_status_isr(mss_uart_instance_t * this_uart)
+ if( status & MSS_UART_DCTS )
+ uart_dcts_handler();
+ if( status & MSS_UART_CTS )
+ The MSS_UART_get_tx_status() function returns the transmitter status of the
+ MSS UART instance. It reads both the UART’s line status register (LSR) and
+ returns the status of the transmit holding register empty (THRE) and
+ transmitter empty (TEMT) bits.*
+ This function returns the UART’s transmitter status as an 8-bit unsigned
+ integer. The returned value is 0 if the transmitter status bits are not
+ set or the function execution failed. The driver provides a set of bit
+ mask constants that should be compared with and/or used to mask the
+ returned value to determine the transmitter status.
+ result indicates that the corresponding transmitter status bit is set:
+ • MSS_UART_THRE (bit mask = 0x20)
+ • MSS_UART_TEMT (bit mask = 0x40)
+ result indicates that the transmitter is busy or the function execution
+ failed.
+ • MSS_UART_TX_BUSY (bit mask = 0x00)
+ MSS_UART_polled_tx(&g_mss_uart0, tx_buff, sizeof(tx_buff));
+ while(!(MSS_UART_TEMT & MSS_UART_get_tx_status(&g_mss_uart0)))
+ The MSS_UART_set_break() function is used to send the break
+ (9 zeros after stop bit) signal on the TX line. This function can be used
+ only when the MSS UART is initialized in LIN mode by using MSS_UART_lin_init().
+ MSS_UART_set_break(&g_mss_uart0);
+ The MSS_UART_clear_break() function is used to remove the break signal on the
+ TX line. This function can be used only when the MSS UART is initialized in
+ LIN mode by using MSS_UART_lin_init().
+ MSS_UART_clear_break(&g_mss_uart0);
+ The MSS_UART_enable_half_duplex() function is used to enable the half-duplex
+ (single wire) mode for the MSS UART. Though it finds application in Smartcard
+ mode, half-duplex mode can be used in other modes as well.
+ MSS_UART_enable_half_duplex(&g_mss_uart0);
+ The MSS_UART_disable_half_duplex() function is used to disable the half-duplex
+ MSS_UART_disable_half_duplex(&g_mss_uart0);
+ The MSS_UART_set_rx_endian() function is used to configure the LSB first or
+ MSB first setting for MSS UART receiver
+ @param endian
+ The endian parameter tells the LSB first or MSB first configuration.
+ This parameter is of type mss_uart_endian_t.
+ MSS_UART_set_rx_endian(&g_mss_uart0, MSS_UART_LITTLEEND);
+ The MSS_UART_set_tx_endian() function is used to configure the LSB first or
+ MSB first setting for MSS UART transmitter.
+ MSS_UART_set_tx_endian(&g_mss_uart0, MSS_UART_LITTLEEND);
+ The MSS_UART_set_filter_length () function is used to configure the glitch
+ filter length of the MSS UART. This should be configured in accordance with
+ the chosen baud rate.
+ @param length
+ The length parameter is of mss_uart_filter_length_t type that determines
+ the length of the glitch filter.
+ MSS_UART_set_filter_length(&g_mss_uart0, MSS_UART_LEN2);
+ The MSS_UART_enable_afm() function is used to enable address flag detection
+ mode of the MSS UART
+ MSS_UART_enable_afm(&g_mss_uart0);
+ The MSS_UART_disable_afm() function is used to disable address flag detection
+ mode of the MSS UART.
+ MSS_UART_disable_afm(&g_mss_uart0);
+ The MSS_UART_enable_afclear () function is used to enable address flag clear
+ of the MSS UART. This should be used in conjunction with address flag
+ detection mode (AFM).
+ MSS_UART_enable_afclear(&g_mss_uart0);
+ The MSS_UART_disable_afclear () function is used to disable address flag
+ clear of the MSS UART. This should be used in conjunction with address flag
+ MSS_UART_disable_afclear(&g_mss_uart0);
+ The MSS_UART_enable_rx_timeout() function is used to enable and configure
+ the receiver timeout functionality of MSS UART. This function accepts the
+ timeout parameter and applies the timeout based up on the baud rate as per
+ the formula 4 x timeout x bit time.
+ @param timeout
+ The timeout parameter specifies the receiver timeout multiple.
+ It should be configured according to the baud rate in use.
+ MSS_UART_enable_rx_timeout(&g_mss_uart0 , 24);
+ The MSS_UART_disable_rx_timeout() function is used to disable the receiver
+ timeout functionality of MSS UART.
+ MSS_UART_disable_rx_timeout(&g_mss_uart0);
+ The MSS_UART_enable_tx_time_guard() function is used to enable and configure
+ the transmitter time guard functionality of MSS UART. This function accepts
+ the timeguard parameter and applies the timeguard based up on the baud rate
+ as per the formula timeguard x bit time.
+ MSS_UART_enable_tx_time_guard(&g_mss_uart0 , 24);
+ The MSS_UART_disable_tx_time_guard() function is used to disable the
+ transmitter time guard functionality of MSS UART.
+ MSS_UART_disable_tx_time_guard(&g_mss_uart0);
+ The MSS_UART_set_address() function is used to set the 8-bit address for
+ the MSS UART referenced by this_uart parameter.
+ @param address
+ The address parameter is the 8-bit address which is to be configured
+ to the MSS UART referenced by this_uart parameter.
+ MSS_UART_set_address(&g_mss_uart0, 0xAA);
+ The MSS_UART_set_ready_mode() function is used to configure the MODE0 or MODE1
+ to the TXRDY and RXRDY signals of the MSS UART referenced by this_uart
+ parameter. The mode parameter is used to provide the mode to be configured.
+ @param mode
+ The mode parameter is the mss_uart_ready_mode_t type which is used to
+ configure the TXRDY and RXRDY signal modes.
+ MSS_UART_set_ready_mode(&g_mss_uart0, MSS_UART_READY_MODE0);
+ The MSS_UART_set_usart_mode() function is used to configure the MSS UART
+ referenced by the parameter this_uart in USART mode. Various USART modes
+ are supported which can be configured by the parameter mode of type
+ mss_uart_usart_mode_t.
+ The mode parameter is the USART mode to be configured.
+ This parameter is of type mss_uart_usart_mode_t.
+ MSS_UART_set_usart_mode(&g_mss_uart0, MSS_UART_SYNC_MASTER_POS_EDGE_CLK);
+#endif /* __MSS_UART_H_ */
@@ -0,0 +1,83 @@
+ * Register bit offsets and masks defintions for SmartFusion2 MSS MMUART.
+#ifndef MSS_UART_REGS_H_
+#define MSS_UART_REGS_H_
+ Register Bit definitions
+/* Line Control register bit definitions */
+#define SB 6u /* Set break */
+#define DLAB 7u /* Divisor latch access bit */
+/* FIFO Control register bit definitions */
+#define RXRDY_TXRDYN_EN 0u /* Enable TXRDY and RXRDY signals */
+#define CLEAR_RX_FIFO 1u /* Clear receiver FIFO */
+#define CLEAR_TX_FIFO 2u /* Clear transimtter FIFO */
+#define RDYMODE 3u /* Mode 0 or Mode 1 for TXRDY and RXRDY */
+/* Modem Control register bit definitions */
+#define LOOP 4u /* Local loopback */
+#define RLOOP 5u /* Remote loopback */
+#define ECHO 6u /* Automatic echo */
+#define RLOOP_MASK 0x6u /* Remote loopback & Automatic echo*/
+/* Line Status register bit definitions */
+#define DR 0u /* Data ready */
+#define THRE 5u /* Transmitter holding register empty */
+#define TEMT 6u /* Transitter empty */
+/* Interrupt Enable register bit definitions */
+#define ERBFI 0u /* Enable receiver buffer full interrupt */
+#define ETBEI 1u /* Enable transmitter buffer empty interrupt */
+#define ELSI 2u /* Enable line status interrupt */
+#define EDSSI 3u /* Enable modem status interrupt */
+/* Multimode register 0 bit definitions */
+#define ELIN 3u /* Enable LIN header detection */
+#define ETTG 5u /* Enable transmitter time guard */
+#define ERTO 6u /* Enable receiver time-out */
+#define EFBR 7u /* Enable fractional baud rate mode */
+/* Multimode register 1 bit definitions */
+#define E_MSB_RX 0u /* MSB / LSB first for receiver */
+#define E_MSB_TX 1u /* MSB / LSB first for transmitter */
+#define EIRD 2u /* Enable IrDA modem */
+#define EIRX 3u /* Input polarity for IrDA modem */
+#define EITX 4u /* Output polarity for IrDA modem */
+#define EITP 5u /* Output pulse width for IrDA modem */
+/* Multimode register 2 bit definitions */
+#define EERR 0u /* Enable ERR / NACK during stop time */
+#define EAFM 1u /* Enable 9-bit address flag mode */
+#define EAFC 2u /* Enable address flag clear */
+#define ESWM 3u /* Enable single wire half-duplex mode */
+/* Multimode Interrupt Enable register and
+ Multimode Interrupt Identification register definitions */
+#define ERTOI 0u /* Enable receiver timeout interrupt */
+#define ENACKI 1u /* Enable NACK / ERR interrupt */
+#define EPID_PEI 2u /* Enable PID parity error interrupt */
+#define ELINBI 3u /* Enable LIN break interrupt */
+#define ELINSI 4u /* Enable LIN sync detection interrupt */
+#endif /* MSS_UART_REGS_H_ */
@@ -0,0 +1,385 @@
+ * Smartfusion2 system configuration. This file is automatically generated
+ * by the Libero tools. It contains the Smartfusion2 system configuration that
+ * was selected during the hardware configuration flow.
+#include "../../CMSIS/sys_init_cfg_types.h"
+ * !!! WARNING !!!
+ *==============================================================================
+ * The project including this file must be linked so that the content of this
+ * file is located in internal eNVM at run time. The content of this file is
+ * used to configure the system prior to RAM content initialization. This means
+ * that the content of the data structures below will be used before the copy
+ * from LMA to VMA takes place. The LMA and VMA locations of the content of this
+ * file must be identical for the system to be seamlessly configured as part of
+ * the CMSIS boot process.
+ * Clock configuration
+/* No configuration data structure required. */
+ * Memory remapping configuration
+/* TBD. */
+#include "sys_config_mddr_define.h"
+MDDR_TypeDef * const g_m2s_mddr_addr = (MDDR_TypeDef *)0x40020800;
+const ddr_subsys_cfg_t g_m2s_mddr_subsys_config =
+ /*---------------------------------------------------------------------
+ MDDR_DDRC_DYN_SOFT_RESET_CR,
+ MDDR_DDRC_RESERVED0,
+ MDDR_DDRC_DYN_REFRESH_1_CR,
+ MDDR_DDRC_DYN_REFRESH_2_CR,
+ MDDR_DDRC_DYN_POWERDOWN_CR,
+ MDDR_DDRC_DYN_DEBUG_CR,
+ MDDR_DDRC_MODE_CR,
+ MDDR_DDRC_ADDR_MAP_BANK_CR,
+ MDDR_DDRC_ECC_DATA_MASK_CR,
+ MDDR_DDRC_ADDR_MAP_COL_1_CR,
+ MDDR_DDRC_ADDR_MAP_COL_2_CR,
+ MDDR_DDRC_ADDR_MAP_ROW_1_CR,
+ MDDR_DDRC_ADDR_MAP_ROW_2_CR,
+ MDDR_DDRC_INIT_1_CR,
+ MDDR_DDRC_CKE_RSTN_CYCLES_1_CR,
+ MDDR_DDRC_CKE_RSTN_CYCLES_2_CR,
+ MDDR_DDRC_INIT_MR_CR,
+ MDDR_DDRC_INIT_EMR_CR,
+ MDDR_DDRC_INIT_EMR2_CR,
+ MDDR_DDRC_INIT_EMR3_CR,
+ MDDR_DDRC_DRAM_BANK_TIMING_PARAM_CR,
+ MDDR_DDRC_DRAM_RD_WR_LATENCY_CR,
+ MDDR_DDRC_DRAM_RD_WR_PRE_CR,
+ MDDR_DDRC_DRAM_MR_TIMING_PARAM_CR,
+ MDDR_DDRC_DRAM_RAS_TIMING_CR,
+ MDDR_DDRC_DRAM_RD_WR_TRNARND_TIME_CR,
+ MDDR_DDRC_DRAM_T_PD_CR,
+ MDDR_DDRC_DRAM_BANK_ACT_TIMING_CR,
+ MDDR_DDRC_ODT_PARAM_1_CR,
+ MDDR_DDRC_ODT_PARAM_2_CR,
+ MDDR_DDRC_ADDR_MAP_COL_3_CR,
+ MDDR_DDRC_MODE_REG_RD_WR_CR,
+ MDDR_DDRC_MODE_REG_DATA_CR,
+ MDDR_DDRC_PWR_SAVE_1_CR,
+ MDDR_DDRC_PWR_SAVE_2_CR,
+ MDDR_DDRC_ZQ_LONG_TIME_CR,
+ MDDR_DDRC_ZQ_SHORT_TIME_CR,
+ MDDR_DDRC_ZQ_SHORT_INT_REFRESH_MARGIN_1_CR,
+ MDDR_DDRC_ZQ_SHORT_INT_REFRESH_MARGIN_2_CR,
+ MDDR_DDRC_PERF_PARAM_1_CR,
+ MDDR_DDRC_HPR_QUEUE_PARAM_1_CR,
+ MDDR_DDRC_HPR_QUEUE_PARAM_2_CR,
+ MDDR_DDRC_LPR_QUEUE_PARAM_1_CR,
+ MDDR_DDRC_LPR_QUEUE_PARAM_2_CR,
+ MDDR_DDRC_WR_QUEUE_PARAM_CR,
+ MDDR_DDRC_PERF_PARAM_2_CR,
+ MDDR_DDRC_PERF_PARAM_3_CR,
+ MDDR_DDRC_DFI_RDDATA_EN_CR,
+ MDDR_DDRC_DFI_MIN_CTRLUPD_TIMING_CR,
+ MDDR_DDRC_DFI_MAX_CTRLUPD_TIMING_CR,
+ MDDR_DDRC_DFI_WR_LVL_CONTROL_1_CR,
+ MDDR_DDRC_DFI_WR_LVL_CONTROL_2_CR,
+ MDDR_DDRC_DFI_RD_LVL_CONTROL_1_CR,
+ MDDR_DDRC_DFI_RD_LVL_CONTROL_2_CR,
+ MDDR_DDRC_DFI_CTRLUPD_TIME_INTERVAL_CR,
+ MDDR_DDRC_DYN_SOFT_RESET_ALIAS_CR,
+ MDDR_DDRC_AXI_FABRIC_PRI_ID_CR,
+ MDDR_PHY_LOOPBACK_TEST_CR,
+ MDDR_PHY_BOARD_LOOPBACK_CR,
+ MDDR_PHY_CTRL_SLAVE_RATIO_CR,
+ MDDR_PHY_CTRL_SLAVE_FORCE_CR,
+ MDDR_PHY_CTRL_SLAVE_DELAY_CR,
+ MDDR_PHY_DATA_SLICE_IN_USE_CR,
+ MDDR_PHY_LVL_NUM_OF_DQ0_CR,
+ MDDR_PHY_DQ_OFFSET_1_CR,
+ MDDR_PHY_DQ_OFFSET_2_CR,
+ MDDR_PHY_DQ_OFFSET_3_CR,
+ MDDR_PHY_DIS_CALIB_RST_CR,
+ MDDR_PHY_DLL_LOCK_DIFF_CR,
+ MDDR_PHY_FIFO_WE_IN_DELAY_1_CR,
+ MDDR_PHY_FIFO_WE_IN_DELAY_2_CR,
+ MDDR_PHY_FIFO_WE_IN_DELAY_3_CR,
+ MDDR_PHY_FIFO_WE_IN_FORCE_CR,
+ MDDR_PHY_FIFO_WE_SLAVE_RATIO_1_CR,
+ MDDR_PHY_FIFO_WE_SLAVE_RATIO_2_CR,
+ MDDR_PHY_FIFO_WE_SLAVE_RATIO_3_CR,
+ MDDR_PHY_FIFO_WE_SLAVE_RATIO_4_CR,
+ MDDR_PHY_GATELVL_INIT_MODE_CR,
+ MDDR_PHY_GATELVL_INIT_RATIO_1_CR,
+ MDDR_PHY_GATELVL_INIT_RATIO_2_CR,
+ MDDR_PHY_GATELVL_INIT_RATIO_3_CR,
+ MDDR_PHY_GATELVL_INIT_RATIO_4_CR,
+ MDDR_PHY_LOCAL_ODT_CR,
+ MDDR_PHY_INVERT_CLKOUT_CR,
+ MDDR_PHY_RD_DQS_SLAVE_DELAY_1_CR,
+ MDDR_PHY_RD_DQS_SLAVE_DELAY_2_CR,
+ MDDR_PHY_RD_DQS_SLAVE_DELAY_3_CR,
+ MDDR_PHY_RD_DQS_SLAVE_FORCE_CR,
+ MDDR_PHY_RD_DQS_SLAVE_RATIO_1_CR,
+ MDDR_PHY_RD_DQS_SLAVE_RATIO_2_CR,
+ MDDR_PHY_RD_DQS_SLAVE_RATIO_3_CR,
+ MDDR_PHY_RD_DQS_SLAVE_RATIO_4_CR,
+ MDDR_PHY_WR_DQS_SLAVE_DELAY_1_CR,
+ MDDR_PHY_WR_DQS_SLAVE_DELAY_2_CR,
+ MDDR_PHY_WR_DQS_SLAVE_DELAY_3_CR,
+ MDDR_PHY_WR_DQS_SLAVE_FORCE_CR,
+ MDDR_PHY_WR_DQS_SLAVE_RATIO_1_CR,
+ MDDR_PHY_WR_DQS_SLAVE_RATIO_2_CR,
+ MDDR_PHY_WR_DQS_SLAVE_RATIO_3_CR,
+ MDDR_PHY_WR_DQS_SLAVE_RATIO_4_CR,
+ MDDR_PHY_WR_DATA_SLAVE_DELAY_1_CR,
+ MDDR_PHY_WR_DATA_SLAVE_DELAY_2_CR,
+ MDDR_PHY_WR_DATA_SLAVE_DELAY_3_CR,
+ MDDR_PHY_WR_DATA_SLAVE_FORCE_CR,
+ MDDR_PHY_WR_DATA_SLAVE_RATIO_1_CR,
+ MDDR_PHY_WR_DATA_SLAVE_RATIO_2_CR,
+ MDDR_PHY_WR_DATA_SLAVE_RATIO_3_CR,
+ MDDR_PHY_WR_DATA_SLAVE_RATIO_4_CR,
+ MDDR_PHY_WRLVL_INIT_MODE_CR,
+ MDDR_PHY_WRLVL_INIT_RATIO_1_CR,
+ MDDR_PHY_WRLVL_INIT_RATIO_2_CR,
+ MDDR_PHY_WRLVL_INIT_RATIO_3_CR,
+ MDDR_PHY_WRLVL_INIT_RATIO_4_CR,
+ MDDR_PHY_WR_RD_RL_CR,
+ MDDR_PHY_RDC_FIFO_RST_ERR_CNT_CLR_CR,
+ MDDR_PHY_RDC_WE_TO_RE_DELAY_CR,
+ MDDR_PHY_USE_FIXED_RE_CR,
+ MDDR_PHY_USE_RANK0_DELAYS_CR,
+ MDDR_PHY_USE_LVL_TRNG_LEVEL_CR,
+ MDDR_PHY_DYN_CONFIG_CR,
+ MDDR_PHY_RD_WR_GATE_LVL_CR,
+ MDDR_PHY_DYN_RESET_CR
+ MDDR_DDR_FIC_NB_ADDR_CR,
+ MDDR_DDR_FIC_NBRWB_SIZE_CR,
+ MDDR_DDR_FIC_WB_TIMEOUT_CR,
+ MDDR_DDR_FIC_HPD_SW_RW_EN_CR,
+ MDDR_DDR_FIC_HPD_SW_RW_INVAL_CR,
+ MDDR_DDR_FIC_SW_WR_ERCLR_CR,
+ MDDR_DDR_FIC_ERR_INT_ENABLE_CR,
+ MDDR_DDR_FIC_NUM_AHB_MASTERS_CR,
+ MDDR_DDR_FIC_LOCK_TIMEOUTVAL_1_CR,
+ MDDR_DDR_FIC_LOCK_TIMEOUTVAL_2_CR,
+ MDDR_DDR_FIC_LOCK_TIMEOUT_EN_CR
+#include "sys_config_fddr_define.h"
+FDDR_TypeDef * const g_m2s_fddr_addr = (FDDR_TypeDef *)0x40021000;
+const fddr_sysreg_t g_m2s_fddr_sysreg_subsys_config =
+ 0x0001u, /* PLL_CONFIG_LOW_1 */
+ 0x0002u, /* PLL_CONFIG_LOW_2 */
+ 0x0003u, /* PLL_CONFIG_HIGH */
+ 0x0004u, /* FACC_CLK_EN */
+ 0x0005u, /* FACC_MUX_CONFIG */
+ 0x0006u, /* FACC_DIVISOR_RATIO */
+ 0x0007u, /* PLL_DELAY_LINE_SEL */
+ 0x0008u, /* SOFT_RESET */
+ 0x0009u, /* IO_CALIB */
+ 0x000Au, /* INTERRUPT_ENABLE */
+ 0x000Bu, /* AXI_AHB_MODE_SEL */
+ 0x000Cu /* PHY_SELF_REF_EN */
+const ddr_subsys_cfg_t g_m2s_fddr_subsys_config =
+ FDDR_DDRC_DYN_SOFT_RESET_CR,
+ FDDR_DDRC_RESERVED0,
+ FDDR_DDRC_DYN_REFRESH_1_CR,
+ FDDR_DDRC_DYN_REFRESH_2_CR,
+ FDDR_DDRC_DYN_POWERDOWN_CR,
+ FDDR_DDRC_DYN_DEBUG_CR,
+ FDDR_DDRC_MODE_CR,
+ FDDR_DDRC_ADDR_MAP_BANK_CR,
+ FDDR_DDRC_ECC_DATA_MASK_CR,
+ FDDR_DDRC_ADDR_MAP_COL_1_CR,
+ FDDR_DDRC_ADDR_MAP_COL_2_CR,
+ FDDR_DDRC_ADDR_MAP_ROW_1_CR,
+ FDDR_DDRC_ADDR_MAP_ROW_2_CR,
+ FDDR_DDRC_INIT_1_CR,
+ FDDR_DDRC_CKE_RSTN_CYCLES_1_CR,
+ FDDR_DDRC_CKE_RSTN_CYCLES_2_CR,
+ FDDR_DDRC_INIT_MR_CR,
+ FDDR_DDRC_INIT_EMR_CR,
+ FDDR_DDRC_INIT_EMR2_CR,
+ FDDR_DDRC_INIT_EMR3_CR,
+ FDDR_DDRC_DRAM_BANK_TIMING_PARAM_CR,
+ FDDR_DDRC_DRAM_RD_WR_LATENCY_CR,
+ FDDR_DDRC_DRAM_RD_WR_PRE_CR,
+ FDDR_DDRC_DRAM_MR_TIMING_PARAM_CR,
+ FDDR_DDRC_DRAM_RAS_TIMING_CR,
+ FDDR_DDRC_DRAM_RD_WR_TRNARND_TIME_CR,
+ FDDR_DDRC_DRAM_T_PD_CR,
+ FDDR_DDRC_DRAM_BANK_ACT_TIMING_CR,
+ FDDR_DDRC_ODT_PARAM_1_CR,
+ FDDR_DDRC_ODT_PARAM_2_CR,
+ FDDR_DDRC_ADDR_MAP_COL_3_CR,
+ FDDR_DDRC_MODE_REG_RD_WR_CR,
+ FDDR_DDRC_MODE_REG_DATA_CR,
+ FDDR_DDRC_PWR_SAVE_1_CR,
+ FDDR_DDRC_PWR_SAVE_2_CR,
+ FDDR_DDRC_ZQ_LONG_TIME_CR,
+ FDDR_DDRC_ZQ_SHORT_TIME_CR,
+ FDDR_DDRC_ZQ_SHORT_INT_REFRESH_MARGIN_1_CR,
+ FDDR_DDRC_ZQ_SHORT_INT_REFRESH_MARGIN_2_CR,
+ FDDR_DDRC_PERF_PARAM_1_CR,
+ FDDR_DDRC_HPR_QUEUE_PARAM_1_CR,
+ FDDR_DDRC_HPR_QUEUE_PARAM_2_CR,
+ FDDR_DDRC_LPR_QUEUE_PARAM_1_CR,
+ FDDR_DDRC_LPR_QUEUE_PARAM_2_CR,
+ FDDR_DDRC_WR_QUEUE_PARAM_CR,
+ FDDR_DDRC_PERF_PARAM_2_CR,
+ FDDR_DDRC_PERF_PARAM_3_CR,
+ FDDR_DDRC_DFI_RDDATA_EN_CR,
+ FDDR_DDRC_DFI_MIN_CTRLUPD_TIMING_CR,
+ FDDR_DDRC_DFI_MAX_CTRLUPD_TIMING_CR,
+ FDDR_DDRC_DFI_WR_LVL_CONTROL_1_CR,
+ FDDR_DDRC_DFI_WR_LVL_CONTROL_2_CR,
+ FDDR_DDRC_DFI_RD_LVL_CONTROL_1_CR,
+ FDDR_DDRC_DFI_RD_LVL_CONTROL_2_CR,
+ FDDR_DDRC_DFI_CTRLUPD_TIME_INTERVAL_CR,
+ FDDR_DDRC_DYN_SOFT_RESET_ALIAS_CR,
+ FDDR_DDRC_AXI_FABRIC_PRI_ID_CR
+ FDDR_PHY_LOOPBACK_TEST_CR,
+ FDDR_PHY_BOARD_LOOPBACK_CR,
+ FDDR_PHY_CTRL_SLAVE_RATIO_CR,
+ FDDR_PHY_CTRL_SLAVE_FORCE_CR,
+ FDDR_PHY_CTRL_SLAVE_DELAY_CR,
+ FDDR_PHY_DATA_SLICE_IN_USE_CR,
+ FDDR_PHY_LVL_NUM_OF_DQ0_CR,
+ FDDR_PHY_DQ_OFFSET_1_CR,
+ FDDR_PHY_DQ_OFFSET_2_CR,
+ FDDR_PHY_DQ_OFFSET_3_CR,
+ FDDR_PHY_DIS_CALIB_RST_CR,
+ FDDR_PHY_DLL_LOCK_DIFF_CR,
+ FDDR_PHY_FIFO_WE_IN_DELAY_1_CR,
+ FDDR_PHY_FIFO_WE_IN_DELAY_2_CR,
+ FDDR_PHY_FIFO_WE_IN_DELAY_3_CR,
+ FDDR_PHY_FIFO_WE_IN_FORCE_CR,
+ FDDR_PHY_FIFO_WE_SLAVE_RATIO_1_CR,
+ FDDR_PHY_FIFO_WE_SLAVE_RATIO_2_CR,
+ FDDR_PHY_FIFO_WE_SLAVE_RATIO_3_CR,
+ FDDR_PHY_FIFO_WE_SLAVE_RATIO_4_CR,
+ FDDR_PHY_GATELVL_INIT_MODE_CR,
+ FDDR_PHY_GATELVL_INIT_RATIO_1_CR,
+ FDDR_PHY_GATELVL_INIT_RATIO_2_CR,
+ FDDR_PHY_GATELVL_INIT_RATIO_3_CR,
+ FDDR_PHY_GATELVL_INIT_RATIO_4_CR,
+ FDDR_PHY_LOCAL_ODT_CR,
+ FDDR_PHY_INVERT_CLKOUT_CR,
+ FDDR_PHY_RD_DQS_SLAVE_DELAY_1_CR,
+ FDDR_PHY_RD_DQS_SLAVE_DELAY_2_CR,
+ FDDR_PHY_RD_DQS_SLAVE_DELAY_3_CR,
+ FDDR_PHY_RD_DQS_SLAVE_FORCE_CR,
+ FDDR_PHY_RD_DQS_SLAVE_RATIO_1_CR,
+ FDDR_PHY_RD_DQS_SLAVE_RATIO_2_CR,
+ FDDR_PHY_RD_DQS_SLAVE_RATIO_3_CR,
+ FDDR_PHY_RD_DQS_SLAVE_RATIO_4_CR,
+ FDDR_PHY_WR_DQS_SLAVE_DELAY_1_CR,
+ FDDR_PHY_WR_DQS_SLAVE_DELAY_2_CR,
+ FDDR_PHY_WR_DQS_SLAVE_DELAY_3_CR,
+ FDDR_PHY_WR_DQS_SLAVE_FORCE_CR,
+ FDDR_PHY_WR_DQS_SLAVE_RATIO_1_CR,
+ FDDR_PHY_WR_DQS_SLAVE_RATIO_2_CR,
+ FDDR_PHY_WR_DQS_SLAVE_RATIO_3_CR,
+ FDDR_PHY_WR_DQS_SLAVE_RATIO_4_CR,
+ FDDR_PHY_WR_DATA_SLAVE_DELAY_1_CR,
+ FDDR_PHY_WR_DATA_SLAVE_DELAY_2_CR,
+ FDDR_PHY_WR_DATA_SLAVE_DELAY_3_CR,
+ FDDR_PHY_WR_DATA_SLAVE_FORCE_CR,
+ FDDR_PHY_WR_DATA_SLAVE_RATIO_1_CR,
+ FDDR_PHY_WR_DATA_SLAVE_RATIO_2_CR,
+ FDDR_PHY_WR_DATA_SLAVE_RATIO_3_CR,
+ FDDR_PHY_WR_DATA_SLAVE_RATIO_4_CR,
+ FDDR_PHY_WRLVL_INIT_MODE_CR,
+ FDDR_PHY_WRLVL_INIT_RATIO_1_CR,
+ FDDR_PHY_WRLVL_INIT_RATIO_2_CR,
+ FDDR_PHY_WRLVL_INIT_RATIO_3_CR,
+ FDDR_PHY_WRLVL_INIT_RATIO_4_CR,
+ FDDR_PHY_WR_RD_RL_CR,
+ FDDR_PHY_RDC_FIFO_RST_ERR_CNT_CLR_CR,
+ FDDR_PHY_RDC_WE_TO_RE_DELAY_CR,
+ FDDR_PHY_USE_FIXED_RE_CR,
+ FDDR_PHY_USE_RANK0_DELAYS_CR,
+ FDDR_PHY_USE_LVL_TRNG_LEVEL_CR,
+ FDDR_PHY_DYN_CONFIG_CR,
+ FDDR_PHY_RD_WR_GATE_LVL_CR,
+ FDDR_PHY_DYN_RESET_CR,
+ FDDR_DDR_FIC_NB_ADDR_CR,
+ FDDR_DDR_FIC_NBRWB_SIZE_CR,
+ FDDR_DDR_FIC_WB_TIMEOUT_CR,
+ FDDR_DDR_FIC_HPD_SW_RW_EN_CR,
+ FDDR_DDR_FIC_HPD_SW_RW_INVAL_CR,
+ FDDR_DDR_FIC_SW_WR_ERCLR_CR,
+ FDDR_DDR_FIC_ERR_INT_ENABLE_CR,
+ FDDR_DDR_FIC_NUM_AHB_MASTERS_CR,
+ FDDR_DDR_FIC_LOCK_TIMEOUTVAL_1_CR,
+ FDDR_DDR_FIC_LOCK_TIMEOUTVAL_2_CR,
+ FDDR_DDR_FIC_LOCK_TIMEOUT_EN_CR
@@ -0,0 +1,66 @@
+ * by the Libero tools.
+#ifndef MSS_SYSTEM_CONFIGURATION
+#define MSS_SYSTEM_CONFIGURATION
+#include "sys_config_mss_clocks.h"
+/* TBD */
+ * FACC_INIT (Cortex-M3 runs the FACC INIT procedure)
+ * Only set to 1 for design targeting the M2S050T_ES device
+#define MSS_SYS_FACC_INIT_BY_CORTEX 0
+#define MSS_SYS_MDDR_CONFIG_BY_CORTEX 0
+#define MSS_SYS_FDDR_CONFIG_BY_CORTEX 0
+ * SERDES Interface configuration
+#define MSS_SYS_SERDES_0_CONFIG_BY_CORTEX 0
+#include "sys_config_SERDESIF_0.h"
+#define MSS_SYS_SERDES_1_CONFIG_BY_CORTEX 0
+#include "sys_config_SERDESIF_1.h"
+#define MSS_SYS_SERDES_2_CONFIG_BY_CORTEX 0
+#include "sys_config_SERDESIF_2.h"
+#define MSS_SYS_SERDES_3_CONFIG_BY_CORTEX 0
+#include "sys_config_SERDESIF_3.h"
+ * Cache configuration
+#define MSS_SYS_CACHE_CONFIG_BY_CORTEX 0
+#endif /* MSS_SYSTEM_CONFIGURATION */
@@ -0,0 +1,21 @@
+/*=============================================================*/
+/* Created by Microsemi SmartDesign Fri May 22 15:04:18 2020 */
+/* */
+/* Warning: Do not modify this file, it may lead to unexpected */
+/* functional failures in your design. */
+#ifndef SYS_CONFIG_MSS_CLOCKS
+#define SYS_CONFIG_MSS_CLOCKS
+#define MSS_SYS_M3_CLK_FREQ 100000000u
+#define MSS_SYS_MDDR_CLK_FREQ 100000000u
+#define MSS_SYS_APB_0_CLK_FREQ 100000000u
+#define MSS_SYS_APB_1_CLK_FREQ 100000000u
+#define MSS_SYS_APB_2_CLK_FREQ 25000000u
+#define MSS_SYS_FIC_0_CLK_FREQ 100000000u
+#define MSS_SYS_FIC_1_CLK_FREQ 100000000u
+#define MSS_SYS_FIC64_CLK_FREQ 100000000u
+#endif /* SYS_CONFIG_MSS_CLOCKS */
@@ -0,0 +1,987 @@
+<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
+<ProjectOpt xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_opt.xsd">
+ <SchemaVersion>1.0</SchemaVersion>
+ <Header>### uVision Project, (C) Keil Software</Header>
+ <Extensions>
+ <cExt>*.c</cExt>
+ <aExt>*.s*; *.src; *.a*</aExt>
+ <oExt>*.obj</oExt>
+ <lExt>*.lib</lExt>
+ <tExt>*.txt; *.h; *.inc</tExt>
+ <pExt>*.plm</pExt>
+ <CppX>*.cpp</CppX>
+ </Extensions>
+ <DaveTm>
+ <dwLowDateTime>0</dwLowDateTime>
+ <dwHighDateTime>0</dwHighDateTime>
+ </DaveTm>
+ <Target>
+ <TargetName>project</TargetName>
+ <ToolsetNumber>0x4</ToolsetNumber>
+ <ToolsetName>ARM-ADS</ToolsetName>
+ <TargetOption>
+ <CLKADS>20000000</CLKADS>
+ <OPTTT>
+ <gFlags>1</gFlags>
+ <BeepAtEnd>1</BeepAtEnd>
+ <RunSim>1</RunSim>
+ <RunTarget>0</RunTarget>
+ </OPTTT>
+ <OPTHX>
+ <HexSelection>1</HexSelection>
+ <FlashByte>65535</FlashByte>
+ <HexRangeLowAddress>0</HexRangeLowAddress>
+ <HexRangeHighAddress>0</HexRangeHighAddress>
+ <HexOffset>0</HexOffset>
+ </OPTHX>
+ <OPTLEX>
+ <PageWidth>79</PageWidth>
+ <PageLength>66</PageLength>
+ <TabStop>8</TabStop>
+ <ListingPath>.\obj\</ListingPath>
+ </OPTLEX>
+ <ListingPage>
+ <CreateCListing>1</CreateCListing>
+ <CreateAListing>1</CreateAListing>
+ <CreateLListing>1</CreateLListing>
+ <CreateIListing>0</CreateIListing>
+ <AsmCond>1</AsmCond>
+ <AsmSymb>1</AsmSymb>
+ <AsmXref>0</AsmXref>
+ <CCond>1</CCond>
+ <CCode>0</CCode>
+ <CListInc>0</CListInc>
+ <CSymb>0</CSymb>
+ <LinkerCodeListing>0</LinkerCodeListing>
+ </ListingPage>
+ <OPTXL>
+ <LMap>1</LMap>
+ <LComments>1</LComments>
+ <LGenerateSymbols>1</LGenerateSymbols>
+ <LLibSym>1</LLibSym>
+ <LLines>1</LLines>
+ <LLocSym>1</LLocSym>
+ <LPubSym>1</LPubSym>
+ <LXref>0</LXref>
+ <LExpSel>0</LExpSel>
+ </OPTXL>
+ <OPTFL>
+ <tvExp>1</tvExp>
+ <tvExpOptDlg>0</tvExpOptDlg>
+ <IsCurrentTarget>1</IsCurrentTarget>
+ </OPTFL>
+ <CpuCode>255</CpuCode>
+ <Books>
+ <Book>
+ <Number>0</Number>
+ <Title>Datasheet</Title>
+ <Path>DATASHTS\Actel\M2Sxxx\SmartFusion2_DS.pdf</Path>
+ </Book>
+ <Number>1</Number>
+ <Title>Technical Reference Manual</Title>
+ <Path>datashts\arm\cortex_m3\r2p1\DDI0337I_CORTEXM3_R2P1_TRM.PDF</Path>
+ <Number>2</Number>
+ <Title>Generic User Guide</Title>
+ <Path>datashts\arm\cortex_m3\r2p1\DUI0552A_CORTEX_M3_DGUG.PDF</Path>
+ </Books>
+ <DebugOpt>
+ <uSim>0</uSim>
+ <uTrg>1</uTrg>
+ <sLdApp>1</sLdApp>
+ <sGomain>1</sGomain>
+ <sRbreak>1</sRbreak>
+ <sRwatch>1</sRwatch>
+ <sRmem>1</sRmem>
+ <sRfunc>1</sRfunc>
+ <sRbox>1</sRbox>
+ <tLdApp>1</tLdApp>
+ <tGomain>1</tGomain>
+ <tRbreak>1</tRbreak>
+ <tRwatch>1</tRwatch>
+ <tRmem>1</tRmem>
+ <tRfunc>0</tRfunc>
+ <tRbox>1</tRbox>
+ <tRtrace>1</tRtrace>
+ <sRSysVw>1</sRSysVw>
+ <tRSysVw>1</tRSysVw>
+ <tPdscDbg>0</tPdscDbg>
+ <sRunDeb>0</sRunDeb>
+ <sLrtime>0</sLrtime>
+ <nTsel>6</nTsel>
+ <sDll></sDll>
+ <sDllPa></sDllPa>
+ <sDlgDll></sDlgDll>
+ <sDlgPa></sDlgPa>
+ <sIfile></sIfile>
+ <tDll></tDll>
+ <tDllPa></tDllPa>
+ <tDlgDll></tDlgDll>
+ <tDlgPa></tDlgPa>
+ <tIfile></tIfile>
+ <pMon>Segger\JL2CM3.dll</pMon>
+ </DebugOpt>
+ <TargetDriverDllRegistry>
+ <SetRegEntry>
+ <Key>JL2CM3</Key>
+ <Name>-U10000387 -O207 -S8 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -N00("ARM CoreSight SW-DP") -D00(2BA01477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO15 -FD20000000 -FC800 -FN1 -FF0M2Sxxx_256 -FS00 -FL040000</Name>
+ </SetRegEntry>
+ <Key>UL2CM3</Key>
+ <Name>UL2CM3(-O207 -O207 -S9 -C0 -FO7 -FN1 -FC800 -FD20000000 -FF0M2Sxxx_256 -FL040000 -FS00</Name>
+ </TargetDriverDllRegistry>
+ <Breakpoint/>
+ <Tracepoint>
+ <THDelay>0</THDelay>
+ </Tracepoint>
+ <DebugFlag>
+ <trace>0</trace>
+ <periodic>1</periodic>
+ <aLwin>0</aLwin>
+ <aCover>0</aCover>
+ <aSer1>0</aSer1>
+ <aSer2>0</aSer2>
+ <aPa>0</aPa>
+ <viewmode>0</viewmode>
+ <vrSel>0</vrSel>
+ <aSym>0</aSym>
+ <aTbox>0</aTbox>
+ <AscS1>0</AscS1>
+ <AscS2>0</AscS2>
+ <AscS3>0</AscS3>
+ <aSer3>0</aSer3>
+ <eProf>0</eProf>
+ <aLa>0</aLa>
+ <aPa1>0</aPa1>
+ <AscS4>0</AscS4>
+ <aSer4>0</aSer4>
+ <StkLoc>0</StkLoc>
+ <TrcWin>0</TrcWin>
+ <newCpu>0</newCpu>
+ <uProt>0</uProt>
+ </DebugFlag>
+ <LintExecutable></LintExecutable>
+ <LintConfigFile></LintConfigFile>
+ </TargetOption>
+ </Target>
+ <Group>
+ <GroupName>Kernel</GroupName>
+ <tvExp>0</tvExp>
+ <cbSel>0</cbSel>
+ <RteFlg>0</RteFlg>
+ <File>
+ <GroupNumber>1</GroupNumber>
+ <FileNumber>1</FileNumber>
+ <FileType>1</FileType>
+ <Focus>0</Focus>
+ <ColumnNumber>0</ColumnNumber>
+ <TopLine>0</TopLine>
+ <CurrentLine>0</CurrentLine>
+ <bDave2>0</bDave2>
+ <PathWithFileName>..\..\src\clock.c</PathWithFileName>
+ <FilenameWithoutPath>clock.c</FilenameWithoutPath>
+ <bShared>0</bShared>
+ </File>
+ <FileNumber>2</FileNumber>
+ <PathWithFileName>..\..\src\components.c</PathWithFileName>
+ <FilenameWithoutPath>components.c</FilenameWithoutPath>
+ <FileNumber>3</FileNumber>
+ <PathWithFileName>..\..\src\device.c</PathWithFileName>
+ <FilenameWithoutPath>device.c</FilenameWithoutPath>
+ <FileNumber>4</FileNumber>
+ <PathWithFileName>..\..\src\idle.c</PathWithFileName>
+ <FilenameWithoutPath>idle.c</FilenameWithoutPath>
+ <FileNumber>5</FileNumber>
+ <PathWithFileName>..\..\src\ipc.c</PathWithFileName>
+ <FilenameWithoutPath>ipc.c</FilenameWithoutPath>
+ <FileNumber>6</FileNumber>
+ <PathWithFileName>..\..\src\irq.c</PathWithFileName>
+ <FilenameWithoutPath>irq.c</FilenameWithoutPath>
+ <FileNumber>7</FileNumber>
+ <PathWithFileName>..\..\src\kservice.c</PathWithFileName>
+ <FilenameWithoutPath>kservice.c</FilenameWithoutPath>
+ <FileNumber>8</FileNumber>
+ <PathWithFileName>..\..\src\mem.c</PathWithFileName>
+ <FilenameWithoutPath>mem.c</FilenameWithoutPath>
+ <FileNumber>9</FileNumber>
+ <PathWithFileName>..\..\src\mempool.c</PathWithFileName>
+ <FilenameWithoutPath>mempool.c</FilenameWithoutPath>
+ <FileNumber>10</FileNumber>
+ <PathWithFileName>..\..\src\object.c</PathWithFileName>
+ <FilenameWithoutPath>object.c</FilenameWithoutPath>
+ <FileNumber>11</FileNumber>
+ <PathWithFileName>..\..\src\scheduler.c</PathWithFileName>
+ <FilenameWithoutPath>scheduler.c</FilenameWithoutPath>
+ <FileNumber>12</FileNumber>
+ <PathWithFileName>..\..\src\signal.c</PathWithFileName>
+ <FilenameWithoutPath>signal.c</FilenameWithoutPath>
+ <FileNumber>13</FileNumber>
+ <PathWithFileName>..\..\src\thread.c</PathWithFileName>
+ <FilenameWithoutPath>thread.c</FilenameWithoutPath>
+ <FileNumber>14</FileNumber>
+ <PathWithFileName>..\..\src\timer.c</PathWithFileName>
+ <FilenameWithoutPath>timer.c</FilenameWithoutPath>
+ </Group>
+ <GroupName>Applications</GroupName>
+ <GroupNumber>2</GroupNumber>
+ <FileNumber>15</FileNumber>
+ <ColumnNumber>14</ColumnNumber>
+ <TopLine>1</TopLine>
+ <CurrentLine>16</CurrentLine>
+ <PathWithFileName>applications\main.c</PathWithFileName>
+ <FilenameWithoutPath>main.c</FilenameWithoutPath>
+ <FileNumber>16</FileNumber>
+ <PathWithFileName>board\board.c</PathWithFileName>
+ <FilenameWithoutPath>board.c</FilenameWithoutPath>
+ <FileNumber>17</FileNumber>
+ <PathWithFileName>board\config.c</PathWithFileName>
+ <FilenameWithoutPath>config.c</FilenameWithoutPath>
+ <GroupName>CMSIS</GroupName>
+ <GroupNumber>3</GroupNumber>
+ <FileNumber>18</FileNumber>
+ <PathWithFileName>CMSIS\core_cm3.c</PathWithFileName>
+ <FilenameWithoutPath>core_cm3.c</FilenameWithoutPath>
+ <FileNumber>19</FileNumber>
+ <PathWithFileName>CMSIS\system_m2sxxx.c</PathWithFileName>
+ <FilenameWithoutPath>system_m2sxxx.c</FilenameWithoutPath>
+ <FileNumber>20</FileNumber>
+ <FileType>2</FileType>
+ <PathWithFileName>CMSIS\startup_arm\startup_m2sxxx.s</PathWithFileName>
+ <FilenameWithoutPath>startup_m2sxxx.s</FilenameWithoutPath>
+ <GroupName>Drivers</GroupName>
+ <GroupNumber>4</GroupNumber>
+ <FileNumber>21</FileNumber>
+ <PathWithFileName>drivers\drv_uart.c</PathWithFileName>
+ <FilenameWithoutPath>drv_uart.c</FilenameWithoutPath>
+ <FileNumber>22</FileNumber>
+ <PathWithFileName>drivers\drv_gpio.c</PathWithFileName>
+ <FilenameWithoutPath>drv_gpio.c</FilenameWithoutPath>
+ <GroupName>Libraries</GroupName>
+ <GroupNumber>5</GroupNumber>
+ <FileNumber>23</FileNumber>
+ <PathWithFileName>libraries\sys_config\sys_config.c</PathWithFileName>
+ <FilenameWithoutPath>sys_config.c</FilenameWithoutPath>
+ <FileNumber>24</FileNumber>
+ <PathWithFileName>libraries\mss_gpio\mss_gpio.c</PathWithFileName>
+ <FilenameWithoutPath>mss_gpio.c</FilenameWithoutPath>
+ <FileNumber>25</FileNumber>
+ <PathWithFileName>libraries\mss_uart\mss_uart.c</PathWithFileName>
+ <FilenameWithoutPath>mss_uart.c</FilenameWithoutPath>
+ <GroupName>cpu</GroupName>
+ <GroupNumber>6</GroupNumber>
+ <FileNumber>26</FileNumber>
+ <PathWithFileName>..\..\libcpu\arm\common\backtrace.c</PathWithFileName>
+ <FilenameWithoutPath>backtrace.c</FilenameWithoutPath>
+ <FileNumber>27</FileNumber>
+ <PathWithFileName>..\..\libcpu\arm\common\div0.c</PathWithFileName>
+ <FilenameWithoutPath>div0.c</FilenameWithoutPath>
+ <FileNumber>28</FileNumber>
+ <PathWithFileName>..\..\libcpu\arm\common\showmem.c</PathWithFileName>
+ <FilenameWithoutPath>showmem.c</FilenameWithoutPath>
+ <FileNumber>29</FileNumber>
+ <PathWithFileName>..\..\libcpu\arm\cortex-m3\cpuport.c</PathWithFileName>
+ <FilenameWithoutPath>cpuport.c</FilenameWithoutPath>
+ <FileNumber>30</FileNumber>
+ <PathWithFileName>..\..\libcpu\arm\cortex-m3\context_rvds.S</PathWithFileName>
+ <FilenameWithoutPath>context_rvds.S</FilenameWithoutPath>
+ <GroupName>DeviceDrivers</GroupName>
+ <GroupNumber>7</GroupNumber>
+ <FileNumber>31</FileNumber>
+ <PathWithFileName>..\..\components\drivers\misc\pin.c</PathWithFileName>
+ <FilenameWithoutPath>pin.c</FilenameWithoutPath>
+ <FileNumber>32</FileNumber>
+ <PathWithFileName>..\..\components\drivers\serial\serial.c</PathWithFileName>
+ <FilenameWithoutPath>serial.c</FilenameWithoutPath>
+ <FileNumber>33</FileNumber>
+ <PathWithFileName>..\..\components\drivers\src\completion.c</PathWithFileName>
+ <FilenameWithoutPath>completion.c</FilenameWithoutPath>
+ <FileNumber>34</FileNumber>
+ <PathWithFileName>..\..\components\drivers\src\dataqueue.c</PathWithFileName>
+ <FilenameWithoutPath>dataqueue.c</FilenameWithoutPath>
+ <FileNumber>35</FileNumber>
+ <PathWithFileName>..\..\components\drivers\src\pipe.c</PathWithFileName>
+ <FilenameWithoutPath>pipe.c</FilenameWithoutPath>
+ <FileNumber>36</FileNumber>
+ <PathWithFileName>..\..\components\drivers\src\ringblk_buf.c</PathWithFileName>
+ <FilenameWithoutPath>ringblk_buf.c</FilenameWithoutPath>
+ <FileNumber>37</FileNumber>
+ <PathWithFileName>..\..\components\drivers\src\ringbuffer.c</PathWithFileName>
+ <FilenameWithoutPath>ringbuffer.c</FilenameWithoutPath>
+ <FileNumber>38</FileNumber>
+ <PathWithFileName>..\..\components\drivers\src\waitqueue.c</PathWithFileName>
+ <FilenameWithoutPath>waitqueue.c</FilenameWithoutPath>
+ <FileNumber>39</FileNumber>
+ <PathWithFileName>..\..\components\drivers\src\workqueue.c</PathWithFileName>
+ <FilenameWithoutPath>workqueue.c</FilenameWithoutPath>
+ <GroupName>finsh</GroupName>
+ <GroupNumber>8</GroupNumber>
+ <FileNumber>40</FileNumber>
+ <PathWithFileName>..\..\components\finsh\shell.c</PathWithFileName>
+ <FilenameWithoutPath>shell.c</FilenameWithoutPath>
+ <FileNumber>41</FileNumber>
+ <PathWithFileName>..\..\components\finsh\cmd.c</PathWithFileName>
+ <FilenameWithoutPath>cmd.c</FilenameWithoutPath>
+ <FileNumber>42</FileNumber>
+ <PathWithFileName>..\..\components\finsh\msh.c</PathWithFileName>
+ <FilenameWithoutPath>msh.c</FilenameWithoutPath>
+ <GroupName>libc</GroupName>
+ <GroupNumber>9</GroupNumber>
+ <FileNumber>43</FileNumber>
+ <PathWithFileName>..\..\components\libc\compilers\armlibc\libc.c</PathWithFileName>
+ <FilenameWithoutPath>libc.c</FilenameWithoutPath>
+ <FileNumber>44</FileNumber>
+ <PathWithFileName>..\..\components\libc\compilers\armlibc\mem_std.c</PathWithFileName>
+ <FilenameWithoutPath>mem_std.c</FilenameWithoutPath>
+ <FileNumber>45</FileNumber>
+ <PathWithFileName>..\..\components\libc\compilers\armlibc\stubs.c</PathWithFileName>
+ <FilenameWithoutPath>stubs.c</FilenameWithoutPath>
+ <FileNumber>46</FileNumber>
+ <PathWithFileName>..\..\components\libc\compilers\common\time.c</PathWithFileName>
+ <FilenameWithoutPath>time.c</FilenameWithoutPath>
+</ProjectOpt>
@@ -0,0 +1,801 @@
+<ProjectOpt xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_optx.xsd">
+ <oExt>*.obj; *.o</oExt>
+ <nMigrate>0</nMigrate>
+ <CLKADS>12000000</CLKADS>
+ <RunSim>0</RunSim>
+ <RunTarget>1</RunTarget>
+ <RunAbUc>0</RunAbUc>
+ <bEvRecOn>1</bEvRecOn>
+ <bSchkAxf>0</bSchkAxf>
+ <bTchkAxf>0</bTchkAxf>
+ <nTsel>4</nTsel>
+ <Name>-U10000387 -O78 -S8 -ZTIFSpeedSel50000 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -N00("ARM CoreSight SW-DP") -D00(2BA01477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO15 -FD20000000 -FC1000 -FN1 -FF0M2Sxxx_256.FLM -FS00 -FL040000 -FP0($$Device:M2S010$Flash\M2Sxxx_256.FLM)</Name>
+ <Name>UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0M2Sxxx_256 -FS00 -FL040000 -FP0($$Device:M2S010$Flash\M2Sxxx_256.FLM))</Name>
+ <bLintAuto>0</bLintAuto>
+ <bAutoGenD>0</bAutoGenD>
+ <LntExFlags>0</LntExFlags>
+ <pMisraName></pMisraName>
+ <pszMrule></pszMrule>
+ <pSingCmds></pSingCmds>
+ <pMultCmds></pMultCmds>
+ <pMisraNamep></pMisraNamep>
+ <pszMrulep></pszMrulep>
+ <pSingCmdsp></pSingCmdsp>
+ <pMultCmdsp></pMultCmdsp>
@@ -0,0 +1,684 @@
+<Project xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_proj.xsd">
+ <SchemaVersion>1.1</SchemaVersion>
+ <Targets>
+ <TargetCommonOption>
+ <Device>M2S010</Device>
+ <Vendor>Microsemi</Vendor>
+ <Cpu>IRAM(0x20000000-0x2000FFFF) IROM(0x0-0x3FFFF) CLOCK(20000000) CPUTYPE("Cortex-M3")</Cpu>
+ <FlashUtilSpec></FlashUtilSpec>
+ <StartupFile></StartupFile>
+ <FlashDriverDll>UL2CM3(-O207 -S9 -C0 -FO7 -FD20000000 -FC800 -FN1 -FF0M2Sxxx_256 -FS00 -FL040000)</FlashDriverDll>
+ <DeviceId>6800</DeviceId>
+ <RegisterFile></RegisterFile>
+ <MemoryEnv></MemoryEnv>
+ <Cmp></Cmp>
+ <Asm></Asm>
+ <Linker></Linker>
+ <OHString></OHString>
+ <InfinionOptionDll></InfinionOptionDll>
+ <SLE66CMisc></SLE66CMisc>
+ <SLE66AMisc></SLE66AMisc>
+ <SLE66LinkerMisc></SLE66LinkerMisc>
+ <SFDFile></SFDFile>
+ <bCustSvd>0</bCustSvd>
+ <UseEnv>0</UseEnv>
+ <BinPath></BinPath>
+ <IncludePath></IncludePath>
+ <LibPath></LibPath>
+ <RegisterFilePath></RegisterFilePath>
+ <DBRegisterFilePath></DBRegisterFilePath>
+ <TargetStatus>
+ <Error>0</Error>
+ <ExitCodeStop>0</ExitCodeStop>
+ <ButtonStop>0</ButtonStop>
+ <NotGenerated>0</NotGenerated>
+ <InvalidFlash>1</InvalidFlash>
+ </TargetStatus>
+ <OutputDirectory>.\obj\</OutputDirectory>
+ <OutputName>rtthread</OutputName>
+ <CreateExecutable>1</CreateExecutable>
+ <CreateLib>0</CreateLib>
+ <CreateHexFile>1</CreateHexFile>
+ <DebugInformation>1</DebugInformation>
+ <BrowseInformation>1</BrowseInformation>
+ <HexFormatSelection>1</HexFormatSelection>
+ <Merge32K>0</Merge32K>
+ <CreateBatchFile>0</CreateBatchFile>
+ <BeforeCompile>
+ <RunUserProg1>0</RunUserProg1>
+ <RunUserProg2>0</RunUserProg2>
+ <UserProg1Name></UserProg1Name>
+ <UserProg2Name></UserProg2Name>
+ <UserProg1Dos16Mode>0</UserProg1Dos16Mode>
+ <UserProg2Dos16Mode>0</UserProg2Dos16Mode>
+ <nStopU1X>0</nStopU1X>
+ <nStopU2X>0</nStopU2X>
+ </BeforeCompile>
+ <BeforeMake>
+ </BeforeMake>
+ <AfterMake>
+ <RunUserProg1>1</RunUserProg1>
+ <UserProg1Name>fromelf --bin -o "$L@L.bin" "#L"</UserProg1Name>
+ </AfterMake>
+ <SelectedForBatchBuild>0</SelectedForBatchBuild>
+ <SVCSIdString></SVCSIdString>
+ </TargetCommonOption>
+ <CommonProperty>
+ <UseCPPCompiler>0</UseCPPCompiler>
+ <RVCTCodeConst>0</RVCTCodeConst>
+ <RVCTZI>0</RVCTZI>
+ <RVCTOtherData>0</RVCTOtherData>
+ <ModuleSelection>0</ModuleSelection>
+ <IncludeInBuild>1</IncludeInBuild>
+ <AlwaysBuild>0</AlwaysBuild>
+ <GenerateAssemblyFile>0</GenerateAssemblyFile>
+ <AssembleAssemblyFile>0</AssembleAssemblyFile>
+ <PublicsOnly>0</PublicsOnly>
+ <StopOnExitCode>3</StopOnExitCode>
+ <CustomArgument></CustomArgument>
+ <IncludeLibraryModules></IncludeLibraryModules>
+ <ComprImg>1</ComprImg>
+ </CommonProperty>
+ <DllOption>
+ <SimDllName>SARMCM3.DLL</SimDllName>
+ <SimDllArguments>-MPU</SimDllArguments>
+ <SimDlgDll>DCM.DLL</SimDlgDll>
+ <SimDlgDllArguments>-pCM3</SimDlgDllArguments>
+ <TargetDllName>SARMCM3.DLL</TargetDllName>
+ <TargetDllArguments>-MPU</TargetDllArguments>
+ <TargetDlgDll>TCM.DLL</TargetDlgDll>
+ <TargetDlgDllArguments>-pCM3</TargetDlgDllArguments>
+ </DllOption>
+ <DebugOption>
+ <Oh166RecLen>16</Oh166RecLen>
+ <Simulator>
+ <UseSimulator>0</UseSimulator>
+ <LoadApplicationAtStartup>1</LoadApplicationAtStartup>
+ <RunToMain>1</RunToMain>
+ <RestoreBreakpoints>1</RestoreBreakpoints>
+ <RestoreWatchpoints>1</RestoreWatchpoints>
+ <RestoreMemoryDisplay>1</RestoreMemoryDisplay>
+ <RestoreFunctions>1</RestoreFunctions>
+ <RestoreToolbox>1</RestoreToolbox>
+ <LimitSpeedToRealTime>0</LimitSpeedToRealTime>
+ <RestoreSysVw>1</RestoreSysVw>
+ </Simulator>
+ <UseTarget>1</UseTarget>
+ <RestoreFunctions>0</RestoreFunctions>
+ <RestoreTracepoints>1</RestoreTracepoints>
+ <UsePdscDebugDescription>0</UsePdscDebugDescription>
+ <RunDebugAfterBuild>0</RunDebugAfterBuild>
+ <TargetSelection>6</TargetSelection>
+ <SimDlls>
+ <CpuDll></CpuDll>
+ <CpuDllArguments></CpuDllArguments>
+ <PeripheralDll></PeripheralDll>
+ <PeripheralDllArguments></PeripheralDllArguments>
+ <InitializationFile></InitializationFile>
+ </SimDlls>
+ <TargetDlls>
+ <Driver>Segger\JL2CM3.dll</Driver>
+ </TargetDlls>
+ </DebugOption>
+ <Utilities>
+ <Flash1>
+ <UseTargetDll>1</UseTargetDll>
+ <UseExternalTool>0</UseExternalTool>
+ <RunIndependent>0</RunIndependent>
+ <UpdateFlashBeforeDebugging>1</UpdateFlashBeforeDebugging>
+ <Capability>0</Capability>
+ <DriverSelection>-1</DriverSelection>
+ </Flash1>
+ <bUseTDR>1</bUseTDR>
+ <Flash2>BIN\UL2CM3.DLL</Flash2>
+ <Flash3></Flash3>
+ <Flash4></Flash4>
+ <pFcarmOut></pFcarmOut>
+ <pFcarmGrp></pFcarmGrp>
+ <pFcArmRoot></pFcArmRoot>
+ <FcArmLst>0</FcArmLst>
+ </Utilities>
+ <TargetArmAds>
+ <ArmAdsMisc>
+ <GenerateListings>0</GenerateListings>
+ <asHll>1</asHll>
+ <asAsm>1</asAsm>
+ <asMacX>1</asMacX>
+ <asSyms>1</asSyms>
+ <asFals>1</asFals>
+ <asDbgD>1</asDbgD>
+ <asForm>1</asForm>
+ <ldLst>0</ldLst>
+ <ldmm>1</ldmm>
+ <ldXref>1</ldXref>
+ <BigEnd>0</BigEnd>
+ <AdsALst>1</AdsALst>
+ <AdsACrf>1</AdsACrf>
+ <AdsANop>0</AdsANop>
+ <AdsANot>0</AdsANot>
+ <AdsLLst>1</AdsLLst>
+ <AdsLmap>1</AdsLmap>
+ <AdsLcgr>1</AdsLcgr>
+ <AdsLsym>1</AdsLsym>
+ <AdsLszi>1</AdsLszi>
+ <AdsLtoi>1</AdsLtoi>
+ <AdsLsun>1</AdsLsun>
+ <AdsLven>1</AdsLven>
+ <AdsLsxf>1</AdsLsxf>
+ <RvctClst>0</RvctClst>
+ <GenPPlst>0</GenPPlst>
+ <AdsCpuType>"Cortex-M3"</AdsCpuType>
+ <RvctDeviceName></RvctDeviceName>
+ <mOS>0</mOS>
+ <uocRom>0</uocRom>
+ <uocRam>0</uocRam>
+ <hadIROM>1</hadIROM>
+ <hadIRAM>1</hadIRAM>
+ <hadXRAM>0</hadXRAM>
+ <uocXRam>0</uocXRam>
+ <RvdsVP>0</RvdsVP>
+ <hadIRAM2>0</hadIRAM2>
+ <hadIROM2>0</hadIROM2>
+ <StupSel>8</StupSel>
+ <useUlib>0</useUlib>
+ <EndSel>0</EndSel>
+ <uLtcg>0</uLtcg>
+ <RoSelD>3</RoSelD>
+ <RwSelD>3</RwSelD>
+ <CodeSel>0</CodeSel>
+ <OptFeed>0</OptFeed>
+ <NoZi1>0</NoZi1>
+ <NoZi2>0</NoZi2>
+ <NoZi3>0</NoZi3>
+ <NoZi4>0</NoZi4>
+ <NoZi5>0</NoZi5>
+ <Ro1Chk>0</Ro1Chk>
+ <Ro2Chk>0</Ro2Chk>
+ <Ro3Chk>0</Ro3Chk>
+ <Ir1Chk>1</Ir1Chk>
+ <Ir2Chk>0</Ir2Chk>
+ <Ra1Chk>0</Ra1Chk>
+ <Ra2Chk>0</Ra2Chk>
+ <Ra3Chk>0</Ra3Chk>
+ <Im1Chk>1</Im1Chk>
+ <Im2Chk>0</Im2Chk>
+ <OnChipMemories>
+ <Ocm1>
+ <Type>0</Type>
+ <StartAddress>0x0</StartAddress>
+ <Size>0x0</Size>
+ </Ocm1>
+ <Ocm2>
+ </Ocm2>
+ <Ocm3>
+ </Ocm3>
+ <Ocm4>
+ </Ocm4>
+ <Ocm5>
+ </Ocm5>
+ <Ocm6>
+ </Ocm6>
+ <IRAM>
+ <StartAddress>0x20000000</StartAddress>
+ <Size>0x10000</Size>
+ </IRAM>
+ <IROM>
+ <Type>1</Type>
+ <Size>0x40000</Size>
+ </IROM>
+ <XRAM>
+ </XRAM>
+ <OCR_RVCT1>
+ </OCR_RVCT1>
+ <OCR_RVCT2>
+ </OCR_RVCT2>
+ <OCR_RVCT3>
+ </OCR_RVCT3>
+ <OCR_RVCT4>
+ </OCR_RVCT4>
+ <OCR_RVCT5>
+ </OCR_RVCT5>
+ <OCR_RVCT6>
+ </OCR_RVCT6>
+ <OCR_RVCT7>
+ </OCR_RVCT7>
+ <OCR_RVCT8>
+ </OCR_RVCT8>
+ <OCR_RVCT9>
+ </OCR_RVCT9>
+ <OCR_RVCT10>
+ </OCR_RVCT10>
+ </OnChipMemories>
+ <RvctStartVector></RvctStartVector>
+ </ArmAdsMisc>
+ <Cads>
+ <interw>1</interw>
+ <Optim>1</Optim>
+ <oTime>0</oTime>
+ <SplitLS>0</SplitLS>
+ <OneElfS>0</OneElfS>
+ <Strict>0</Strict>
+ <EnumInt>0</EnumInt>
+ <PlainCh>0</PlainCh>
+ <Ropi>0</Ropi>
+ <Rwpi>0</Rwpi>
+ <wLevel>0</wLevel>
+ <uThumb>0</uThumb>
+ <uSurpInc>0</uSurpInc>
+ <uC99>0</uC99>
+ <useXO>0</useXO>
+ <VariousControls>
+ <MiscControls></MiscControls>
+ <Define>RT_USING_ARM_LIBC</Define>
+ <Undefine></Undefine>
+ <IncludePath>.;..\..\include;applications;board;CMSIS;drivers;libraries\sys_config;libraries\mss_gpio;libraries\mss_uart;..\..\libcpu\arm\common;..\..\libcpu\arm\cortex-m3;..\..\components\drivers\include;..\..\components\drivers\include;..\..\components\drivers\include;..\..\components\finsh;..\..\components\libc\compilers\armlibc;..\..\components\libc\compilers\common</IncludePath>
+ </VariousControls>
+ </Cads>
+ <Aads>
+ <thumb>0</thumb>
+ <SwStkChk>0</SwStkChk>
+ <NoWarn>0</NoWarn>
+ <Define></Define>
+ </Aads>
+ <LDads>
+ <umfTarg>0</umfTarg>
+ <noStLib>0</noStLib>
+ <RepFail>1</RepFail>
+ <useFile>0</useFile>
+ <TextAddressRange>0x00000000</TextAddressRange>
+ <DataAddressRange>0x20000000</DataAddressRange>
+ <pXoBase></pXoBase>
+ <ScatterFile>.\applications\link.sct</ScatterFile>
+ <IncludeLibs></IncludeLibs>
+ <IncludeLibsPath></IncludeLibsPath>
+ <Misc></Misc>
+ <LinkerInputFile></LinkerInputFile>
+ <DisabledWarnings></DisabledWarnings>
+ </LDads>
+ </TargetArmAds>
+ <Groups>
+ <Files>
+ <FileName>clock.c</FileName>
+ <FilePath>..\..\src\clock.c</FilePath>
+ <FileName>components.c</FileName>
+ <FilePath>..\..\src\components.c</FilePath>
+ <FileName>device.c</FileName>
+ <FilePath>..\..\src\device.c</FilePath>
+ <FileName>idle.c</FileName>
+ <FilePath>..\..\src\idle.c</FilePath>
+ <FileName>ipc.c</FileName>
+ <FilePath>..\..\src\ipc.c</FilePath>
+ <FileName>irq.c</FileName>
+ <FilePath>..\..\src\irq.c</FilePath>
+ <FileName>kservice.c</FileName>
+ <FilePath>..\..\src\kservice.c</FilePath>
+ <FileName>mem.c</FileName>
+ <FilePath>..\..\src\mem.c</FilePath>
+ <FileName>mempool.c</FileName>
+ <FilePath>..\..\src\mempool.c</FilePath>
+ <FileName>object.c</FileName>
+ <FilePath>..\..\src\object.c</FilePath>
+ <FileName>scheduler.c</FileName>
+ <FilePath>..\..\src\scheduler.c</FilePath>
+ <FileName>signal.c</FileName>
+ <FilePath>..\..\src\signal.c</FilePath>
+ <FileName>thread.c</FileName>
+ <FilePath>..\..\src\thread.c</FilePath>
+ <FileName>timer.c</FileName>
+ <FilePath>..\..\src\timer.c</FilePath>
+ </Files>
+ <FileName>main.c</FileName>
+ <FilePath>applications\main.c</FilePath>
+ <FileName>board.c</FileName>
+ <FilePath>board\board.c</FilePath>
+ <FileName>config.c</FileName>
+ <FilePath>board\config.c</FilePath>
+ <FileName>core_cm3.c</FileName>
+ <FilePath>CMSIS\core_cm3.c</FilePath>
+ <FileName>system_m2sxxx.c</FileName>
+ <FilePath>CMSIS\system_m2sxxx.c</FilePath>
+ <FileName>startup_m2sxxx.s</FileName>
+ <FilePath>CMSIS\startup_arm\startup_m2sxxx.s</FilePath>
+ <FileName>drv_uart.c</FileName>
+ <FilePath>drivers\drv_uart.c</FilePath>
+ <FileName>drv_gpio.c</FileName>
+ <FilePath>drivers\drv_gpio.c</FilePath>
+ <FileName>sys_config.c</FileName>
+ <FilePath>libraries\sys_config\sys_config.c</FilePath>
+ <FileName>mss_gpio.c</FileName>
+ <FilePath>libraries\mss_gpio\mss_gpio.c</FilePath>
+ <FileName>mss_uart.c</FileName>
+ <FilePath>libraries\mss_uart\mss_uart.c</FilePath>
+ <FileName>backtrace.c</FileName>
+ <FilePath>..\..\libcpu\arm\common\backtrace.c</FilePath>
+ <FileName>div0.c</FileName>
+ <FilePath>..\..\libcpu\arm\common\div0.c</FilePath>
+ <FileName>showmem.c</FileName>
+ <FilePath>..\..\libcpu\arm\common\showmem.c</FilePath>
+ <FileName>cpuport.c</FileName>
+ <FilePath>..\..\libcpu\arm\cortex-m3\cpuport.c</FilePath>
+ <FileName>context_rvds.S</FileName>
+ <FilePath>..\..\libcpu\arm\cortex-m3\context_rvds.S</FilePath>
+ <FileName>pin.c</FileName>
+ <FilePath>..\..\components\drivers\misc\pin.c</FilePath>
+ <FileName>serial.c</FileName>
+ <FilePath>..\..\components\drivers\serial\serial.c</FilePath>
+ <FileName>completion.c</FileName>
+ <FilePath>..\..\components\drivers\src\completion.c</FilePath>
+ <FileName>dataqueue.c</FileName>
+ <FilePath>..\..\components\drivers\src\dataqueue.c</FilePath>
+ <FileName>pipe.c</FileName>
+ <FilePath>..\..\components\drivers\src\pipe.c</FilePath>
+ <FileName>ringblk_buf.c</FileName>
+ <FilePath>..\..\components\drivers\src\ringblk_buf.c</FilePath>
+ <FileName>ringbuffer.c</FileName>
+ <FilePath>..\..\components\drivers\src\ringbuffer.c</FilePath>
+ <FileName>waitqueue.c</FileName>
+ <FilePath>..\..\components\drivers\src\waitqueue.c</FilePath>
+ <FileName>workqueue.c</FileName>
+ <FilePath>..\..\components\drivers\src\workqueue.c</FilePath>
+ <FileName>shell.c</FileName>
+ <FilePath>..\..\components\finsh\shell.c</FilePath>
+ <FileName>cmd.c</FileName>
+ <FilePath>..\..\components\finsh\cmd.c</FilePath>
+ <FileName>msh.c</FileName>
+ <FilePath>..\..\components\finsh\msh.c</FilePath>
+ <FileName>libc.c</FileName>
+ <FilePath>..\..\components\libc\compilers\armlibc\libc.c</FilePath>
+ <FileName>mem_std.c</FileName>
+ <FilePath>..\..\components\libc\compilers\armlibc\mem_std.c</FilePath>
+ <FileName>stubs.c</FileName>
+ <FilePath>..\..\components\libc\compilers\armlibc\stubs.c</FilePath>
+ <FileName>time.c</FileName>
+ <FilePath>..\..\components\libc\compilers\common\time.c</FilePath>
+ </Groups>
+ </Targets>
+</Project>
@@ -0,0 +1,667 @@
+<Project xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_projx.xsd">
+ <SchemaVersion>2.1</SchemaVersion>
+ <pCCUsed>5060750::V5.06 update 6 (build 750)::ARMCC</pCCUsed>
+ <uAC6>0</uAC6>
+ <PackID>Microsemi.M2Sxxx.1.0.64</PackID>
+ <PackURL>http://cores.actel-ip.com/CMSIS-Pack</PackURL>
+ <Cpu>IRAM(0x20000000,0x10000) IROM(0x00000000,0x40000) CPUTYPE("Cortex-M3") CLOCK(12000000) ELITTLE</Cpu>
+ <FlashDriverDll>UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0M2Sxxx_256 -FS00 -FL040000 -FP0($$Device:M2S010$Flash\M2Sxxx_256.FLM))</FlashDriverDll>
+ <DeviceId>0</DeviceId>
+ <RegisterFile>$$Device:M2S010$CMSIS\m2sxxx.h</RegisterFile>
+ <SFDFile>$$Device:M2S010$SVD\M2Sxxx.svd</SFDFile>
+ <nStopB1X>0</nStopB1X>
+ <nStopB2X>0</nStopB2X>
+ <nStopA1X>0</nStopA1X>
+ <nStopA2X>0</nStopA2X>
+ <SimDllArguments> </SimDllArguments>
+ <TargetDllArguments></TargetDllArguments>
+ <Capability>1</Capability>
+ <RvdsMve>0</RvdsMve>
+ <nSecure>0</nSecure>
+ <NoZi4>1</NoZi4>
+ <OneElfS>1</OneElfS>
+ <wLevel>2</wLevel>
+ <uGnu>0</uGnu>
+ <v6Lang>1</v6Lang>
+ <v6LangP>1</v6LangP>
+ <vShortEn>1</vShortEn>
+ <vShortWch>1</vShortWch>
+ <v6Lto>0</v6Lto>
+ <v6WtE>0</v6WtE>
+ <v6Rtti>0</v6Rtti>
+ <uClangAs>0</uClangAs>
+ <RTE>
+ <apis/>
+ <components/>
+ <files/>
+ </RTE>
@@ -0,0 +1,165 @@
+#ifndef RT_CONFIG_H__
+#define RT_CONFIG_H__
+/* Automatically generated file; DO NOT EDIT. */
+/* RT-Thread Configuration */
+/* RT-Thread Kernel */
+#define RT_NAME_MAX 8
+#define RT_ALIGN_SIZE 4
+#define RT_THREAD_PRIORITY_32
+#define RT_THREAD_PRIORITY_MAX 32
+#define RT_TICK_PER_SECOND 100
+#define RT_USING_OVERFLOW_CHECK
+#define RT_USING_HOOK
+#define RT_USING_IDLE_HOOK
+#define RT_IDLE_HOOK_LIST_SIZE 4
+#define IDLE_THREAD_STACK_SIZE 256
+#define RT_USING_TIMER_SOFT
+#define RT_TIMER_THREAD_PRIO 4
+#define RT_TIMER_THREAD_STACK_SIZE 512
+#define RT_DEBUG
+/* Inter-Thread communication */
+#define RT_USING_SEMAPHORE
+#define RT_USING_MUTEX
+#define RT_USING_EVENT
+#define RT_USING_MAILBOX
+#define RT_USING_MESSAGEQUEUE
+/* Memory Management */
+#define RT_USING_MEMPOOL
+#define RT_USING_SMALL_MEM
+#define RT_USING_HEAP
+/* Kernel Device Object */
+#define RT_USING_DEVICE
+#define RT_USING_CONSOLE
+#define RT_CONSOLEBUF_SIZE 128
+#define RT_CONSOLE_DEVICE_NAME "uart0"
+#define RT_VER_NUM 0x40003
+/* RT-Thread Components */
+#define RT_USING_COMPONENTS_INIT
+#define RT_USING_USER_MAIN
+#define RT_MAIN_THREAD_STACK_SIZE 2048
+#define RT_MAIN_THREAD_PRIORITY 10
+/* C++ features */
+/* Command shell */
+#define RT_USING_FINSH
+#define FINSH_THREAD_NAME "tshell"
+#define FINSH_USING_HISTORY
+#define FINSH_HISTORY_LINES 5
+#define FINSH_USING_SYMTAB
+#define FINSH_USING_DESCRIPTION
+#define FINSH_THREAD_PRIORITY 20
+#define FINSH_THREAD_STACK_SIZE 1024
+#define FINSH_CMD_SIZE 80
+#define FINSH_USING_MSH
+#define FINSH_USING_MSH_DEFAULT
+#define FINSH_USING_MSH_ONLY
+#define FINSH_ARG_MAX 10
+/* Device virtual file system */
+/* Device Drivers */
+#define RT_USING_DEVICE_IPC
+#define RT_PIPE_BUFSZ 512
+#define RT_USING_SERIAL
+#define RT_SERIAL_USING_DMA
+#define RT_SERIAL_RB_BUFSZ 64
+#define RT_USING_PIN
+/* Using USB */
+/* POSIX layer and C standard library */
+#define RT_USING_LIBC
+/* Network */
+/* Socket abstraction layer */
+/* Network interface device */
+/* light weight TCP/IP stack */
+/* AT commands */
+/* VBUS(Virtual Software BUS) */
+/* Utilities */
+/* RT-Thread online packages */
+/* IoT - internet of things */
+/* Wi-Fi */
+/* Marvell WiFi */
+/* Wiced WiFi */
+/* IoT Cloud */
+/* security packages */
+/* language packages */
+/* multimedia packages */
+/* tools packages */
+/* system packages */
+/* peripheral libraries and drivers */
+/* miscellaneous packages */
+/* samples: kernel and components samples */
+/* Hardware Drivers Config */
+/* On-chip Peripheral Drivers */
+/* UART Drivers */
+#define BSP_USING_UART0
+#define BSP_USING_UART1
+/* GPIO Drivers */
+#define BSP_USING_GPIO
+#define SOC_SF2_M2S010
@@ -0,0 +1,82 @@
+CROSS_TOOL = 'gcc'
+if os.getenv('RTT_CC'):
+ CROSS_TOOL = os.getenv('RTT_CC')
+# device options
+ARCH = 'arm'
+CPU = 'cortex-m3'
+if CROSS_TOOL == 'gcc':
+ PLATFORM = 'gcc'
+ EXEC_PATH = 'D:/Program/env/tools/gnu_gcc/arm_gcc/mingw/bin'
+elif CROSS_TOOL == 'keil':
+ PLATFORM = 'armcc'
+ EXEC_PATH = 'D:/Program/Keil_v5'
+if os.getenv('RTT_EXEC_PATH'):
+ EXEC_PATH = os.getenv('RTT_EXEC_PATH')
+# BUILD = 'debug'
+BUILD = 'release'
+if PLATFORM == 'gcc':
+ PREFIX = 'arm-none-eabi-'
+ CC = PREFIX + 'gcc'
+ CXX = PREFIX + 'g++'
+ AS = PREFIX + 'gcc'
+ AR = PREFIX + 'ar'
+ LINK = PREFIX + 'gcc'
+ TARGET_EXT = 'elf'
+ SIZE = PREFIX + 'size'
+ OBJDUMP = PREFIX + 'objdump'
+ OBJCPY = PREFIX + 'objcopy'
+ DEVICE = ' -mcpu=cortex-m3 -mthumb -ffunction-sections -fdata-sections -Wall'
+ CFLAGS = DEVICE + ' -std=c99'
+ AFLAGS = ' -c' + DEVICE + ' -x assembler-with-cpp -Wa,-mimplicit-it=thumb '
+ # link script file path
+ LFLAGS = DEVICE + ' -Wl,--gc-sections,-Map=rtthread.map,-cref,-u,Reset_Handler -T CMSIS/startup_gcc/debug-in-microsemi-smartfusion2-envm.ld'
+ CPATH = ''
+ LPATH = ''
+ if BUILD == 'debug':
+ CFLAGS += ' -O0 -gdwarf-2 -g'
+ AFLAGS += ' -gdwarf-2'
+ CFLAGS += ' -O2'
+ POST_ACTION = OBJCPY + ' -O binary $TARGET rtthread.bin\n' + OBJCPY + ' -O ihex $TARGET rtthread.hex\n' + SIZE + ' $TARGET \n'
+elif PLATFORM == 'armcc':
+ # toolchains
+ CC = 'armcc'
+ AS = 'armasm'
+ AR = 'armar'
+ LINK = 'armlink'
+ TARGET_EXT = 'axf'
+ DEVICE = ' --cpu ' + CPU
+ CFLAGS = '-c ' + DEVICE + ' --apcs=interwork --c99'
+ AFLAGS = DEVICE + ' --apcs=interwork '
+ # link scatter file path
+ LFLAGS = DEVICE + ' --scatter "applications/link.sct" --info sizes --info totals --info unused --info veneers --list rtthread.map --strict'
+ CFLAGS += ' -I' + EXEC_PATH + '/ARM/ARMCC/INC'
+ LFLAGS += ' --libpath ' + EXEC_PATH + '/ARM/ARMCC/LIB'
+ CFLAGS += ' -D__MICROLIB '
+ AFLAGS += ' --pd "__MICROLIB SETA 1" '
+ LFLAGS += ' --library_type=microlib '
+ EXEC_PATH += '/arm/armcc/bin/'
+ CFLAGS += ' -g -O0'
+ AFLAGS += ' -g'
+ POST_ACTION = 'fromelf --bin $TARGET --output rtthread.bin \nfromelf -z $TARGET'
@@ -0,0 +1,187 @@
+ <GroupName>Source Group 1</GroupName>
@@ -0,0 +1,185 @@
@@ -0,0 +1,412 @@
@@ -0,0 +1,395 @@
@@ -35,7 +35,7 @@
#define HAL_MODULE_ENABLED
/*#define HAL_ADC_MODULE_ENABLED */
/*#define HAL_CRYP_MODULE_ENABLED */
-/*#define HAL_CAN_MODULE_ENABLED */
+#define HAL_CAN_MODULE_ENABLED
/*#define HAL_CAN_LEGACY_MODULE_ENABLED */
/*#define HAL_CEC_MODULE_ENABLED */
/*#define HAL_CORTEX_MODULE_ENABLED */
@@ -294,6 +294,73 @@ void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
}
+* @brief CAN MSP Initialization
+* This function configures the hardware resources used in this example
+* @param hcan: CAN handle pointer
+* @retval None
+void HAL_CAN_MspInit(CAN_HandleTypeDef* hcan)
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(hcan->Instance==CAN1)
+ /* USER CODE BEGIN CAN1_MspInit 0 */
+ /* USER CODE END CAN1_MspInit 0 */
+ /* Peripheral clock enable */
+ __HAL_RCC_CAN1_CLK_ENABLE();
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**CAN GPIO Configuration
+ PA11 ------> CAN_RX
+ PA12 ------> CAN_TX
+ GPIO_InitStruct.Pin = GPIO_PIN_11;
+ GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+ GPIO_InitStruct.Pin = GPIO_PIN_12;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
+ /* USER CODE BEGIN CAN1_MspInit 1 */
+ /* USER CODE END CAN1_MspInit 1 */
+* @brief CAN MSP De-Initialization
+* This function freeze the hardware resources used in this example
+void HAL_CAN_MspDeInit(CAN_HandleTypeDef* hcan)
+ /* USER CODE BEGIN CAN1_MspDeInit 0 */
+ /* USER CODE END CAN1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_CAN1_CLK_DISABLE();
+ HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
+ /* USER CODE BEGIN CAN1_MspDeInit 1 */
+ /* USER CODE END CAN1_MspDeInit 1 */
static uint32_t FSMC_Initialized = 0;
@@ -188,7 +188,18 @@ menu "On-chip Peripheral Drivers"
bool "Enable ADC1"
default n
+ menuconfig BSP_USING_CAN
+ bool "Enable CAN"
+ select RT_USING_CAN
+ if BSP_USING_CAN
+ config BSP_USING_CAN1
+ bool "Enable CAN1"
+ config BSP_USING_CAN2
+ bool "Enable CAN2"
config BSP_USING_ON_CHIP_FLASH
bool "Enable on-chip FLASH"
@@ -222,9 +222,6 @@ void HAL_UART_MspInit(UART_HandleTypeDef* huart)
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(huart->Instance==USART1)
- /* USER CODE BEGIN USART1_MspInit 0 */
- /* USER CODE END USART1_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_USART1_CLK_ENABLE();
@@ -242,12 +239,28 @@ void HAL_UART_MspInit(UART_HandleTypeDef* huart)
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
- /* USER CODE BEGIN USART1_MspInit 1 */
- /* USER CODE END USART1_MspInit 1 */
+ if(huart->Instance==USART2)
+ __HAL_RCC_USART2_CLK_ENABLE();
+ /**USART1 GPIO Configuration
+ PA2 ------> USART2_TX
+ PA3 ------> USART2_RX
+ GPIO_InitStruct.Pin = GPIO_PIN_2;
+ GPIO_InitStruct.Pin = GPIO_PIN_3;
/**
@@ -37,6 +37,15 @@ menu "On-chip Peripheral Drivers"
bool "Enable UART1 RX DMA"
depends on BSP_USING_UART1 && RT_SERIAL_USING_DMA
+ config BSP_USING_UART2
+ bool "Enable UART2"
+ config BSP_UART2_RX_USING_DMA
+ bool "Enable UART2 RX DMA"
+ depends on BSP_USING_UART2 && RT_SERIAL_USING_DMA
menuconfig BSP_USING_ONCHIP_RTC
@@ -19,7 +19,9 @@
#define DBG_LVL DBG_INFO
#include <rtdbg.h>
+#ifndef MIN
#define MIN(a, b) ((a) < (b) ? (a) : (b))
enum
@@ -17,8 +17,7 @@
#define RT_DATAQUEUE_EVENT_LWM 0x03
struct rt_data_item;
-#define RT_DATAQUEUE_SIZE(dq) ((dq)->put_index - (dq)->get_index)
-#define RT_DATAQUEUE_EMPTY(dq) ((dq)->size - RT_DATAQUEUE_SIZE(dq))
/* data queue implementation */
struct rt_data_queue
@@ -26,10 +25,11 @@ struct rt_data_queue
rt_uint16_t size;
rt_uint16_t lwm;
- rt_bool_t waiting_lwm;
- rt_uint16_t get_index;
- rt_uint16_t put_index;
+ rt_uint16_t get_index : 15;
+ rt_uint16_t is_empty : 1;
+ rt_uint16_t put_index : 15;
+ rt_uint16_t is_full : 1;
struct rt_data_item *queue;
@@ -60,5 +60,6 @@ rt_err_t rt_data_queue_peak(struct rt_data_queue *queue,
rt_size_t *size);
void rt_data_queue_reset(struct rt_data_queue *queue);
rt_err_t rt_data_queue_deinit(struct rt_data_queue *queue);
+rt_uint16_t rt_data_queue_len(struct rt_data_queue *queue);
@@ -28,7 +28,7 @@ rt_data_queue_init(struct rt_data_queue *queue,
void (*evt_notify)(struct rt_data_queue *queue, rt_uint32_t event))
RT_ASSERT(queue != RT_NULL);
- RT_ASSERT((0x10000 % size) == 0);
+ RT_ASSERT(size > 0);
queue->evt_notify = evt_notify;
@@ -38,6 +38,8 @@ rt_data_queue_init(struct rt_data_queue *queue,
queue->get_index = 0;
queue->put_index = 0;
+ queue->is_empty = 1;
+ queue->is_full = 0;
rt_list_init(&(queue->suspended_push_list));
rt_list_init(&(queue->suspended_pop_list));
@@ -61,14 +63,14 @@ rt_err_t rt_data_queue_push(struct rt_data_queue *queue,
rt_thread_t thread;
rt_err_t result;
- RT_ASSERT(queue->magic == DATAQUEUE_MAGIC);
+ RT_ASSERT(queue->magic == DATAQUEUE_MAGIC);
result = RT_EOK;
thread = rt_thread_self();
level = rt_hw_interrupt_disable();
- while (queue->put_index - queue->get_index == queue->size)
+ while (queue->is_full)
/* queue is full */
if (timeout == 0)
@@ -109,9 +111,18 @@ rt_err_t rt_data_queue_push(struct rt_data_queue *queue,
if (result != RT_EOK) goto __exit;
- queue->queue[queue->put_index % queue->size].data_ptr = data_ptr;
- queue->queue[queue->put_index % queue->size].data_size = data_size;
+ queue->queue[queue->put_index].data_ptr = data_ptr;
+ queue->queue[queue->put_index].data_size = data_size;
queue->put_index += 1;
+ if (queue->put_index == queue->size)
+ queue->put_index = 0;
+ queue->is_empty = 0;
+ if (queue->put_index == queue->get_index)
+ queue->is_full = 1;
/* there is at least one thread in suspended list */
if (!rt_list_isempty(&(queue->suspended_pop_list)))
@@ -151,8 +162,8 @@ rt_err_t rt_data_queue_pop(struct rt_data_queue *queue,
RT_ASSERT(data_ptr != RT_NULL);
RT_ASSERT(size != RT_NULL);
@@ -160,7 +171,7 @@ rt_err_t rt_data_queue_pop(struct rt_data_queue *queue,
- while (queue->get_index == queue->put_index)
+ while (queue->is_empty)
/* queue is empty */
@@ -201,12 +212,20 @@ rt_err_t rt_data_queue_pop(struct rt_data_queue *queue,
goto __exit;
- *data_ptr = queue->queue[queue->get_index % queue->size].data_ptr;
- *size = queue->queue[queue->get_index % queue->size].data_size;
+ *data_ptr = queue->queue[queue->get_index].data_ptr;
+ *size = queue->queue[queue->get_index].data_size;
queue->get_index += 1;
+ if (queue->get_index == queue->size)
+ queue->get_index = 0;
- if ((queue->put_index - queue->get_index) <= queue->lwm)
+ if (rt_data_queue_len(queue) <= queue->lwm)
if (!rt_list_isempty(&(queue->suspended_push_list)))
@@ -251,20 +270,18 @@ rt_err_t rt_data_queue_peak(struct rt_data_queue *queue,
rt_ubase_t level;
- level = rt_hw_interrupt_disable();
- if (queue->get_index == queue->put_index)
+ if (queue->is_empty)
- rt_hw_interrupt_enable(level);
return -RT_EEMPTY;
rt_hw_interrupt_enable(level);
@@ -274,10 +291,20 @@ RTM_EXPORT(rt_data_queue_peak);
void rt_data_queue_reset(struct rt_data_queue *queue)
+ rt_ubase_t level;
struct rt_thread *thread;
- register rt_ubase_t temp;
+ RT_ASSERT(queue != RT_NULL);
RT_ASSERT(queue->magic == DATAQUEUE_MAGIC);
rt_enter_critical();
/* wakeup all suspend threads */
@@ -286,7 +313,7 @@ void rt_data_queue_reset(struct rt_data_queue *queue)
while (!rt_list_isempty(&(queue->suspended_pop_list)))
/* disable interrupt */
- temp = rt_hw_interrupt_disable();
/* get next suspend thread */
thread = rt_list_entry(queue->suspended_pop_list.next,
@@ -303,14 +330,14 @@ void rt_data_queue_reset(struct rt_data_queue *queue)
rt_thread_resume(thread);
/* enable interrupt */
- rt_hw_interrupt_enable(temp);
/* resume on push list */
while (!rt_list_isempty(&(queue->suspended_push_list)))
thread = rt_list_entry(queue->suspended_push_list.next,
@@ -327,7 +354,7 @@ void rt_data_queue_reset(struct rt_data_queue *queue)
rt_exit_critical();
@@ -339,19 +366,49 @@ rt_err_t rt_data_queue_deinit(struct rt_data_queue *queue)
rt_data_queue_reset(queue);
queue->magic = 0;
- rt_free(queue->queue);
+ rt_free(queue->queue);
return RT_EOK;
RTM_EXPORT(rt_data_queue_deinit);
+rt_uint16_t rt_data_queue_len(struct rt_data_queue *queue)
+ rt_int16_t len;
+ if (queue->put_index > queue->get_index)
+ len = queue->put_index - queue->get_index;
+ len = queue->size + queue->put_index - queue->get_index;
+ return len;
+RTM_EXPORT(rt_data_queue_len);
@@ -45,6 +45,9 @@ extern "C" {
#define RT_TOUCH_CTRL_SET_X_TO_Y (5) /* Set X Y coordinate exchange */
#define RT_TOUCH_CTRL_DISABLE_INT (6) /* Disable interrupt */
#define RT_TOUCH_CTRL_ENABLE_INT (7) /* Enable interrupt */
+#define RT_TOUCH_CTRL_POWER_ON (8) /* Touch Power On */
+#define RT_TOUCH_CTRL_POWER_OFF (9) /* Touch Power Off */
+#define RT_TOUCH_CTRL_GET_STATUS (10) /* Get Touch Power Status */
/* Touch event */
#define RT_TOUCH_EVENT_NONE (0) /* Touch none */
@@ -29,6 +29,8 @@ if GetDepend('RT_USING_DEVICE') == False:
if GetDepend('RT_USING_SMP') == False:
SrcRemove(src, ['cpu.c'])
-group = DefineGroup('Kernel', src, depend = [''], CPPPATH = CPPPATH)
+CPPDEFINES = ['__RTTHREAD__']
+group = DefineGroup('Kernel', src, depend = [''], CPPPATH = CPPPATH, CPPDEFINES = CPPDEFINES)
Return('group')
@@ -126,8 +126,8 @@ rt_err_t rt_memheap_detach(struct rt_memheap *heap)
RT_ASSERT(heap);
RT_ASSERT(rt_object_get_type(&heap->parent) == RT_Object_Class_MemHeap);
RT_ASSERT(rt_object_is_systemobject(&heap->parent));
- rt_object_detach(&(heap->lock.parent.parent));
+ rt_sem_detach(&heap->lock);
rt_object_detach(&(heap->parent));
/* Return a successful completion. */
@@ -55,6 +55,20 @@ $(if $(strip $(LOCALS)),$(eval $(LOCALS): $(S_SRC)
@$(CROSS_COMPILE)gcc $$(AFLAGS) -c $$< -o $$@))
endef
+define add_s_file
+$(eval S_SRC := $(1:$(BSP_ROOT)/%=%)) \
+$(eval S_SRC := $(S_SRC:$(RTT_ROOT)/%=%)) \
+$(eval SOBJ := $(1:%.s=%.o)) \
+$(eval SOBJ := $(SOBJ:$(BSP_ROOT)/%=$(BSP_BUILD_DIR)/%)) \
+$(eval SOBJ := $(SOBJ:$(RTT_ROOT)/%=$(RTT_BUILD_DIR)/%)) \
+$(eval LOCALS := $(addprefix $(BUILD_DIR)/,$(SOBJ))) \
+$(eval OBJS += $(LOCALS)) \
+$(if $(strip $(LOCALS)),$(eval $(LOCALS): $(S_SRC)
+ @if [ ! -d $$(@D) ]; then mkdir -p $$(@D); fi
+ @echo cc $$<
+ @$(CROSS_COMPILE)gcc $$(AFLAGS) -c $$< -o $$@))
+endef
add_flg = $(eval CFLAGS += $1) \
$(eval AFLAGS += $1) \
$(eval CXXFLAGS += $1)
@@ -89,6 +103,9 @@ $(if $(SRCS),$(foreach f,$(SRCS),$(call add_cxx_file,$(f))))
SRCS := $(strip $(filter %.S,$(SRC_FILES)))
$(if $(SRCS),$(foreach f,$(SRCS),$(call add_S_file,$(f))))
+SRCS := $(strip $(filter %.s,$(SRC_FILES)))
+$(if $(SRCS),$(foreach f,$(SRCS),$(call add_s_file,$(f))))
CFLAGS += $(CPPPATHS)
CXXFLAGS += $(CPPPATHS)
AFLAGS += $(CPPPATHS)