#define CPU_HARVARD 0
/// Valid pointers should be >= than this value (used for debug)
- #if (CPU_CM3_LM3S1968 || CPU_CM3_LM3S8962 || CPU_CM3_STM32F103RB)
+ #if (CPU_CM3_LM3S1968 || CPU_CM3_LM3S8962 || CPU_CM3_STM32F103RB || CPU_CM3_AT91SAM3)
#define CPU_RAM_START 0x20000000
#else
- #warning Fix CPU_RAM_START address for your Cortex-M3, default value set to 0x200
- #define CPU_RAM_START 0x200
+ #warning Fix CPU_RAM_START address for your Cortex-M3, default value set to 0x20000000
+ #define CPU_RAM_START 0x20000000
#endif
#if defined(__ARMEB__)
#include "kdebug_lm3s.c"
#elif CPU_CM3_STM32
#include "kdebug_stm32.c"
+#elif CPU_CM3_AT91SAM3
+ #include "kdebug_sam3.c"
/*#elif Add other families here */
#else
#error Unknown CPU
--- /dev/null
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction. Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License. This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \brief AT91SAM3 debug support (implementation).
+ *
+ * \author Stefano Fedrigo <aleph@develer.com>
+ */
+
+#include <cfg/cfg_debug.h>
+#include <cfg/macros.h> /* for BV() */
+
+#include <io/sam3_gpio.h>
+#include <io/sam3_pmc.h>
+#include <io/sam3_uart.h>
+
+
+#if CONFIG_KDEBUG_PORT == 0
+ #define UART_BASE UART0_BASE
+ #define UART_INT INT_UART0
+ #define UART_GPIO_BASE GPIO_PORTA_BASE
+ #ifdef CPU_CM3_AT91SAM3U
+ #define UART_PINS (BV(12) | BV(11))
+ #else
+ #define UART_PINS (BV(10) | BV(9))
+ #endif
+#elif (CONFIG_KDEBUG_PORT == 1) && !defined(CPU_CM3_AT91SAM3U)
+ #define UART_BASE UART1_BASE
+ #define UART_INT INT_UART1
+ #define UART_GPIO_BASE GPIO_PORTB_BASE
+ #define UART_PINS (BV(3) | BV(2))
+#else
+ #error "UART port not supported in this board"
+#endif
+
+// TODO: refactor serial simple functions and use them, see lm3s kdebug
+#define KDBG_WAIT_READY() while (!(HWREG(UART_BASE + UART_SR) & UART_SR_TXRDY)) {}
+#define KDBG_WAIT_TXDONE() while (!(HWREG(UART_BASE + UART_SR) & UART_SR_TXEMPTY)) {}
+
+#define KDBG_WRITE_CHAR(c) do { HWREG(UART_BASE + UART_THR) = (c); } while(0)
+
+/* Debug unit is used only for debug purposes so does not generate interrupts. */
+#define KDBG_MASK_IRQ(old) do { (void)old; } while(0)
+
+/* Debug unit is used only for debug purposes so does not generate interrupts. */
+#define KDBG_RESTORE_IRQ(old) do { (void)old; } while(0)
+
+typedef uint32_t kdbg_irqsave_t;
+
+
+INLINE void kdbg_hw_init(void)
+{
+ /* Disable PIO mode and set appropriate UART pins peripheral mode */
+ HWREG(UART_GPIO_BASE + GPIO_PDR) = UART_PINS;
+ HWREG(UART_GPIO_BASE + GPIO_ABCDSR1) &= ~UART_PINS;
+ HWREG(UART_GPIO_BASE + GPIO_ABCDSR2) &= ~UART_PINS;
+
+ /* Enable the peripheral clock */
+ PMC_PCER_R = UART_INT;
+
+ /* Reset and disable receiver & transmitter */
+ HWREG(UART_BASE + UART_CR) = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS;
+
+ /* Set mode: normal, no parity */
+ HWREG(UART_BASE + UART_MR) = UART_MR_PAR_NO;
+
+ /* Set baud rate */
+ HWREG(UART_BASE + UART_BRGR) = CPU_FREQ / CONFIG_KDEBUG_BAUDRATE / 16;
+
+ /* Enable receiver & transmitter */
+ HWREG(UART_BASE + UART_CR) = UART_CR_RXEN | UART_CR_TXEN;
+}
#include <io/lm3s.h>
#elif CPU_CM3_STM32
#include <io/stm32.h>
+#elif CPU_CM3_AT91SAM3
+ #include <io/sam3.h>
/*#elif Add other families here */
#else
#error Unknown CPU
--- /dev/null
+#
+#-*- coding: utf-8 -*-
+#
+# \file
+# <!--
+# This file is part of BeRTOS.
+#
+# Bertos is free software; you can redistribute it and/or modify
+# it under the terms of the GNU General Public License as published by
+# the Free Software Foundation; either version 2 of the License, or
+# (at your option) any later version.
+#
+# This program is distributed in the hope that it will be useful,
+# but WITHOUT ANY WARRANTY; without even the implied warranty of
+# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+# GNU General Public License for more details.
+#
+# You should have received a copy of the GNU General Public License
+# along with this program; if not, write to the Free Software
+# Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+#
+# As a special exception, you may use this file as part of a free software
+# library without restriction. Specifically, if other files instantiate
+# templates or use macros or inline functions from this file, or you compile
+# this file and link it with other files to produce an executable, this
+# file does not by itself cause the resulting executable to be covered by
+# the GNU General Public License. This exception does not however
+# invalidate any other reasons why the executable file might be covered by
+# the GNU General Public License.
+#
+# Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+#
+# -->
+#
+# General CPU info denfinition for Cortex-M3-based LM3S1968 board.
+#
+# This file contain all info for the BeRTOS wizard.
+#
+# \author Andrea Righi <arighi@develer.com>
+#
+#
+
+# Import the common settings for the path.
+include("cm3.common")
+
+# CPU type used for flashing/debugging
+MK_PROGRAMMER_CPU = "sam3"
+MK_FLASH_SCRIPT = PRG_SCRIPTS_DIR + "arm/flash-sam3.sh"
+
+# CPU default clock frequency
+CPU_DEFAULT_FREQ = "48000000UL"
+
+# Special CPU related tags.
+CPU_TAGS += ["sam3"]
+
+# Additional hw drivers.
+#MK_CPU_CSRC += DRV_DIR + "gpio_sam3.c " + DRV_DIR + "clock_sam3.c "
+
+# Short description of the cpu.
+CPU_DESC += [ "256 Kbytes on-chip flash memory",
+ "24 Kbytes on-chip SRAM memory" ]
+
+# GCC flags for this cpu.
+MK_CPU_CPPFLAGS += " -D__ARM_AT91SAM3N4__"
+MK_CPU_LDFLAGS += " -T " + SCRIPT_DIR + "at91sam3n4_ram.ld"
--- /dev/null
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction. Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License. This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \author Stefano Fedrigo <aleph@develer.com>
+ */
+
+#ifndef SAM3_H
+#define SAM3_H
+
+// TODO: refactor common cortex-m3 regs
+
+#include <cpu/detect.h>
+#include <cfg/compiler.h>
+
+#include "sam3_memmap.h"
+#include "sam3_gpio.h"
+#include "sam3_nvic.h"
+#include "sam3_uart.h"
+
+#endif /* SAM3_H */
--- /dev/null
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction. Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License. This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \brief AT91SAM3 GPIO hardware definitions.
+ */
+
+#ifndef SAM3_GPIO_H
+#define SAM3_GPIO_H
+
+/**
+ * GPIO registers base addresses.
+ */
+/*\{*/
+#define GPIO_PORTA_BASE 0x400E0E00
+#define GPIO_PORTB_BASE 0x400E1000
+#define GPIO_PORTC_BASE 0x400E1200
+/*\}*/
+
+/**
+ * GPIO register offsets.
+ */
+/*\{*/
+#define GPIO_PER 0x00 //< PIO Enable Register
+#define GPIO_PDR 0x04 //< PIO Disable Register
+#define GPIO_PSR 0x08 //< PIO Status Register
+#define GPIO_OER 0x10 //< Output Enable Register
+#define GPIO_ODR 0x14 //< Output Disable Register
+#define GPIO_OSR 0x18 //< Output Status Register
+#define GPIO_IFER 0x20 //< Glitch Input Filter Enable Register
+#define GPIO_IFDR 0x24 //< Glitch Input Filter Disable Register
+#define GPIO_IFSR 0x28 //< Glitch Input Filter Status Register
+#define GPIO_SODR 0x30 //< Set Output Data Register
+#define GPIO_CODR 0x34 //< Clear Output Data Register
+#define GPIO_ODSR 0x38 //< Output Data Status Register
+#define GPIO_PDSR 0x3C //< Pin Data Status Register
+#define GPIO_IER 0x40 //< Interrupt Enable Register
+#define GPIO_IDR 0x44 //< Interrupt Disable Register
+#define GPIO_IMR 0x48 //< Interrupt Mask Register
+#define GPIO_ISR 0x4C //< Interrupt Status Register
+#define GPIO_MDER 0x50 //< Multi-driver Enable Register
+#define GPIO_MDDR 0x54 //< Multi-driver Disable Register
+#define GPIO_MDSR 0x58 //< Multi-driver Status Register
+#define GPIO_PUDR 0x60 //< Pull-up Disable Register
+#define GPIO_PUER 0x64 //< Pull-up Enable Register
+#define GPIO_PUSR 0x68 //< Pad Pull-up Status Register
+#define GPIO_ABCDSR1 0x70 //< Peripheral Select Register 1
+#define GPIO_ABCDSR2 0x74 //< Peripheral Select Register 2
+#define GPIO_IFSCDR 0x80 //< Input Filter Slow Clock Disable Register
+#define GPIO_IFSCER 0x84 //< Input Filter Slow Clock Enable Register
+#define GPIO_IFSCSR 0x88 //< Input Filter Slow Clock Status Register
+#define GPIO_SCDR 0x8C //< Slow Clock Divider Debouncing Register
+#define GPIO_PPDDR 0x90 //< Pad Pull-down Disable Register
+#define GPIO_PPDER 0x94 //< Pad Pull-down Enable Register
+#define GPIO_PPDSR 0x98 //< Pad Pull-down Status Register
+#define GPIO_OWER 0xA0 //< Output Write Enable
+#define GPIO_OWDR 0xA4 //< Output Write Disable
+#define GPIO_OWSR 0xA8 //< Output Write Status Register
+#define GPIO_AIMER 0xB0 //< Additional Interrupt Modes Enable Register
+#define GPIO_AIMDR 0xB4 //< Additional Interrupt Modes Disables Register
+#define GPIO_AIMMR 0xB8 //< Additional Interrupt Modes Mask Register
+#define GPIO_ESR 0xC0 //< Edge Select Register
+#define GPIO_LSR 0xC4 //< Level Select Register
+#define GPIO_ELSR 0xC8 //< Edge/Level Status Register
+#define GPIO_FELLSR 0xD0 //< Falling Edge/Low Level Select Register
+#define GPIO_REHLSR 0xD4 //< Rising Edge/ High Level Select Register
+#define GPIO_FRLHSR 0xD8 //< Fall/Rise - Low/High Status Register
+#define GPIO_LOCKSR 0xE0 //< Lock Status
+#define GPIO_WPMR 0xE4 //< Write Protect Mode Register
+#define GPIO_WPSR 0xE8 //< Write Protect Status Register
+#define GPIO_SCHMITT 0x100 //< Schmitt Trigger Register
+/*\}*/
+
+#endif /* SAM3_GPIO_H */
--- /dev/null
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction. Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License. This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \brief AT91SAM3 memory map.
+ */
+
+#ifndef STM32_MEMMAP_H
+#define STM32_MEMMAP_H
+
+/* Peripheral and SRAM base address in the alias region */
+#define PERIPH_BB_BASE (0x42000000)
+#define SRAM_BB_BASE (0x22000000)
+
+/* Peripheral and SRAM base address in the bit-band region */
+#define SRAM_BASE (0x20000000)
+#define PERIPH_BASE (0x40000000)
+
+/* Flash refisters base address */
+#define FLASH_BASE (0x40022000)
+/* Flash Option Bytes base address */
+#define OB_BASE (0x1FFFF800)
+
+/* Peripheral memory map */
+#define APB1PERIPH_BASE (PERIPH_BASE)
+#define APB2PERIPH_BASE (PERIPH_BASE + 0x10000)
+#define AHBPERIPH_BASE (PERIPH_BASE + 0x20000)
+
+#define TIM2_BASE (APB1PERIPH_BASE + 0x0000)
+#define TIM3_BASE (APB1PERIPH_BASE + 0x0400)
+#define TIM4_BASE (APB1PERIPH_BASE + 0x0800)
+#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00)
+#define TIM6_BASE (APB1PERIPH_BASE + 0x1000)
+#define TIM7_BASE (APB1PERIPH_BASE + 0x1400)
+#define RTC_BASE (APB1PERIPH_BASE + 0x2800)
+#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00)
+#define IWDG_BASE (APB1PERIPH_BASE + 0x3000)
+#define SPI2_BASE (APB1PERIPH_BASE + 0x3800)
+#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00)
+#define USART2_BASE (APB1PERIPH_BASE + 0x4400)
+#define USART3_BASE (APB1PERIPH_BASE + 0x4800)
+#define UART4_BASE (APB1PERIPH_BASE + 0x4C00)
+#define UART5_BASE (APB1PERIPH_BASE + 0x5000)
+#define I2C1_BASE (APB1PERIPH_BASE + 0x5400)
+#define I2C2_BASE (APB1PERIPH_BASE + 0x5800)
+#define CAN1_BASE (APB1PERIPH_BASE + 0x6400)
+#define CAN2_BASE (APB1PERIPH_BASE + 0x6800)
+#define BKP_BASE (APB1PERIPH_BASE + 0x6C00)
+#define PWR_BASE (APB1PERIPH_BASE + 0x7000)
+#define DAC_BASE (APB1PERIPH_BASE + 0x7400)
+#define CEC_BASE (APB1PERIPH_BASE + 0x7800)
+
+#define AFIO_BASE (APB2PERIPH_BASE + 0x0000)
+#define EXTI_BASE (APB2PERIPH_BASE + 0x0400)
+#define GPIOA_BASE (APB2PERIPH_BASE + 0x0800)
+#define GPIOB_BASE (APB2PERIPH_BASE + 0x0C00)
+#define GPIOC_BASE (APB2PERIPH_BASE + 0x1000)
+#define GPIOD_BASE (APB2PERIPH_BASE + 0x1400)
+#define GPIOE_BASE (APB2PERIPH_BASE + 0x1800)
+#define GPIOF_BASE (APB2PERIPH_BASE + 0x1C00)
+#define GPIOG_BASE (APB2PERIPH_BASE + 0x2000)
+#define ADC1_BASE (APB2PERIPH_BASE + 0x2400)
+#define ADC2_BASE (APB2PERIPH_BASE + 0x2800)
+#define TIM1_BASE (APB2PERIPH_BASE + 0x2C00)
+#define SPI1_BASE (APB2PERIPH_BASE + 0x3000)
+#define TIM8_BASE (APB2PERIPH_BASE + 0x3400)
+#define USART1_BASE (APB2PERIPH_BASE + 0x3800)
+#define ADC3_BASE (APB2PERIPH_BASE + 0x3C00)
+#define TIM15_BASE (APB2PERIPH_BASE + 0x4000)
+#define TIM16_BASE (APB2PERIPH_BASE + 0x4400)
+#define TIM17_BASE (APB2PERIPH_BASE + 0x4800)
+
+#define SDIO_BASE (PERIPH_BASE + 0x18000)
+
+
+#define DMA1_BASE (AHBPERIPH_BASE + 0X0000)
+#define DMA1_CHANNEL1_BASE (AHBPERIPH_BASE + 0X0008)
+#define DMA1_CHANNEL2_BASE (AHBPERIPH_BASE + 0X001C)
+#define DMA1_CHANNEL3_BASE (AHBPERIPH_BASE + 0X0030)
+#define DMA1_CHANNEL4_BASE (AHBPERIPH_BASE + 0X0044)
+#define DMA1_CHANNEL5_BASE (AHBPERIPH_BASE + 0X0058)
+#define DMA1_CHANNEL6_BASE (AHBPERIPH_BASE + 0X006C)
+#define DMA1_CHANNEL7_BASE (AHBPERIPH_BASE + 0X0080)
+#define DMA2_BASE (AHBPERIPH_BASE + 0X0400)
+#define DMA2_CHANNEL1_BASE (AHBPERIPH_BASE + 0X0408)
+#define DMA2_CHANNEL2_BASE (AHBPERIPH_BASE + 0X041C)
+#define DMA2_CHANNEL3_BASE (AHBPERIPH_BASE + 0X0430)
+#define DMA2_CHANNEL4_BASE (AHBPERIPH_BASE + 0X0444)
+#define DMA2_CHANNEL5_BASE (AHBPERIPH_BASE + 0X0458)
+#define RCC_BASE (AHBPERIPH_BASE + 0X1000)
+#define CRC_BASE (AHBPERIPH_BASE + 0X3000)
+
+#define FLASH_R_BASE (AHBPERIPH_BASE + 0x2000) ///< Flash registers base address
+
+#define ETH_BASE (AHBPERIPH_BASE + 0x8000)
+#define ETH_MAC_BASE (ETH_BASE)
+#define ETH_MMC_BASE (ETH_BASE + 0x0100)
+#define ETH_PTP_BASE (ETH_BASE + 0x0700)
+#define ETH_DMA_BASE (ETH_BASE + 0x1000)
+
+#define FSMC_BANK1_R_BASE (FSMC_R_BASE + 0x0000) ///< FSMC Bank1 registers base address
+#define FSMC_BANK1E_R_BASE (FSMC_R_BASE + 0x0104) ///< FSMC Bank1E registers base address
+#define FSMC_BANK2_R_BASE (FSMC_R_BASE + 0x0060) ///< FSMC Bank2 registers base address
+#define FSMC_BANK3_R_BASE (FSMC_R_BASE + 0x0080) ///< FSMC Bank3 registers base address
+#define FSMC_BANK4_R_BASE (FSMC_R_BASE + 0x00A0) ///< FSMC Bank4 registers base address
+
+#define DBGMCU_BASE ((uint32_t)0xE0042000) ///< Debug MCU registers base address
+
+/* System Control Space memory map */
+#define SCS_BASE (0xE000E000)
+
+#define SYSTICK_BASE (SCS_BASE + 0x0010)
+#define NVIC_BASE (SCS_BASE + 0x0100)
+#define SCB_BASE (SCS_BASE + 0x0D00)
+
+#endif /* STM32_MEMMAP_H */
--- /dev/null
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction. Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License. This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \brief AT91SAM3 NVIC hardware.
+ */
+
+#ifndef SAM3_NVIC_H
+#define SAM3_NVIC_H
+
+/**
+ * The following are defines for the fault assignments.
+ */
+/*\{*/
+#define FAULT_NMI 2 ///< NMI fault
+#define FAULT_HARD 3 ///< Hard fault
+#define FAULT_MPU 4 ///< MPU fault
+#define FAULT_BUS 5 ///< Bus fault
+#define FAULT_USAGE 6 ///< Usage fault
+#define FAULT_SVCALL 11 ///< SVCall
+#define FAULT_DEBUG 12 ///< Debug monitor
+#define FAULT_PENDSV 14 ///< PendSV
+#define FAULT_SYSTICK 15 ///< System Tick
+/*\}*/
+
+/**
+ * NVIC registers (NVIC)
+ */
+/*\{*/
+#define NVIC_INT_TYPE_R (*((reg32_t *)0xE000E004))
+#define NVIC_ST_CTRL_R (*((reg32_t *)0xE000E010))
+#define NVIC_ST_RELOAD_R (*((reg32_t *)0xE000E014))
+#define NVIC_ST_CURRENT_R (*((reg32_t *)0xE000E018))
+#define NVIC_ST_CAL_R (*((reg32_t *)0xE000E01C))
+#define NVIC_EN0_R (*((reg32_t *)0xE000E100))
+#define NVIC_EN1_R (*((reg32_t *)0xE000E104))
+#define NVIC_DIS0_R (*((reg32_t *)0xE000E180))
+#define NVIC_DIS1_R (*((reg32_t *)0xE000E184))
+#define NVIC_PEND0_R (*((reg32_t *)0xE000E200))
+#define NVIC_PEND1_R (*((reg32_t *)0xE000E204))
+#define NVIC_UNPEND0_R (*((reg32_t *)0xE000E280))
+#define NVIC_UNPEND1_R (*((reg32_t *)0xE000E284))
+#define NVIC_ACTIVE0_R (*((reg32_t *)0xE000E300))
+#define NVIC_ACTIVE1_R (*((reg32_t *)0xE000E304))
+#define NVIC_PRI0_R (*((reg32_t *)0xE000E400))
+#define NVIC_PRI1_R (*((reg32_t *)0xE000E404))
+#define NVIC_PRI2_R (*((reg32_t *)0xE000E408))
+#define NVIC_PRI3_R (*((reg32_t *)0xE000E40C))
+#define NVIC_PRI4_R (*((reg32_t *)0xE000E410))
+#define NVIC_PRI5_R (*((reg32_t *)0xE000E414))
+#define NVIC_PRI6_R (*((reg32_t *)0xE000E418))
+#define NVIC_PRI7_R (*((reg32_t *)0xE000E41C))
+#define NVIC_PRI8_R (*((reg32_t *)0xE000E420))
+#define NVIC_PRI9_R (*((reg32_t *)0xE000E424))
+#define NVIC_PRI10_R (*((reg32_t *)0xE000E428))
+#define NVIC_CPUID_R (*((reg32_t *)0xE000ED00))
+#define NVIC_INT_CTRL_R (*((reg32_t *)0xE000ED04))
+#define NVIC_VTABLE_R (*((reg32_t *)0xE000ED08))
+#define NVIC_APINT_R (*((reg32_t *)0xE000ED0C))
+#define NVIC_SYS_CTRL_R (*((reg32_t *)0xE000ED10))
+#define NVIC_CFG_CTRL_R (*((reg32_t *)0xE000ED14))
+#define NVIC_SYS_PRI1_R (*((reg32_t *)0xE000ED18))
+#define NVIC_SYS_PRI2_R (*((reg32_t *)0xE000ED1C))
+#define NVIC_SYS_PRI3_R (*((reg32_t *)0xE000ED20))
+#define NVIC_SYS_HND_CTRL_R (*((reg32_t *)0xE000ED24))
+#define NVIC_FAULT_STAT_R (*((reg32_t *)0xE000ED28))
+#define NVIC_HFAULT_STAT_R (*((reg32_t *)0xE000ED2C))
+#define NVIC_DEBUG_STAT_R (*((reg32_t *)0xE000ED30))
+#define NVIC_MM_ADDR_R (*((reg32_t *)0xE000ED34))
+#define NVIC_FAULT_ADDR_R (*((reg32_t *)0xE000ED38))
+#define NVIC_MPU_TYPE_R (*((reg32_t *)0xE000ED90))
+#define NVIC_MPU_CTRL_R (*((reg32_t *)0xE000ED94))
+#define NVIC_MPU_NUMBER_R (*((reg32_t *)0xE000ED98))
+#define NVIC_MPU_BASE_R (*((reg32_t *)0xE000ED9C))
+#define NVIC_MPU_ATTR_R (*((reg32_t *)0xE000EDA0))
+#define NVIC_DBG_CTRL_R (*((reg32_t *)0xE000EDF0))
+#define NVIC_DBG_XFER_R (*((reg32_t *)0xE000EDF4))
+#define NVIC_DBG_DATA_R (*((reg32_t *)0xE000EDF8))
+#define NVIC_DBG_INT_R (*((reg32_t *)0xE000EDFC))
+#define NVIC_SW_TRIG_R (*((reg32_t *)0xE000EF00))
+/*\}*/
+
+/**
+ * The following are defines for the NVIC register addresses.
+ */
+/*\{*/
+#define NVIC_INT_TYPE 0xE000E004 ///< Interrupt Controller Type Reg
+#define NVIC_ST_CTRL 0xE000E010 ///< SysTick Control and Status Reg
+#define NVIC_ST_RELOAD 0xE000E014 ///< SysTick Reload Value Register
+#define NVIC_ST_CURRENT 0xE000E018 ///< SysTick Current Value Register
+#define NVIC_ST_CAL 0xE000E01C ///< SysTick Calibration Value Reg
+#define NVIC_EN0 0xE000E100 ///< IRQ 0 to 31 Set Enable Register
+#define NVIC_EN1 0xE000E104 ///< IRQ 32 to 63 Set Enable Register
+#define NVIC_DIS0 0xE000E180 ///< IRQ 0 to 31 Clear Enable Reg
+#define NVIC_DIS1 0xE000E184 ///< IRQ 32 to 63 Clear Enable Reg
+#define NVIC_PEND0 0xE000E200 ///< IRQ 0 to 31 Set Pending Register
+#define NVIC_PEND1 0xE000E204 ///< IRQ 32 to 63 Set Pending Reg
+#define NVIC_UNPEND0 0xE000E280 ///< IRQ 0 to 31 Clear Pending Reg
+#define NVIC_UNPEND1 0xE000E284 ///< IRQ 32 to 63 Clear Pending Reg
+#define NVIC_ACTIVE0 0xE000E300 ///< IRQ 0 to 31 Active Register
+#define NVIC_ACTIVE1 0xE000E304 ///< IRQ 32 to 63 Active Register
+#define NVIC_PRI0 0xE000E400 ///< IRQ 0 to 3 Priority Register
+#define NVIC_PRI1 0xE000E404 ///< IRQ 4 to 7 Priority Register
+#define NVIC_PRI2 0xE000E408 ///< IRQ 8 to 11 Priority Register
+#define NVIC_PRI3 0xE000E40C ///< IRQ 12 to 15 Priority Register
+#define NVIC_PRI4 0xE000E410 ///< IRQ 16 to 19 Priority Register
+#define NVIC_PRI5 0xE000E414 ///< IRQ 20 to 23 Priority Register
+#define NVIC_PRI6 0xE000E418 ///< IRQ 24 to 27 Priority Register
+#define NVIC_PRI7 0xE000E41C ///< IRQ 28 to 31 Priority Register
+#define NVIC_PRI8 0xE000E420 ///< IRQ 32 to 35 Priority Register
+#define NVIC_PRI9 0xE000E424 ///< IRQ 36 to 39 Priority Register
+#define NVIC_PRI10 0xE000E428 ///< IRQ 40 to 43 Priority Register
+#define NVIC_PRI11 0xE000E42C ///< IRQ 44 to 47 Priority Register
+#define NVIC_PRI12 0xE000E430 ///< IRQ 48 to 51 Priority Register
+#define NVIC_PRI13 0xE000E434 ///< IRQ 52 to 55 Priority Register
+#define NVIC_CPUID 0xE000ED00 ///< CPUID Base Register
+#define NVIC_INT_CTRL 0xE000ED04 ///< Interrupt Control State Register
+#define NVIC_VTABLE 0xE000ED08 ///< Vector Table Offset Register
+#define NVIC_APINT 0xE000ED0C ///< App. Int & Reset Control Reg
+#define NVIC_SYS_CTRL 0xE000ED10 ///< System Control Register
+#define NVIC_CFG_CTRL 0xE000ED14 ///< Configuration Control Register
+#define NVIC_SYS_PRI1 0xE000ED18 ///< Sys. Handlers 4 to 7 Priority
+#define NVIC_SYS_PRI2 0xE000ED1C ///< Sys. Handlers 8 to 11 Priority
+#define NVIC_SYS_PRI3 0xE000ED20 ///< Sys. Handlers 12 to 15 Priority
+#define NVIC_SYS_HND_CTRL 0xE000ED24 ///< System Handler Control and State
+#define NVIC_FAULT_STAT 0xE000ED28 ///< Configurable Fault Status Reg
+#define NVIC_HFAULT_STAT 0xE000ED2C ///< Hard Fault Status Register
+#define NVIC_DEBUG_STAT 0xE000ED30 ///< Debug Status Register
+#define NVIC_MM_ADDR 0xE000ED34 ///< Mem Manage Address Register
+#define NVIC_FAULT_ADDR 0xE000ED38 ///< Bus Fault Address Register
+#define NVIC_MPU_TYPE 0xE000ED90 ///< MPU Type Register
+#define NVIC_MPU_CTRL 0xE000ED94 ///< MPU Control Register
+#define NVIC_MPU_NUMBER 0xE000ED98 ///< MPU Region Number Register
+#define NVIC_MPU_BASE 0xE000ED9C ///< MPU Region Base Address Register
+#define NVIC_MPU_ATTR 0xE000EDA0 ///< MPU Region Attribute & Size Reg
+#define NVIC_DBG_CTRL 0xE000EDF0 ///< Debug Control and Status Reg
+#define NVIC_DBG_XFER 0xE000EDF4 ///< Debug Core Reg. Transfer Select
+#define NVIC_DBG_DATA 0xE000EDF8 ///< Debug Core Register Data
+#define NVIC_DBG_INT 0xE000EDFC ///< Debug Reset Interrupt Control
+#define NVIC_SW_TRIG 0xE000EF00 ///< Software Trigger Interrupt Reg
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_INT_TYPE register.
+ */
+/*\{*/
+#define NVIC_INT_TYPE_LINES_M 0x0000001F ///< Number of interrupt lines (x32)
+#define NVIC_INT_TYPE_LINES_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_ST_CTRL register.
+ */
+/*\{*/
+#define NVIC_ST_CTRL_COUNT 0x00010000 ///< Count flag
+#define NVIC_ST_CTRL_CLK_SRC 0x00000004 ///< Clock Source
+#define NVIC_ST_CTRL_INTEN 0x00000002 ///< Interrupt enable
+#define NVIC_ST_CTRL_ENABLE 0x00000001 ///< Counter mode
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_ST_RELOAD register.
+ */
+/*\{*/
+#define NVIC_ST_RELOAD_M 0x00FFFFFF ///< Counter load value
+#define NVIC_ST_RELOAD_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_ST_CURRENT
+ * register.
+ */
+/*\{*/
+#define NVIC_ST_CURRENT_M 0x00FFFFFF ///< Counter current value
+#define NVIC_ST_CURRENT_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_ST_CAL register.
+ */
+/*\{*/
+#define NVIC_ST_CAL_NOREF 0x80000000 ///< No reference clock
+#define NVIC_ST_CAL_SKEW 0x40000000 ///< Clock skew
+#define NVIC_ST_CAL_ONEMS_M 0x00FFFFFF ///< 1ms reference value
+#define NVIC_ST_CAL_ONEMS_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_EN0 register.
+ */
+/*\{*/
+#define NVIC_EN0_INT31 0x80000000 ///< Interrupt 31 enable
+#define NVIC_EN0_INT30 0x40000000 ///< Interrupt 30 enable
+#define NVIC_EN0_INT29 0x20000000 ///< Interrupt 29 enable
+#define NVIC_EN0_INT28 0x10000000 ///< Interrupt 28 enable
+#define NVIC_EN0_INT27 0x08000000 ///< Interrupt 27 enable
+#define NVIC_EN0_INT26 0x04000000 ///< Interrupt 26 enable
+#define NVIC_EN0_INT25 0x02000000 ///< Interrupt 25 enable
+#define NVIC_EN0_INT24 0x01000000 ///< Interrupt 24 enable
+#define NVIC_EN0_INT23 0x00800000 ///< Interrupt 23 enable
+#define NVIC_EN0_INT22 0x00400000 ///< Interrupt 22 enable
+#define NVIC_EN0_INT21 0x00200000 ///< Interrupt 21 enable
+#define NVIC_EN0_INT20 0x00100000 ///< Interrupt 20 enable
+#define NVIC_EN0_INT19 0x00080000 ///< Interrupt 19 enable
+#define NVIC_EN0_INT18 0x00040000 ///< Interrupt 18 enable
+#define NVIC_EN0_INT17 0x00020000 ///< Interrupt 17 enable
+#define NVIC_EN0_INT16 0x00010000 ///< Interrupt 16 enable
+#define NVIC_EN0_INT15 0x00008000 ///< Interrupt 15 enable
+#define NVIC_EN0_INT14 0x00004000 ///< Interrupt 14 enable
+#define NVIC_EN0_INT13 0x00002000 ///< Interrupt 13 enable
+#define NVIC_EN0_INT12 0x00001000 ///< Interrupt 12 enable
+#define NVIC_EN0_INT11 0x00000800 ///< Interrupt 11 enable
+#define NVIC_EN0_INT10 0x00000400 ///< Interrupt 10 enable
+#define NVIC_EN0_INT9 0x00000200 ///< Interrupt 9 enable
+#define NVIC_EN0_INT8 0x00000100 ///< Interrupt 8 enable
+#define NVIC_EN0_INT7 0x00000080 ///< Interrupt 7 enable
+#define NVIC_EN0_INT6 0x00000040 ///< Interrupt 6 enable
+#define NVIC_EN0_INT5 0x00000020 ///< Interrupt 5 enable
+#define NVIC_EN0_INT4 0x00000010 ///< Interrupt 4 enable
+#define NVIC_EN0_INT3 0x00000008 ///< Interrupt 3 enable
+#define NVIC_EN0_INT2 0x00000004 ///< Interrupt 2 enable
+#define NVIC_EN0_INT1 0x00000002 ///< Interrupt 1 enable
+#define NVIC_EN0_INT0 0x00000001 ///< Interrupt 0 enable
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_EN1 register.
+ */
+/*\{*/
+#define NVIC_EN1_INT59 0x08000000 ///< Interrupt 59 enable
+#define NVIC_EN1_INT58 0x04000000 ///< Interrupt 58 enable
+#define NVIC_EN1_INT57 0x02000000 ///< Interrupt 57 enable
+#define NVIC_EN1_INT56 0x01000000 ///< Interrupt 56 enable
+#define NVIC_EN1_INT55 0x00800000 ///< Interrupt 55 enable
+#define NVIC_EN1_INT54 0x00400000 ///< Interrupt 54 enable
+#define NVIC_EN1_INT53 0x00200000 ///< Interrupt 53 enable
+#define NVIC_EN1_INT52 0x00100000 ///< Interrupt 52 enable
+#define NVIC_EN1_INT51 0x00080000 ///< Interrupt 51 enable
+#define NVIC_EN1_INT50 0x00040000 ///< Interrupt 50 enable
+#define NVIC_EN1_INT49 0x00020000 ///< Interrupt 49 enable
+#define NVIC_EN1_INT48 0x00010000 ///< Interrupt 48 enable
+#define NVIC_EN1_INT47 0x00008000 ///< Interrupt 47 enable
+#define NVIC_EN1_INT46 0x00004000 ///< Interrupt 46 enable
+#define NVIC_EN1_INT45 0x00002000 ///< Interrupt 45 enable
+#define NVIC_EN1_INT44 0x00001000 ///< Interrupt 44 enable
+#define NVIC_EN1_INT43 0x00000800 ///< Interrupt 43 enable
+#define NVIC_EN1_INT42 0x00000400 ///< Interrupt 42 enable
+#define NVIC_EN1_INT41 0x00000200 ///< Interrupt 41 enable
+#define NVIC_EN1_INT40 0x00000100 ///< Interrupt 40 enable
+#define NVIC_EN1_INT39 0x00000080 ///< Interrupt 39 enable
+#define NVIC_EN1_INT38 0x00000040 ///< Interrupt 38 enable
+#define NVIC_EN1_INT37 0x00000020 ///< Interrupt 37 enable
+#define NVIC_EN1_INT36 0x00000010 ///< Interrupt 36 enable
+#define NVIC_EN1_INT35 0x00000008 ///< Interrupt 35 enable
+#define NVIC_EN1_INT34 0x00000004 ///< Interrupt 34 enable
+#define NVIC_EN1_INT33 0x00000002 ///< Interrupt 33 enable
+#define NVIC_EN1_INT32 0x00000001 ///< Interrupt 32 enable
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_DIS0 register.
+ */
+/*\{*/
+#define NVIC_DIS0_INT31 0x80000000 ///< Interrupt 31 disable
+#define NVIC_DIS0_INT30 0x40000000 ///< Interrupt 30 disable
+#define NVIC_DIS0_INT29 0x20000000 ///< Interrupt 29 disable
+#define NVIC_DIS0_INT28 0x10000000 ///< Interrupt 28 disable
+#define NVIC_DIS0_INT27 0x08000000 ///< Interrupt 27 disable
+#define NVIC_DIS0_INT26 0x04000000 ///< Interrupt 26 disable
+#define NVIC_DIS0_INT25 0x02000000 ///< Interrupt 25 disable
+#define NVIC_DIS0_INT24 0x01000000 ///< Interrupt 24 disable
+#define NVIC_DIS0_INT23 0x00800000 ///< Interrupt 23 disable
+#define NVIC_DIS0_INT22 0x00400000 ///< Interrupt 22 disable
+#define NVIC_DIS0_INT21 0x00200000 ///< Interrupt 21 disable
+#define NVIC_DIS0_INT20 0x00100000 ///< Interrupt 20 disable
+#define NVIC_DIS0_INT19 0x00080000 ///< Interrupt 19 disable
+#define NVIC_DIS0_INT18 0x00040000 ///< Interrupt 18 disable
+#define NVIC_DIS0_INT17 0x00020000 ///< Interrupt 17 disable
+#define NVIC_DIS0_INT16 0x00010000 ///< Interrupt 16 disable
+#define NVIC_DIS0_INT15 0x00008000 ///< Interrupt 15 disable
+#define NVIC_DIS0_INT14 0x00004000 ///< Interrupt 14 disable
+#define NVIC_DIS0_INT13 0x00002000 ///< Interrupt 13 disable
+#define NVIC_DIS0_INT12 0x00001000 ///< Interrupt 12 disable
+#define NVIC_DIS0_INT11 0x00000800 ///< Interrupt 11 disable
+#define NVIC_DIS0_INT10 0x00000400 ///< Interrupt 10 disable
+#define NVIC_DIS0_INT9 0x00000200 ///< Interrupt 9 disable
+#define NVIC_DIS0_INT8 0x00000100 ///< Interrupt 8 disable
+#define NVIC_DIS0_INT7 0x00000080 ///< Interrupt 7 disable
+#define NVIC_DIS0_INT6 0x00000040 ///< Interrupt 6 disable
+#define NVIC_DIS0_INT5 0x00000020 ///< Interrupt 5 disable
+#define NVIC_DIS0_INT4 0x00000010 ///< Interrupt 4 disable
+#define NVIC_DIS0_INT3 0x00000008 ///< Interrupt 3 disable
+#define NVIC_DIS0_INT2 0x00000004 ///< Interrupt 2 disable
+#define NVIC_DIS0_INT1 0x00000002 ///< Interrupt 1 disable
+#define NVIC_DIS0_INT0 0x00000001 ///< Interrupt 0 disable
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_DIS1 register.
+ */
+/*\{*/
+#define NVIC_DIS1_INT59 0x08000000 ///< Interrupt 59 disable
+#define NVIC_DIS1_INT58 0x04000000 ///< Interrupt 58 disable
+#define NVIC_DIS1_INT57 0x02000000 ///< Interrupt 57 disable
+#define NVIC_DIS1_INT56 0x01000000 ///< Interrupt 56 disable
+#define NVIC_DIS1_INT55 0x00800000 ///< Interrupt 55 disable
+#define NVIC_DIS1_INT54 0x00400000 ///< Interrupt 54 disable
+#define NVIC_DIS1_INT53 0x00200000 ///< Interrupt 53 disable
+#define NVIC_DIS1_INT52 0x00100000 ///< Interrupt 52 disable
+#define NVIC_DIS1_INT51 0x00080000 ///< Interrupt 51 disable
+#define NVIC_DIS1_INT50 0x00040000 ///< Interrupt 50 disable
+#define NVIC_DIS1_INT49 0x00020000 ///< Interrupt 49 disable
+#define NVIC_DIS1_INT48 0x00010000 ///< Interrupt 48 disable
+#define NVIC_DIS1_INT47 0x00008000 ///< Interrupt 47 disable
+#define NVIC_DIS1_INT46 0x00004000 ///< Interrupt 46 disable
+#define NVIC_DIS1_INT45 0x00002000 ///< Interrupt 45 disable
+#define NVIC_DIS1_INT44 0x00001000 ///< Interrupt 44 disable
+#define NVIC_DIS1_INT43 0x00000800 ///< Interrupt 43 disable
+#define NVIC_DIS1_INT42 0x00000400 ///< Interrupt 42 disable
+#define NVIC_DIS1_INT41 0x00000200 ///< Interrupt 41 disable
+#define NVIC_DIS1_INT40 0x00000100 ///< Interrupt 40 disable
+#define NVIC_DIS1_INT39 0x00000080 ///< Interrupt 39 disable
+#define NVIC_DIS1_INT38 0x00000040 ///< Interrupt 38 disable
+#define NVIC_DIS1_INT37 0x00000020 ///< Interrupt 37 disable
+#define NVIC_DIS1_INT36 0x00000010 ///< Interrupt 36 disable
+#define NVIC_DIS1_INT35 0x00000008 ///< Interrupt 35 disable
+#define NVIC_DIS1_INT34 0x00000004 ///< Interrupt 34 disable
+#define NVIC_DIS1_INT33 0x00000002 ///< Interrupt 33 disable
+#define NVIC_DIS1_INT32 0x00000001 ///< Interrupt 32 disable
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PEND0 register.
+ */
+/*\{*/
+#define NVIC_PEND0_INT31 0x80000000 ///< Interrupt 31 pend
+#define NVIC_PEND0_INT30 0x40000000 ///< Interrupt 30 pend
+#define NVIC_PEND0_INT29 0x20000000 ///< Interrupt 29 pend
+#define NVIC_PEND0_INT28 0x10000000 ///< Interrupt 28 pend
+#define NVIC_PEND0_INT27 0x08000000 ///< Interrupt 27 pend
+#define NVIC_PEND0_INT26 0x04000000 ///< Interrupt 26 pend
+#define NVIC_PEND0_INT25 0x02000000 ///< Interrupt 25 pend
+#define NVIC_PEND0_INT24 0x01000000 ///< Interrupt 24 pend
+#define NVIC_PEND0_INT23 0x00800000 ///< Interrupt 23 pend
+#define NVIC_PEND0_INT22 0x00400000 ///< Interrupt 22 pend
+#define NVIC_PEND0_INT21 0x00200000 ///< Interrupt 21 pend
+#define NVIC_PEND0_INT20 0x00100000 ///< Interrupt 20 pend
+#define NVIC_PEND0_INT19 0x00080000 ///< Interrupt 19 pend
+#define NVIC_PEND0_INT18 0x00040000 ///< Interrupt 18 pend
+#define NVIC_PEND0_INT17 0x00020000 ///< Interrupt 17 pend
+#define NVIC_PEND0_INT16 0x00010000 ///< Interrupt 16 pend
+#define NVIC_PEND0_INT15 0x00008000 ///< Interrupt 15 pend
+#define NVIC_PEND0_INT14 0x00004000 ///< Interrupt 14 pend
+#define NVIC_PEND0_INT13 0x00002000 ///< Interrupt 13 pend
+#define NVIC_PEND0_INT12 0x00001000 ///< Interrupt 12 pend
+#define NVIC_PEND0_INT11 0x00000800 ///< Interrupt 11 pend
+#define NVIC_PEND0_INT10 0x00000400 ///< Interrupt 10 pend
+#define NVIC_PEND0_INT9 0x00000200 ///< Interrupt 9 pend
+#define NVIC_PEND0_INT8 0x00000100 ///< Interrupt 8 pend
+#define NVIC_PEND0_INT7 0x00000080 ///< Interrupt 7 pend
+#define NVIC_PEND0_INT6 0x00000040 ///< Interrupt 6 pend
+#define NVIC_PEND0_INT5 0x00000020 ///< Interrupt 5 pend
+#define NVIC_PEND0_INT4 0x00000010 ///< Interrupt 4 pend
+#define NVIC_PEND0_INT3 0x00000008 ///< Interrupt 3 pend
+#define NVIC_PEND0_INT2 0x00000004 ///< Interrupt 2 pend
+#define NVIC_PEND0_INT1 0x00000002 ///< Interrupt 1 pend
+#define NVIC_PEND0_INT0 0x00000001 ///< Interrupt 0 pend
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PEND1 register.
+ */
+/*\{*/
+#define NVIC_PEND1_INT59 0x08000000 ///< Interrupt 59 pend
+#define NVIC_PEND1_INT58 0x04000000 ///< Interrupt 58 pend
+#define NVIC_PEND1_INT57 0x02000000 ///< Interrupt 57 pend
+#define NVIC_PEND1_INT56 0x01000000 ///< Interrupt 56 pend
+#define NVIC_PEND1_INT55 0x00800000 ///< Interrupt 55 pend
+#define NVIC_PEND1_INT54 0x00400000 ///< Interrupt 54 pend
+#define NVIC_PEND1_INT53 0x00200000 ///< Interrupt 53 pend
+#define NVIC_PEND1_INT52 0x00100000 ///< Interrupt 52 pend
+#define NVIC_PEND1_INT51 0x00080000 ///< Interrupt 51 pend
+#define NVIC_PEND1_INT50 0x00040000 ///< Interrupt 50 pend
+#define NVIC_PEND1_INT49 0x00020000 ///< Interrupt 49 pend
+#define NVIC_PEND1_INT48 0x00010000 ///< Interrupt 48 pend
+#define NVIC_PEND1_INT47 0x00008000 ///< Interrupt 47 pend
+#define NVIC_PEND1_INT46 0x00004000 ///< Interrupt 46 pend
+#define NVIC_PEND1_INT45 0x00002000 ///< Interrupt 45 pend
+#define NVIC_PEND1_INT44 0x00001000 ///< Interrupt 44 pend
+#define NVIC_PEND1_INT43 0x00000800 ///< Interrupt 43 pend
+#define NVIC_PEND1_INT42 0x00000400 ///< Interrupt 42 pend
+#define NVIC_PEND1_INT41 0x00000200 ///< Interrupt 41 pend
+#define NVIC_PEND1_INT40 0x00000100 ///< Interrupt 40 pend
+#define NVIC_PEND1_INT39 0x00000080 ///< Interrupt 39 pend
+#define NVIC_PEND1_INT38 0x00000040 ///< Interrupt 38 pend
+#define NVIC_PEND1_INT37 0x00000020 ///< Interrupt 37 pend
+#define NVIC_PEND1_INT36 0x00000010 ///< Interrupt 36 pend
+#define NVIC_PEND1_INT35 0x00000008 ///< Interrupt 35 pend
+#define NVIC_PEND1_INT34 0x00000004 ///< Interrupt 34 pend
+#define NVIC_PEND1_INT33 0x00000002 ///< Interrupt 33 pend
+#define NVIC_PEND1_INT32 0x00000001 ///< Interrupt 32 pend
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_UNPEND0 register.
+ */
+/*\{*/
+#define NVIC_UNPEND0_INT31 0x80000000 ///< Interrupt 31 unpend
+#define NVIC_UNPEND0_INT30 0x40000000 ///< Interrupt 30 unpend
+#define NVIC_UNPEND0_INT29 0x20000000 ///< Interrupt 29 unpend
+#define NVIC_UNPEND0_INT28 0x10000000 ///< Interrupt 28 unpend
+#define NVIC_UNPEND0_INT27 0x08000000 ///< Interrupt 27 unpend
+#define NVIC_UNPEND0_INT26 0x04000000 ///< Interrupt 26 unpend
+#define NVIC_UNPEND0_INT25 0x02000000 ///< Interrupt 25 unpend
+#define NVIC_UNPEND0_INT24 0x01000000 ///< Interrupt 24 unpend
+#define NVIC_UNPEND0_INT23 0x00800000 ///< Interrupt 23 unpend
+#define NVIC_UNPEND0_INT22 0x00400000 ///< Interrupt 22 unpend
+#define NVIC_UNPEND0_INT21 0x00200000 ///< Interrupt 21 unpend
+#define NVIC_UNPEND0_INT20 0x00100000 ///< Interrupt 20 unpend
+#define NVIC_UNPEND0_INT19 0x00080000 ///< Interrupt 19 unpend
+#define NVIC_UNPEND0_INT18 0x00040000 ///< Interrupt 18 unpend
+#define NVIC_UNPEND0_INT17 0x00020000 ///< Interrupt 17 unpend
+#define NVIC_UNPEND0_INT16 0x00010000 ///< Interrupt 16 unpend
+#define NVIC_UNPEND0_INT15 0x00008000 ///< Interrupt 15 unpend
+#define NVIC_UNPEND0_INT14 0x00004000 ///< Interrupt 14 unpend
+#define NVIC_UNPEND0_INT13 0x00002000 ///< Interrupt 13 unpend
+#define NVIC_UNPEND0_INT12 0x00001000 ///< Interrupt 12 unpend
+#define NVIC_UNPEND0_INT11 0x00000800 ///< Interrupt 11 unpend
+#define NVIC_UNPEND0_INT10 0x00000400 ///< Interrupt 10 unpend
+#define NVIC_UNPEND0_INT9 0x00000200 ///< Interrupt 9 unpend
+#define NVIC_UNPEND0_INT8 0x00000100 ///< Interrupt 8 unpend
+#define NVIC_UNPEND0_INT7 0x00000080 ///< Interrupt 7 unpend
+#define NVIC_UNPEND0_INT6 0x00000040 ///< Interrupt 6 unpend
+#define NVIC_UNPEND0_INT5 0x00000020 ///< Interrupt 5 unpend
+#define NVIC_UNPEND0_INT4 0x00000010 ///< Interrupt 4 unpend
+#define NVIC_UNPEND0_INT3 0x00000008 ///< Interrupt 3 unpend
+#define NVIC_UNPEND0_INT2 0x00000004 ///< Interrupt 2 unpend
+#define NVIC_UNPEND0_INT1 0x00000002 ///< Interrupt 1 unpend
+#define NVIC_UNPEND0_INT0 0x00000001 ///< Interrupt 0 unpend
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_UNPEND1 register.
+ */
+/*\{*/
+#define NVIC_UNPEND1_INT59 0x08000000 ///< Interrupt 59 unpend
+#define NVIC_UNPEND1_INT58 0x04000000 ///< Interrupt 58 unpend
+#define NVIC_UNPEND1_INT57 0x02000000 ///< Interrupt 57 unpend
+#define NVIC_UNPEND1_INT56 0x01000000 ///< Interrupt 56 unpend
+#define NVIC_UNPEND1_INT55 0x00800000 ///< Interrupt 55 unpend
+#define NVIC_UNPEND1_INT54 0x00400000 ///< Interrupt 54 unpend
+#define NVIC_UNPEND1_INT53 0x00200000 ///< Interrupt 53 unpend
+#define NVIC_UNPEND1_INT52 0x00100000 ///< Interrupt 52 unpend
+#define NVIC_UNPEND1_INT51 0x00080000 ///< Interrupt 51 unpend
+#define NVIC_UNPEND1_INT50 0x00040000 ///< Interrupt 50 unpend
+#define NVIC_UNPEND1_INT49 0x00020000 ///< Interrupt 49 unpend
+#define NVIC_UNPEND1_INT48 0x00010000 ///< Interrupt 48 unpend
+#define NVIC_UNPEND1_INT47 0x00008000 ///< Interrupt 47 unpend
+#define NVIC_UNPEND1_INT46 0x00004000 ///< Interrupt 46 unpend
+#define NVIC_UNPEND1_INT45 0x00002000 ///< Interrupt 45 unpend
+#define NVIC_UNPEND1_INT44 0x00001000 ///< Interrupt 44 unpend
+#define NVIC_UNPEND1_INT43 0x00000800 ///< Interrupt 43 unpend
+#define NVIC_UNPEND1_INT42 0x00000400 ///< Interrupt 42 unpend
+#define NVIC_UNPEND1_INT41 0x00000200 ///< Interrupt 41 unpend
+#define NVIC_UNPEND1_INT40 0x00000100 ///< Interrupt 40 unpend
+#define NVIC_UNPEND1_INT39 0x00000080 ///< Interrupt 39 unpend
+#define NVIC_UNPEND1_INT38 0x00000040 ///< Interrupt 38 unpend
+#define NVIC_UNPEND1_INT37 0x00000020 ///< Interrupt 37 unpend
+#define NVIC_UNPEND1_INT36 0x00000010 ///< Interrupt 36 unpend
+#define NVIC_UNPEND1_INT35 0x00000008 ///< Interrupt 35 unpend
+#define NVIC_UNPEND1_INT34 0x00000004 ///< Interrupt 34 unpend
+#define NVIC_UNPEND1_INT33 0x00000002 ///< Interrupt 33 unpend
+#define NVIC_UNPEND1_INT32 0x00000001 ///< Interrupt 32 unpend
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_ACTIVE0 register.
+ */
+/*\{*/
+#define NVIC_ACTIVE0_INT31 0x80000000 ///< Interrupt 31 active
+#define NVIC_ACTIVE0_INT30 0x40000000 ///< Interrupt 30 active
+#define NVIC_ACTIVE0_INT29 0x20000000 ///< Interrupt 29 active
+#define NVIC_ACTIVE0_INT28 0x10000000 ///< Interrupt 28 active
+#define NVIC_ACTIVE0_INT27 0x08000000 ///< Interrupt 27 active
+#define NVIC_ACTIVE0_INT26 0x04000000 ///< Interrupt 26 active
+#define NVIC_ACTIVE0_INT25 0x02000000 ///< Interrupt 25 active
+#define NVIC_ACTIVE0_INT24 0x01000000 ///< Interrupt 24 active
+#define NVIC_ACTIVE0_INT23 0x00800000 ///< Interrupt 23 active
+#define NVIC_ACTIVE0_INT22 0x00400000 ///< Interrupt 22 active
+#define NVIC_ACTIVE0_INT21 0x00200000 ///< Interrupt 21 active
+#define NVIC_ACTIVE0_INT20 0x00100000 ///< Interrupt 20 active
+#define NVIC_ACTIVE0_INT19 0x00080000 ///< Interrupt 19 active
+#define NVIC_ACTIVE0_INT18 0x00040000 ///< Interrupt 18 active
+#define NVIC_ACTIVE0_INT17 0x00020000 ///< Interrupt 17 active
+#define NVIC_ACTIVE0_INT16 0x00010000 ///< Interrupt 16 active
+#define NVIC_ACTIVE0_INT15 0x00008000 ///< Interrupt 15 active
+#define NVIC_ACTIVE0_INT14 0x00004000 ///< Interrupt 14 active
+#define NVIC_ACTIVE0_INT13 0x00002000 ///< Interrupt 13 active
+#define NVIC_ACTIVE0_INT12 0x00001000 ///< Interrupt 12 active
+#define NVIC_ACTIVE0_INT11 0x00000800 ///< Interrupt 11 active
+#define NVIC_ACTIVE0_INT10 0x00000400 ///< Interrupt 10 active
+#define NVIC_ACTIVE0_INT9 0x00000200 ///< Interrupt 9 active
+#define NVIC_ACTIVE0_INT8 0x00000100 ///< Interrupt 8 active
+#define NVIC_ACTIVE0_INT7 0x00000080 ///< Interrupt 7 active
+#define NVIC_ACTIVE0_INT6 0x00000040 ///< Interrupt 6 active
+#define NVIC_ACTIVE0_INT5 0x00000020 ///< Interrupt 5 active
+#define NVIC_ACTIVE0_INT4 0x00000010 ///< Interrupt 4 active
+#define NVIC_ACTIVE0_INT3 0x00000008 ///< Interrupt 3 active
+#define NVIC_ACTIVE0_INT2 0x00000004 ///< Interrupt 2 active
+#define NVIC_ACTIVE0_INT1 0x00000002 ///< Interrupt 1 active
+#define NVIC_ACTIVE0_INT0 0x00000001 ///< Interrupt 0 active
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_ACTIVE1 register.
+ */
+/*\{*/
+#define NVIC_ACTIVE1_INT59 0x08000000 ///< Interrupt 59 active
+#define NVIC_ACTIVE1_INT58 0x04000000 ///< Interrupt 58 active
+#define NVIC_ACTIVE1_INT57 0x02000000 ///< Interrupt 57 active
+#define NVIC_ACTIVE1_INT56 0x01000000 ///< Interrupt 56 active
+#define NVIC_ACTIVE1_INT55 0x00800000 ///< Interrupt 55 active
+#define NVIC_ACTIVE1_INT54 0x00400000 ///< Interrupt 54 active
+#define NVIC_ACTIVE1_INT53 0x00200000 ///< Interrupt 53 active
+#define NVIC_ACTIVE1_INT52 0x00100000 ///< Interrupt 52 active
+#define NVIC_ACTIVE1_INT51 0x00080000 ///< Interrupt 51 active
+#define NVIC_ACTIVE1_INT50 0x00040000 ///< Interrupt 50 active
+#define NVIC_ACTIVE1_INT49 0x00020000 ///< Interrupt 49 active
+#define NVIC_ACTIVE1_INT48 0x00010000 ///< Interrupt 48 active
+#define NVIC_ACTIVE1_INT47 0x00008000 ///< Interrupt 47 active
+#define NVIC_ACTIVE1_INT46 0x00004000 ///< Interrupt 46 active
+#define NVIC_ACTIVE1_INT45 0x00002000 ///< Interrupt 45 active
+#define NVIC_ACTIVE1_INT44 0x00001000 ///< Interrupt 44 active
+#define NVIC_ACTIVE1_INT43 0x00000800 ///< Interrupt 43 active
+#define NVIC_ACTIVE1_INT42 0x00000400 ///< Interrupt 42 active
+#define NVIC_ACTIVE1_INT41 0x00000200 ///< Interrupt 41 active
+#define NVIC_ACTIVE1_INT40 0x00000100 ///< Interrupt 40 active
+#define NVIC_ACTIVE1_INT39 0x00000080 ///< Interrupt 39 active
+#define NVIC_ACTIVE1_INT38 0x00000040 ///< Interrupt 38 active
+#define NVIC_ACTIVE1_INT37 0x00000020 ///< Interrupt 37 active
+#define NVIC_ACTIVE1_INT36 0x00000010 ///< Interrupt 36 active
+#define NVIC_ACTIVE1_INT35 0x00000008 ///< Interrupt 35 active
+#define NVIC_ACTIVE1_INT34 0x00000004 ///< Interrupt 34 active
+#define NVIC_ACTIVE1_INT33 0x00000002 ///< Interrupt 33 active
+#define NVIC_ACTIVE1_INT32 0x00000001 ///< Interrupt 32 active
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PRI0 register.
+ */
+/*\{*/
+#define NVIC_PRI0_INT3_M 0xFF000000 ///< Interrupt 3 priority mask
+#define NVIC_PRI0_INT2_M 0x00FF0000 ///< Interrupt 2 priority mask
+#define NVIC_PRI0_INT1_M 0x0000FF00 ///< Interrupt 1 priority mask
+#define NVIC_PRI0_INT0_M 0x000000FF ///< Interrupt 0 priority mask
+#define NVIC_PRI0_INT3_S 24
+#define NVIC_PRI0_INT2_S 16
+#define NVIC_PRI0_INT1_S 8
+#define NVIC_PRI0_INT0_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PRI1 register.
+ */
+/*\{*/
+#define NVIC_PRI1_INT7_M 0xFF000000 ///< Interrupt 7 priority mask
+#define NVIC_PRI1_INT6_M 0x00FF0000 ///< Interrupt 6 priority mask
+#define NVIC_PRI1_INT5_M 0x0000FF00 ///< Interrupt 5 priority mask
+#define NVIC_PRI1_INT4_M 0x000000FF ///< Interrupt 4 priority mask
+#define NVIC_PRI1_INT7_S 24
+#define NVIC_PRI1_INT6_S 16
+#define NVIC_PRI1_INT5_S 8
+#define NVIC_PRI1_INT4_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PRI2 register.
+ */
+/*\{*/
+#define NVIC_PRI2_INT11_M 0xFF000000 ///< Interrupt 11 priority mask
+#define NVIC_PRI2_INT10_M 0x00FF0000 ///< Interrupt 10 priority mask
+#define NVIC_PRI2_INT9_M 0x0000FF00 ///< Interrupt 9 priority mask
+#define NVIC_PRI2_INT8_M 0x000000FF ///< Interrupt 8 priority mask
+#define NVIC_PRI2_INT11_S 24
+#define NVIC_PRI2_INT10_S 16
+#define NVIC_PRI2_INT9_S 8
+#define NVIC_PRI2_INT8_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PRI3 register.
+ */
+/*\{*/
+#define NVIC_PRI3_INT15_M 0xFF000000 ///< Interrupt 15 priority mask
+#define NVIC_PRI3_INT14_M 0x00FF0000 ///< Interrupt 14 priority mask
+#define NVIC_PRI3_INT13_M 0x0000FF00 ///< Interrupt 13 priority mask
+#define NVIC_PRI3_INT12_M 0x000000FF ///< Interrupt 12 priority mask
+#define NVIC_PRI3_INT15_S 24
+#define NVIC_PRI3_INT14_S 16
+#define NVIC_PRI3_INT13_S 8
+#define NVIC_PRI3_INT12_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PRI4 register.
+ */
+/*\{*/
+#define NVIC_PRI4_INT19_M 0xFF000000 ///< Interrupt 19 priority mask
+#define NVIC_PRI4_INT18_M 0x00FF0000 ///< Interrupt 18 priority mask
+#define NVIC_PRI4_INT17_M 0x0000FF00 ///< Interrupt 17 priority mask
+#define NVIC_PRI4_INT16_M 0x000000FF ///< Interrupt 16 priority mask
+#define NVIC_PRI4_INT19_S 24
+#define NVIC_PRI4_INT18_S 16
+#define NVIC_PRI4_INT17_S 8
+#define NVIC_PRI4_INT16_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PRI5 register.
+ */
+/*\{*/
+#define NVIC_PRI5_INT23_M 0xFF000000 ///< Interrupt 23 priority mask
+#define NVIC_PRI5_INT22_M 0x00FF0000 ///< Interrupt 22 priority mask
+#define NVIC_PRI5_INT21_M 0x0000FF00 ///< Interrupt 21 priority mask
+#define NVIC_PRI5_INT20_M 0x000000FF ///< Interrupt 20 priority mask
+#define NVIC_PRI5_INT23_S 24
+#define NVIC_PRI5_INT22_S 16
+#define NVIC_PRI5_INT21_S 8
+#define NVIC_PRI5_INT20_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PRI6 register.
+ */
+/*\{*/
+#define NVIC_PRI6_INT27_M 0xFF000000 ///< Interrupt 27 priority mask
+#define NVIC_PRI6_INT26_M 0x00FF0000 ///< Interrupt 26 priority mask
+#define NVIC_PRI6_INT25_M 0x0000FF00 ///< Interrupt 25 priority mask
+#define NVIC_PRI6_INT24_M 0x000000FF ///< Interrupt 24 priority mask
+#define NVIC_PRI6_INT27_S 24
+#define NVIC_PRI6_INT26_S 16
+#define NVIC_PRI6_INT25_S 8
+#define NVIC_PRI6_INT24_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PRI7 register.
+ */
+/*\{*/
+#define NVIC_PRI7_INT31_M 0xFF000000 ///< Interrupt 31 priority mask
+#define NVIC_PRI7_INT30_M 0x00FF0000 ///< Interrupt 30 priority mask
+#define NVIC_PRI7_INT29_M 0x0000FF00 ///< Interrupt 29 priority mask
+#define NVIC_PRI7_INT28_M 0x000000FF ///< Interrupt 28 priority mask
+#define NVIC_PRI7_INT31_S 24
+#define NVIC_PRI7_INT30_S 16
+#define NVIC_PRI7_INT29_S 8
+#define NVIC_PRI7_INT28_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PRI8 register.
+ */
+/*\{*/
+#define NVIC_PRI8_INT35_M 0xFF000000 ///< Interrupt 35 priority mask
+#define NVIC_PRI8_INT34_M 0x00FF0000 ///< Interrupt 34 priority mask
+#define NVIC_PRI8_INT33_M 0x0000FF00 ///< Interrupt 33 priority mask
+#define NVIC_PRI8_INT32_M 0x000000FF ///< Interrupt 32 priority mask
+#define NVIC_PRI8_INT35_S 24
+#define NVIC_PRI8_INT34_S 16
+#define NVIC_PRI8_INT33_S 8
+#define NVIC_PRI8_INT32_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PRI9 register.
+ */
+/*\{*/
+#define NVIC_PRI9_INT39_M 0xFF000000 ///< Interrupt 39 priority mask
+#define NVIC_PRI9_INT38_M 0x00FF0000 ///< Interrupt 38 priority mask
+#define NVIC_PRI9_INT37_M 0x0000FF00 ///< Interrupt 37 priority mask
+#define NVIC_PRI9_INT36_M 0x000000FF ///< Interrupt 36 priority mask
+#define NVIC_PRI9_INT39_S 24
+#define NVIC_PRI9_INT38_S 16
+#define NVIC_PRI9_INT37_S 8
+#define NVIC_PRI9_INT36_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_PRI10 register.
+ */
+/*\{*/
+#define NVIC_PRI10_INT43_M 0xFF000000 ///< Interrupt 43 priority mask
+#define NVIC_PRI10_INT42_M 0x00FF0000 ///< Interrupt 42 priority mask
+#define NVIC_PRI10_INT41_M 0x0000FF00 ///< Interrupt 41 priority mask
+#define NVIC_PRI10_INT40_M 0x000000FF ///< Interrupt 40 priority mask
+#define NVIC_PRI10_INT43_S 24
+#define NVIC_PRI10_INT42_S 16
+#define NVIC_PRI10_INT41_S 8
+#define NVIC_PRI10_INT40_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_CPUID register.
+ */
+/*\{*/
+#define NVIC_CPUID_IMP_M 0xFF000000 ///< Implementer
+#define NVIC_CPUID_VAR_M 0x00F00000 ///< Variant
+#define NVIC_CPUID_PARTNO_M 0x0000FFF0 ///< Processor part number
+#define NVIC_CPUID_REV_M 0x0000000F ///< Revision
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_INT_CTRL register.
+ */
+/*\{*/
+#define NVIC_INT_CTRL_NMI_SET 0x80000000 ///< Pend a NMI
+#define NVIC_INT_CTRL_PEND_SV 0x10000000 ///< Pend a PendSV
+#define NVIC_INT_CTRL_UNPEND_SV 0x08000000 ///< Unpend a PendSV
+#define NVIC_INT_CTRL_PENDSTSET 0x04000000 ///< Set pending SysTick interrupt
+#define NVIC_INT_CTRL_PENDSTCLR 0x02000000 ///< Clear pending SysTick interrupt
+#define NVIC_INT_CTRL_ISR_PRE 0x00800000 ///< Debug interrupt handling
+#define NVIC_INT_CTRL_ISR_PEND 0x00400000 ///< Debug interrupt pending
+#define NVIC_INT_CTRL_VEC_PEN_M 0x003FF000 ///< Highest pending exception
+#define NVIC_INT_CTRL_RET_BASE 0x00000800 ///< Return to base
+#define NVIC_INT_CTRL_VEC_ACT_M 0x000003FF ///< Current active exception
+#define NVIC_INT_CTRL_VEC_PEN_S 12
+#define NVIC_INT_CTRL_VEC_ACT_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_VTABLE register.
+ */
+/*\{*/
+#define NVIC_VTABLE_BASE 0x20000000 ///< Vector table base
+#define NVIC_VTABLE_OFFSET_M 0x1FFFFF00 ///< Vector table offset
+#define NVIC_VTABLE_OFFSET_S 8
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_APINT register.
+ */
+/*\{*/
+#define NVIC_APINT_VECTKEY_M 0xFFFF0000 ///< Vector key mask
+#define NVIC_APINT_VECTKEY 0x05FA0000 ///< Vector key
+#define NVIC_APINT_ENDIANESS 0x00008000 ///< Data endianess
+#define NVIC_APINT_PRIGROUP_M 0x00000700 ///< Priority group
+#define NVIC_APINT_PRIGROUP_0_8 0x00000700 ///< Priority group 0.8 split
+#define NVIC_APINT_PRIGROUP_1_7 0x00000600 ///< Priority group 1.7 split
+#define NVIC_APINT_PRIGROUP_2_6 0x00000500 ///< Priority group 2.6 split
+#define NVIC_APINT_PRIGROUP_3_5 0x00000400 ///< Priority group 3.5 split
+#define NVIC_APINT_PRIGROUP_4_4 0x00000300 ///< Priority group 4.4 split
+#define NVIC_APINT_PRIGROUP_5_3 0x00000200 ///< Priority group 5.3 split
+#define NVIC_APINT_PRIGROUP_6_2 0x00000100 ///< Priority group 6.2 split
+#define NVIC_APINT_SYSRESETREQ 0x00000004 ///< System reset request
+#define NVIC_APINT_VECT_CLR_ACT 0x00000002 ///< Clear active NMI/fault info
+#define NVIC_APINT_VECT_RESET 0x00000001 ///< System reset
+#define NVIC_APINT_PRIGROUP_7_1 0x00000000 ///< Priority group 7.1 split
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_SYS_CTRL register.
+ */
+/*\{*/
+#define NVIC_SYS_CTRL_SEVONPEND 0x00000010 ///< Wakeup on pend
+#define NVIC_SYS_CTRL_SLEEPDEEP 0x00000004 ///< Deep sleep enable
+#define NVIC_SYS_CTRL_SLEEPEXIT 0x00000002 ///< Sleep on ISR exit
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_CFG_CTRL register.
+ */
+/*\{*/
+#define NVIC_CFG_CTRL_BFHFNMIGN 0x00000100 ///< Ignore bus fault in NMI/fault
+#define NVIC_CFG_CTRL_DIV0 0x00000010 ///< Trap on divide by 0
+#define NVIC_CFG_CTRL_UNALIGNED 0x00000008 ///< Trap on unaligned access
+#define NVIC_CFG_CTRL_DEEP_PEND 0x00000004 ///< Allow deep interrupt trigger
+#define NVIC_CFG_CTRL_MAIN_PEND 0x00000002 ///< Allow main interrupt trigger
+#define NVIC_CFG_CTRL_BASE_THR 0x00000001 ///< Thread state control
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_SYS_PRI1 register.
+ */
+/*\{*/
+#define NVIC_SYS_PRI1_RES_M 0xFF000000 ///< Priority of reserved handler
+#define NVIC_SYS_PRI1_USAGE_M 0x00FF0000 ///< Priority of usage fault handler
+#define NVIC_SYS_PRI1_BUS_M 0x0000FF00 ///< Priority of bus fault handler
+#define NVIC_SYS_PRI1_MEM_M 0x000000FF ///< Priority of mem manage handler
+#define NVIC_SYS_PRI1_USAGE_S 16
+#define NVIC_SYS_PRI1_BUS_S 8
+#define NVIC_SYS_PRI1_MEM_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_SYS_PRI2 register.
+ */
+/*\{*/
+#define NVIC_SYS_PRI2_SVC_M 0xFF000000 ///< Priority of SVCall handler
+#define NVIC_SYS_PRI2_RES_M 0x00FFFFFF ///< Priority of reserved handlers
+#define NVIC_SYS_PRI2_SVC_S 24
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_SYS_PRI3 register.
+ */
+/*\{*/
+#define NVIC_SYS_PRI3_TICK_M 0xFF000000 ///< Priority of Sys Tick handler
+#define NVIC_SYS_PRI3_PENDSV_M 0x00FF0000 ///< Priority of PendSV handler
+#define NVIC_SYS_PRI3_RES_M 0x0000FF00 ///< Priority of reserved handler
+#define NVIC_SYS_PRI3_DEBUG_M 0x000000FF ///< Priority of debug handler
+#define NVIC_SYS_PRI3_TICK_S 24
+#define NVIC_SYS_PRI3_PENDSV_S 16
+#define NVIC_SYS_PRI3_DEBUG_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_SYS_HND_CTRL
+ * register.
+ */
+/*\{*/
+#define NVIC_SYS_HND_CTRL_USAGE 0x00040000 ///< Usage fault enable
+#define NVIC_SYS_HND_CTRL_BUS 0x00020000 ///< Bus fault enable
+#define NVIC_SYS_HND_CTRL_MEM 0x00010000 ///< Mem manage fault enable
+#define NVIC_SYS_HND_CTRL_SVC 0x00008000 ///< SVCall is pended
+#define NVIC_SYS_HND_CTRL_BUSP 0x00004000 ///< Bus fault is pended
+#define NVIC_SYS_HND_CTRL_TICK 0x00000800 ///< Sys tick is active
+#define NVIC_SYS_HND_CTRL_PNDSV 0x00000400 ///< PendSV is active
+#define NVIC_SYS_HND_CTRL_MON 0x00000100 ///< Monitor is active
+#define NVIC_SYS_HND_CTRL_SVCA 0x00000080 ///< SVCall is active
+#define NVIC_SYS_HND_CTRL_USGA 0x00000008 ///< Usage fault is active
+#define NVIC_SYS_HND_CTRL_BUSA 0x00000002 ///< Bus fault is active
+#define NVIC_SYS_HND_CTRL_MEMA 0x00000001 ///< Mem manage is active
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_FAULT_STAT
+ * register.
+ */
+/*\{*/
+#define NVIC_FAULT_STAT_DIV0 0x02000000 ///< Divide by zero fault
+#define NVIC_FAULT_STAT_UNALIGN 0x01000000 ///< Unaligned access fault
+#define NVIC_FAULT_STAT_NOCP 0x00080000 ///< No coprocessor fault
+#define NVIC_FAULT_STAT_INVPC 0x00040000 ///< Invalid PC fault
+#define NVIC_FAULT_STAT_INVSTAT 0x00020000 ///< Invalid state fault
+#define NVIC_FAULT_STAT_UNDEF 0x00010000 ///< Undefined instruction fault
+#define NVIC_FAULT_STAT_BFARV 0x00008000 ///< BFAR is valid
+#define NVIC_FAULT_STAT_BSTKE 0x00001000 ///< Stack bus fault
+#define NVIC_FAULT_STAT_BUSTKE 0x00000800 ///< Unstack bus fault
+#define NVIC_FAULT_STAT_IMPRE 0x00000400 ///< Imprecise data bus error
+#define NVIC_FAULT_STAT_PRECISE 0x00000200 ///< Precise data bus error
+#define NVIC_FAULT_STAT_IBUS 0x00000100 ///< Instruction bus fault
+#define NVIC_FAULT_STAT_MMARV 0x00000080 ///< MMAR is valid
+#define NVIC_FAULT_STAT_MSTKE 0x00000010 ///< Stack access violation
+#define NVIC_FAULT_STAT_MUSTKE 0x00000008 ///< Unstack access violation
+#define NVIC_FAULT_STAT_DERR 0x00000002 ///< Data access violation
+#define NVIC_FAULT_STAT_IERR 0x00000001 ///< Instruction access violation
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_HFAULT_STAT
+ * register.
+ */
+/*\{*/
+#define NVIC_HFAULT_STAT_DBG 0x80000000 ///< Debug event
+#define NVIC_HFAULT_STAT_FORCED 0x40000000 ///< Cannot execute fault handler
+#define NVIC_HFAULT_STAT_VECT 0x00000002 ///< Vector table read fault
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_DEBUG_STAT
+ * register.
+ */
+/*\{*/
+#define NVIC_DEBUG_STAT_EXTRNL 0x00000010 ///< EDBGRQ asserted
+#define NVIC_DEBUG_STAT_VCATCH 0x00000008 ///< Vector catch
+#define NVIC_DEBUG_STAT_DWTTRAP 0x00000004 ///< DWT match
+#define NVIC_DEBUG_STAT_BKPT 0x00000002 ///< Breakpoint instruction
+#define NVIC_DEBUG_STAT_HALTED 0x00000001 ///< Halt request
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_MM_ADDR register.
+ */
+/*\{*/
+#define NVIC_MM_ADDR_M 0xFFFFFFFF ///< Data fault address
+#define NVIC_MM_ADDR_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_FAULT_ADDR
+ * register.
+ */
+/*\{*/
+#define NVIC_FAULT_ADDR_M 0xFFFFFFFF ///< Data bus fault address
+#define NVIC_FAULT_ADDR_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_MPU_TYPE register.
+ */
+/*\{*/
+#define NVIC_MPU_TYPE_IREGION_M 0x00FF0000 ///< Number of I regions
+#define NVIC_MPU_TYPE_DREGION_M 0x0000FF00 ///< Number of D regions
+#define NVIC_MPU_TYPE_SEPARATE 0x00000001 ///< Separate or unified MPU
+#define NVIC_MPU_TYPE_IREGION_S 16
+#define NVIC_MPU_TYPE_DREGION_S 8
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_MPU_CTRL register.
+ */
+/*\{*/
+#define NVIC_MPU_CTRL_PRIVDEFEN 0x00000004 ///< MPU default region in priv mode
+#define NVIC_MPU_CTRL_HFNMIENA 0x00000002 ///< MPU enabled during faults
+#define NVIC_MPU_CTRL_ENABLE 0x00000001 ///< MPU enable
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_MPU_NUMBER
+ * register.
+ */
+/*\{*/
+#define NVIC_MPU_NUMBER_M 0x000000FF ///< MPU region to access
+#define NVIC_MPU_NUMBER_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_MPU_BASE register.
+ */
+/*\{*/
+#define NVIC_MPU_BASE_ADDR_M 0xFFFFFFE0 ///< Base address mask
+#define NVIC_MPU_BASE_VALID 0x00000010 ///< Region number valid
+#define NVIC_MPU_BASE_REGION_M 0x0000000F ///< Region number
+#define NVIC_MPU_BASE_ADDR_S 8
+#define NVIC_MPU_BASE_REGION_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_MPU_ATTR register.
+ */
+/*\{*/
+#define NVIC_MPU_ATTR_M 0xFFFF0000 ///< Attributes
+#define NVIC_MPU_ATTR_AP_NO_NO 0x00000000 ///< prv: no access, usr: no access
+#define NVIC_MPU_ATTR_BUFFRABLE 0x00010000 ///< Bufferable
+#define NVIC_MPU_ATTR_CACHEABLE 0x00020000 ///< Cacheable
+#define NVIC_MPU_ATTR_SHAREABLE 0x00040000 ///< Shareable
+#define NVIC_MPU_ATTR_TEX_M 0x00380000 ///< Type extension mask
+#define NVIC_MPU_ATTR_AP_RW_NO 0x01000000 ///< prv: rw, usr: none
+#define NVIC_MPU_ATTR_AP_RW_RO 0x02000000 ///< prv: rw, usr: read-only
+#define NVIC_MPU_ATTR_AP_RW_RW 0x03000000 ///< prv: rw, usr: rw
+#define NVIC_MPU_ATTR_AP_RO_NO 0x05000000 ///< prv: ro, usr: none
+#define NVIC_MPU_ATTR_AP_RO_RO 0x06000000 ///< prv: ro, usr: ro
+#define NVIC_MPU_ATTR_AP_M 0x07000000 ///< Access permissions mask
+#define NVIC_MPU_ATTR_XN 0x10000000 ///< Execute disable
+#define NVIC_MPU_ATTR_SRD_M 0x0000FF00 ///< Sub-region disable mask
+#define NVIC_MPU_ATTR_SRD_0 0x00000100 ///< Sub-region 0 disable
+#define NVIC_MPU_ATTR_SRD_1 0x00000200 ///< Sub-region 1 disable
+#define NVIC_MPU_ATTR_SRD_2 0x00000400 ///< Sub-region 2 disable
+#define NVIC_MPU_ATTR_SRD_3 0x00000800 ///< Sub-region 3 disable
+#define NVIC_MPU_ATTR_SRD_4 0x00001000 ///< Sub-region 4 disable
+#define NVIC_MPU_ATTR_SRD_5 0x00002000 ///< Sub-region 5 disable
+#define NVIC_MPU_ATTR_SRD_6 0x00004000 ///< Sub-region 6 disable
+#define NVIC_MPU_ATTR_SRD_7 0x00008000 ///< Sub-region 7 disable
+#define NVIC_MPU_ATTR_SIZE_M 0x0000003E ///< Region size mask
+#define NVIC_MPU_ATTR_SIZE_32B 0x00000008 ///< Region size 32 bytes
+#define NVIC_MPU_ATTR_SIZE_64B 0x0000000A ///< Region size 64 bytes
+#define NVIC_MPU_ATTR_SIZE_128B 0x0000000C ///< Region size 128 bytes
+#define NVIC_MPU_ATTR_SIZE_256B 0x0000000E ///< Region size 256 bytes
+#define NVIC_MPU_ATTR_SIZE_512B 0x00000010 ///< Region size 512 bytes
+#define NVIC_MPU_ATTR_SIZE_1K 0x00000012 ///< Region size 1 Kbytes
+#define NVIC_MPU_ATTR_SIZE_2K 0x00000014 ///< Region size 2 Kbytes
+#define NVIC_MPU_ATTR_SIZE_4K 0x00000016 ///< Region size 4 Kbytes
+#define NVIC_MPU_ATTR_SIZE_8K 0x00000018 ///< Region size 8 Kbytes
+#define NVIC_MPU_ATTR_SIZE_16K 0x0000001A ///< Region size 16 Kbytes
+#define NVIC_MPU_ATTR_SIZE_32K 0x0000001C ///< Region size 32 Kbytes
+#define NVIC_MPU_ATTR_SIZE_64K 0x0000001E ///< Region size 64 Kbytes
+#define NVIC_MPU_ATTR_SIZE_128K 0x00000020 ///< Region size 128 Kbytes
+#define NVIC_MPU_ATTR_SIZE_256K 0x00000022 ///< Region size 256 Kbytes
+#define NVIC_MPU_ATTR_SIZE_512K 0x00000024 ///< Region size 512 Kbytes
+#define NVIC_MPU_ATTR_SIZE_1M 0x00000026 ///< Region size 1 Mbytes
+#define NVIC_MPU_ATTR_SIZE_2M 0x00000028 ///< Region size 2 Mbytes
+#define NVIC_MPU_ATTR_SIZE_4M 0x0000002A ///< Region size 4 Mbytes
+#define NVIC_MPU_ATTR_SIZE_8M 0x0000002C ///< Region size 8 Mbytes
+#define NVIC_MPU_ATTR_SIZE_16M 0x0000002E ///< Region size 16 Mbytes
+#define NVIC_MPU_ATTR_SIZE_32M 0x00000030 ///< Region size 32 Mbytes
+#define NVIC_MPU_ATTR_SIZE_64M 0x00000032 ///< Region size 64 Mbytes
+#define NVIC_MPU_ATTR_SIZE_128M 0x00000034 ///< Region size 128 Mbytes
+#define NVIC_MPU_ATTR_SIZE_256M 0x00000036 ///< Region size 256 Mbytes
+#define NVIC_MPU_ATTR_SIZE_512M 0x00000038 ///< Region size 512 Mbytes
+#define NVIC_MPU_ATTR_SIZE_1G 0x0000003A ///< Region size 1 Gbytes
+#define NVIC_MPU_ATTR_SIZE_2G 0x0000003C ///< Region size 2 Gbytes
+#define NVIC_MPU_ATTR_SIZE_4G 0x0000003E ///< Region size 4 Gbytes
+#define NVIC_MPU_ATTR_ENABLE 0x00000001 ///< Region enable
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_DBG_CTRL register.
+ */
+/*\{*/
+#define NVIC_DBG_CTRL_DBGKEY_M 0xFFFF0000 ///< Debug key mask
+#define NVIC_DBG_CTRL_DBGKEY 0xA05F0000 ///< Debug key
+#define NVIC_DBG_CTRL_S_RESET_ST \
+ 0x02000000 ///< Core has reset since last read
+#define NVIC_DBG_CTRL_S_RETIRE_ST \
+ 0x01000000 ///< Core has executed insruction
+ ///< since last read
+#define NVIC_DBG_CTRL_S_LOCKUP 0x00080000 ///< Core is locked up
+#define NVIC_DBG_CTRL_S_SLEEP 0x00040000 ///< Core is sleeping
+#define NVIC_DBG_CTRL_S_HALT 0x00020000 ///< Core status on halt
+#define NVIC_DBG_CTRL_S_REGRDY 0x00010000 ///< Register read/write available
+#define NVIC_DBG_CTRL_C_SNAPSTALL \
+ 0x00000020 ///< Breaks a stalled load/store
+#define NVIC_DBG_CTRL_C_MASKINT 0x00000008 ///< Mask interrupts when stepping
+#define NVIC_DBG_CTRL_C_STEP 0x00000004 ///< Step the core
+#define NVIC_DBG_CTRL_C_HALT 0x00000002 ///< Halt the core
+#define NVIC_DBG_CTRL_C_DEBUGEN 0x00000001 ///< Enable debug
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_DBG_XFER register.
+ */
+/*\{*/
+#define NVIC_DBG_XFER_REG_WNR 0x00010000 ///< Write or not read
+#define NVIC_DBG_XFER_REG_SEL_M 0x0000001F ///< Register
+#define NVIC_DBG_XFER_REG_CFBP 0x00000014 ///< Control/Fault/BasePri/PriMask
+#define NVIC_DBG_XFER_REG_DSP 0x00000013 ///< Deep SP
+#define NVIC_DBG_XFER_REG_PSP 0x00000012 ///< Process SP
+#define NVIC_DBG_XFER_REG_MSP 0x00000011 ///< Main SP
+#define NVIC_DBG_XFER_REG_FLAGS 0x00000010 ///< xPSR/Flags register
+#define NVIC_DBG_XFER_REG_R15 0x0000000F ///< Register R15
+#define NVIC_DBG_XFER_REG_R14 0x0000000E ///< Register R14
+#define NVIC_DBG_XFER_REG_R13 0x0000000D ///< Register R13
+#define NVIC_DBG_XFER_REG_R12 0x0000000C ///< Register R12
+#define NVIC_DBG_XFER_REG_R11 0x0000000B ///< Register R11
+#define NVIC_DBG_XFER_REG_R10 0x0000000A ///< Register R10
+#define NVIC_DBG_XFER_REG_R9 0x00000009 ///< Register R9
+#define NVIC_DBG_XFER_REG_R8 0x00000008 ///< Register R8
+#define NVIC_DBG_XFER_REG_R7 0x00000007 ///< Register R7
+#define NVIC_DBG_XFER_REG_R6 0x00000006 ///< Register R6
+#define NVIC_DBG_XFER_REG_R5 0x00000005 ///< Register R5
+#define NVIC_DBG_XFER_REG_R4 0x00000004 ///< Register R4
+#define NVIC_DBG_XFER_REG_R3 0x00000003 ///< Register R3
+#define NVIC_DBG_XFER_REG_R2 0x00000002 ///< Register R2
+#define NVIC_DBG_XFER_REG_R1 0x00000001 ///< Register R1
+#define NVIC_DBG_XFER_REG_R0 0x00000000 ///< Register R0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_DBG_DATA register.
+ */
+/*\{*/
+#define NVIC_DBG_DATA_M 0xFFFFFFFF ///< Data temporary cache
+#define NVIC_DBG_DATA_S 0
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_DBG_INT register.
+ */
+/*\{*/
+#define NVIC_DBG_INT_HARDERR 0x00000400 ///< Debug trap on hard fault
+#define NVIC_DBG_INT_INTERR 0x00000200 ///< Debug trap on interrupt errors
+#define NVIC_DBG_INT_BUSERR 0x00000100 ///< Debug trap on bus error
+#define NVIC_DBG_INT_STATERR 0x00000080 ///< Debug trap on usage fault state
+#define NVIC_DBG_INT_CHKERR 0x00000040 ///< Debug trap on usage fault check
+#define NVIC_DBG_INT_NOCPERR 0x00000020 ///< Debug trap on coprocessor error
+#define NVIC_DBG_INT_MMERR 0x00000010 ///< Debug trap on mem manage fault
+#define NVIC_DBG_INT_RESET 0x00000008 ///< Core reset status
+#define NVIC_DBG_INT_RSTPENDCLR 0x00000004 ///< Clear pending core reset
+#define NVIC_DBG_INT_RSTPENDING 0x00000002 ///< Core reset is pending
+#define NVIC_DBG_INT_RSTVCATCH 0x00000001 ///< Reset vector catch
+/*\}*/
+
+/**
+ * The following are defines for the bit fields in the NVIC_SW_TRIG register.
+ */
+/*\{*/
+#define NVIC_SW_TRIG_INTID_M 0x000003FF ///< Interrupt to trigger
+#define NVIC_SW_TRIG_INTID_S 0
+/*\}*/
+
+#endif /* SAM3_NVIC_H */
--- /dev/null
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction. Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License. This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \brief AT91SAM3 PMC hardware.
+ */
+
+#ifndef SAM3_PMC_H
+#define SAM3_PMC_H
+
+// FIXME: move these in sam3(?)_int.h
+#define INT_SUPC 0 ///< SAM3N Supply Controller (SUPC)
+#define INT_RSTC 1 ///< SAM3N Reset Controller (RSTC)
+#define INT_RTC 2 ///< SAM3N Real Time Clock (RTC)
+#define INT_RTT 3 ///< SAM3N Real Time Timer (RTT)
+#define INT_WDT 4 ///< SAM3N Watchdog Timer (WDT)
+#define INT_PMC 5 ///< SAM3N Power Management Controller (PMC)
+#define INT_EFC 6 ///< SAM3N Enhanced Flash Controller (EFC)
+#define INT_UART0 8 ///< SAM3N UART 0 (UART0)
+#define INT_UART1 9 ///< SAM3N UART 1 (UART1)
+#define INT_PIOA 11 ///< SAM3N Parallel I/O Controller A (PIOA)
+#define INT_PIOB 12 ///< SAM3N Parallel I/O Controller B (PIOB)
+#define INT_PIOC 13 ///< SAM3N Parallel I/O Controller C (PIOC)
+#define INT_USART0 14 ///< SAM3N USART 0 (USART0)
+#define INT_USART1 15 ///< SAM3N USART 1 (USART1)
+#define INT_TWI0 19 ///< SAM3N Two Wire Interface 0 (TWI0)
+#define INT_TWI1 20 ///< SAM3N Two Wire Interface 1 (TWI1)
+#define INT_SPI 21 ///< SAM3N Serial Peripheral Interface (SPI)
+#define INT_TC0 23 ///< SAM3N Timer/Counter 0 (TC0)
+#define INT_TC1 24 ///< SAM3N Timer/Counter 1 (TC1)
+#define INT_TC2 25 ///< SAM3N Timer/Counter 2 (TC2)
+#define INT_TC3 26 ///< SAM3N Timer/Counter 3 (TC3)
+#define INT_TC4 27 ///< SAM3N Timer/Counter 4 (TC4)
+#define INT_TC5 28 ///< SAM3N Timer/Counter 5 (TC5)
+#define INT_ADC 29 ///< SAM3N Analog To Digital Converter (ADC)
+#define INT_DACC 30 ///< SAM3N Digital To Analog Converter (DACC)
+#define INT_PWM 31 ///< SAM3N Pulse Width Modulation (PWM)
+
+/**
+ * PMC registers.
+ */
+/*\{*/
+#define PMC_SCER_R (*((reg32_t *)0x400E0400)) ///< System Clock Enable Register
+#define PMC_SCDR_R (*((reg32_t *)0x400E0404)) ///< System Clock Disable Register
+#define PMC_SCSR_R (*((reg32_t *)0x400E0408)) ///< System Clock Status Register
+#define PMC_PCER_R (*((reg32_t *)0x400E0410)) ///< Peripheral Clock Enable Register
+#define PMC_PCDR_R (*((reg32_t *)0x400E0414)) ///< Peripheral Clock Disable Register
+#define PMC_PCSR_R (*((reg32_t *)0x400E0418)) ///< Peripheral Clock Status Register
+#define PMC_MOR_R (*((reg32_t *)0x400E0420)) ///< Main Oscillator Register
+#define PMC_MCFR_R (*((reg32_t *)0x400E0424)) ///< Main Clock Frequency Register
+#define PMC_PLLR_R (*((reg32_t *)0x400E0428)) ///< PLL Register
+#define PMC_MCKR_R (*((reg32_t *)0x400E0430)) ///< Master Clock Register
+#define PMC_PCK_R (*((reg32_t *)0x400E0440)) ///< Programmable Clock 0 Register
+#define PMC_IER_R (*((reg32_t *)0x400E0460)) ///< Interrupt Enable Register
+#define PMC_IDR_R (*((reg32_t *)0x400E0464)) ///< Interrupt Disable Register
+#define PMC_SR_R (*((reg32_t *)0x400E0468)) ///< Status Register
+#define PMC_IMR_R (*((reg32_t *)0x400E046C)) ///< Interrupt Mask Register
+#define PMC_FSMR_R (*((reg32_t *)0x400E0470)) ///< Fast Startup Mode Register
+#define PMC_FSPR_R (*((reg32_t *)0x400E0474)) ///< Fast Startup Polarity Register
+#define PMC_FOCR_R (*((reg32_t *)0x400E0478)) ///< Fault Output Clear Register
+#define PMC_WPMR_R (*((reg32_t *)0x400E04E4)) ///< Write Protect Mode Register
+#define PMC_WPSR_R (*((reg32_t *)0x400E04E8)) ///< Write Protect Status Register
+#define PMC_OCR_R (*((reg32_t *)0x400E0510)) ///< Oscillator Calibration Register
+/*\}*/
+
+/**
+ * PMC register addresses.
+ */
+/*\{*/
+#define PMC_SCER 0x400E0400 ///< System Clock Enable Register
+#define PMC_SCDR 0x400E0404 ///< System Clock Disable Register
+#define PMC_SCSR 0x400E0408 ///< System Clock Status Register
+#define PMC_PCER 0x400E0410 ///< Peripheral Clock Enable Register
+#define PMC_PCDR 0x400E0414 ///< Peripheral Clock Disable Register
+#define PMC_PCSR 0x400E0418 ///< Peripheral Clock Status Register
+#define PMC_MOR 0x400E0420 ///< Main Oscillator Register
+#define PMC_MCFR 0x400E0424 ///< Main Clock Frequency Register
+#define PMC_PLLR 0x400E0428 ///< PLL Register
+#define PMC_MCKR 0x400E0430 ///< Master Clock Register
+#define PMC_PCK 0x400E0440 ///< Programmable Clock 0 Register
+#define PMC_IER 0x400E0460 ///< Interrupt Enable Register
+#define PMC_IDR 0x400E0464 ///< Interrupt Disable Register
+#define PMC_SR 0x400E0468 ///< Status Register
+#define PMC_IMR 0x400E046C ///< Interrupt Mask Register
+#define PMC_FSMR 0x400E0470 ///< Fast Startup Mode Register
+#define PMC_FSPR 0x400E0474 ///< Fast Startup Polarity Register
+#define PMC_FOCR 0x400E0478 ///< Fault Output Clear Register
+#define PMC_WPMR 0x400E04E4 ///< Write Protect Mode Register
+#define PMC_WPSR 0x400E04E8 ///< Write Protect Status Register
+#define PMC_OCR 0x400E0510 ///< Oscillator Calibration Register
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_SCER register.
+ */
+/*\{*/
+#define PMC_SCER_PCK0 BV(8) ///< Programmable Clock 0 Output Enable
+#define PMC_SCER_PCK1 BV(9) ///< Programmable Clock 1 Output Enable
+#define PMC_SCER_PCK2 BV(10) ///< Programmable Clock 2 Output Enable
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_SCDR register.
+ */
+/*\{*/
+#define PMC_SCDR_PCK0 BV(8) ///< Programmable Clock 0 Output Disable
+#define PMC_SCDR_PCK1 BV(9) ///< Programmable Clock 1 Output Disable
+#define PMC_SCDR_PCK2 BV(10) ///< Programmable Clock 2 Output Disable
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_SCSR register.
+ */
+/*\{*/
+#define PMC_SCSR_PCK0 BV(8) ///< Programmable Clock 0 Output Status
+#define PMC_SCSR_PCK1 BV(9) ///< Programmable Clock 1 Output Status
+#define PMC_SCSR_PCK2 BV(10) ///< Programmable Clock 2 Output Status
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_PCER register.
+ */
+/*\{*/
+#define PMC_PCER_PID2 BV(2) ///< Peripheral Clock 2 Enable
+#define PMC_PCER_PID3 BV(3) ///< Peripheral Clock 3 Enable
+#define PMC_PCER_PID4 BV(4) ///< Peripheral Clock 4 Enable
+#define PMC_PCER_PID5 BV(5) ///< Peripheral Clock 5 Enable
+#define PMC_PCER_PID6 BV(6) ///< Peripheral Clock 6 Enable
+#define PMC_PCER_PID7 BV(7) ///< Peripheral Clock 7 Enable
+#define PMC_PCER_PID8 BV(8) ///< Peripheral Clock 8 Enable
+#define PMC_PCER_PID9 BV(9) ///< Peripheral Clock 9 Enable
+#define PMC_PCER_PID10 BV(10) ///< Peripheral Clock 10 Enable
+#define PMC_PCER_PID11 BV(11) ///< Peripheral Clock 11 Enable
+#define PMC_PCER_PID12 BV(12) ///< Peripheral Clock 12 Enable
+#define PMC_PCER_PID13 BV(13) ///< Peripheral Clock 13 Enable
+#define PMC_PCER_PID14 BV(14) ///< Peripheral Clock 14 Enable
+#define PMC_PCER_PID15 BV(15) ///< Peripheral Clock 15 Enable
+#define PMC_PCER_PID16 BV(16) ///< Peripheral Clock 16 Enable
+#define PMC_PCER_PID17 BV(17) ///< Peripheral Clock 17 Enable
+#define PMC_PCER_PID18 BV(18) ///< Peripheral Clock 18 Enable
+#define PMC_PCER_PID19 BV(19) ///< Peripheral Clock 19 Enable
+#define PMC_PCER_PID20 BV(20) ///< Peripheral Clock 20 Enable
+#define PMC_PCER_PID21 BV(21) ///< Peripheral Clock 21 Enable
+#define PMC_PCER_PID22 BV(22) ///< Peripheral Clock 22 Enable
+#define PMC_PCER_PID23 BV(23) ///< Peripheral Clock 23 Enable
+#define PMC_PCER_PID24 BV(24) ///< Peripheral Clock 24 Enable
+#define PMC_PCER_PID25 BV(25) ///< Peripheral Clock 25 Enable
+#define PMC_PCER_PID26 BV(26) ///< Peripheral Clock 26 Enable
+#define PMC_PCER_PID27 BV(27) ///< Peripheral Clock 27 Enable
+#define PMC_PCER_PID28 BV(28) ///< Peripheral Clock 28 Enable
+#define PMC_PCER_PID29 BV(29) ///< Peripheral Clock 29 Enable
+#define PMC_PCER_PID30 BV(30) ///< Peripheral Clock 30 Enable
+#define PMC_PCER_PID31 BV(31) ///< Peripheral Clock 31 Enable
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_PCDR register.
+ */
+/*\{*/
+#define PMC_PCDR_PID2 BV(2) ///< Peripheral Clock 2 Disable
+#define PMC_PCDR_PID3 BV(3) ///< Peripheral Clock 3 Disable
+#define PMC_PCDR_PID4 BV(4) ///< Peripheral Clock 4 Disable
+#define PMC_PCDR_PID5 BV(5) ///< Peripheral Clock 5 Disable
+#define PMC_PCDR_PID6 BV(6) ///< Peripheral Clock 6 Disable
+#define PMC_PCDR_PID7 BV(7) ///< Peripheral Clock 7 Disable
+#define PMC_PCDR_PID8 BV(8) ///< Peripheral Clock 8 Disable
+#define PMC_PCDR_PID9 BV(9) ///< Peripheral Clock 9 Disable
+#define PMC_PCDR_PID10 BV(10) ///< Peripheral Clock 10 Disable
+#define PMC_PCDR_PID11 BV(11) ///< Peripheral Clock 11 Disable
+#define PMC_PCDR_PID12 BV(12) ///< Peripheral Clock 12 Disable
+#define PMC_PCDR_PID13 BV(13) ///< Peripheral Clock 13 Disable
+#define PMC_PCDR_PID14 BV(14) ///< Peripheral Clock 14 Disable
+#define PMC_PCDR_PID15 BV(15) ///< Peripheral Clock 15 Disable
+#define PMC_PCDR_PID16 BV(16) ///< Peripheral Clock 16 Disable
+#define PMC_PCDR_PID17 BV(17) ///< Peripheral Clock 17 Disable
+#define PMC_PCDR_PID18 BV(18) ///< Peripheral Clock 18 Disable
+#define PMC_PCDR_PID19 BV(19) ///< Peripheral Clock 19 Disable
+#define PMC_PCDR_PID20 BV(20) ///< Peripheral Clock 20 Disable
+#define PMC_PCDR_PID21 BV(21) ///< Peripheral Clock 21 Disable
+#define PMC_PCDR_PID22 BV(22) ///< Peripheral Clock 22 Disable
+#define PMC_PCDR_PID23 BV(23) ///< Peripheral Clock 23 Disable
+#define PMC_PCDR_PID24 BV(24) ///< Peripheral Clock 24 Disable
+#define PMC_PCDR_PID25 BV(25) ///< Peripheral Clock 25 Disable
+#define PMC_PCDR_PID26 BV(26) ///< Peripheral Clock 26 Disable
+#define PMC_PCDR_PID27 BV(27) ///< Peripheral Clock 27 Disable
+#define PMC_PCDR_PID28 BV(28) ///< Peripheral Clock 28 Disable
+#define PMC_PCDR_PID29 BV(29) ///< Peripheral Clock 29 Disable
+#define PMC_PCDR_PID30 BV(30) ///< Peripheral Clock 30 Disable
+#define PMC_PCDR_PID31 BV(31) ///< Peripheral Clock 31 Disable
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_PCSR register.
+ */
+/*\{*/
+#define PMC_PCSR_PID2 BV(2) ///< Peripheral Clock 2 Status
+#define PMC_PCSR_PID3 BV(3) ///< Peripheral Clock 3 Status
+#define PMC_PCSR_PID4 BV(4) ///< Peripheral Clock 4 Status
+#define PMC_PCSR_PID5 BV(5) ///< Peripheral Clock 5 Status
+#define PMC_PCSR_PID6 BV(6) ///< Peripheral Clock 6 Status
+#define PMC_PCSR_PID7 BV(7) ///< Peripheral Clock 7 Status
+#define PMC_PCSR_PID8 BV(8) ///< Peripheral Clock 8 Status
+#define PMC_PCSR_PID9 BV(9) ///< Peripheral Clock 9 Status
+#define PMC_PCSR_PID10 BV(10) ///< Peripheral Clock 10 Status
+#define PMC_PCSR_PID11 BV(11) ///< Peripheral Clock 11 Status
+#define PMC_PCSR_PID12 BV(12) ///< Peripheral Clock 12 Status
+#define PMC_PCSR_PID13 BV(13) ///< Peripheral Clock 13 Status
+#define PMC_PCSR_PID14 BV(14) ///< Peripheral Clock 14 Status
+#define PMC_PCSR_PID15 BV(15) ///< Peripheral Clock 15 Status
+#define PMC_PCSR_PID16 BV(16) ///< Peripheral Clock 16 Status
+#define PMC_PCSR_PID17 BV(17) ///< Peripheral Clock 17 Status
+#define PMC_PCSR_PID18 BV(18) ///< Peripheral Clock 18 Status
+#define PMC_PCSR_PID19 BV(19) ///< Peripheral Clock 19 Status
+#define PMC_PCSR_PID20 BV(20) ///< Peripheral Clock 20 Status
+#define PMC_PCSR_PID21 BV(21) ///< Peripheral Clock 21 Status
+#define PMC_PCSR_PID22 BV(22) ///< Peripheral Clock 22 Status
+#define PMC_PCSR_PID23 BV(23) ///< Peripheral Clock 23 Status
+#define PMC_PCSR_PID24 BV(24) ///< Peripheral Clock 24 Status
+#define PMC_PCSR_PID25 BV(25) ///< Peripheral Clock 25 Status
+#define PMC_PCSR_PID26 BV(26) ///< Peripheral Clock 26 Status
+#define PMC_PCSR_PID27 BV(27) ///< Peripheral Clock 27 Status
+#define PMC_PCSR_PID28 BV(28) ///< Peripheral Clock 28 Status
+#define PMC_PCSR_PID29 BV(29) ///< Peripheral Clock 29 Status
+#define PMC_PCSR_PID30 BV(30) ///< Peripheral Clock 30 Status
+#define PMC_PCSR_PID31 BV(31) ///< Peripheral Clock 31 Status
+/*\}*/
+
+/**
+ * Defines for bit fields in CKGR_MOR register.
+ */
+/*\{*/
+#define CKGR_MOR_MOSCXTEN BV(0) ///< Main Crystal Oscillator Enable
+#define CKGR_MOR_MOSCXTBY BV(1) ///< Main Crystal Oscillator Bypass
+#define CKGR_MOR_WAITMODE BV(2) ///< Wait Mode Command
+#define CKGR_MOR_MOSCRCEN BV(3) ///< Main On-Chip RC Oscillator Enable
+#define CKGR_MOR_MOSCRCF_S 4
+#define CKGR_MOR_MOSCRCF_M (0x7 << CKGR_MOR_MOSCRCF_S) ///< Main On-Chip RC Oscillator Frequency Selection
+#define CKGR_MOR_MOSCRCF(value) ((CKGR_MOR_MOSCRCF_M & ((value) << CKGR_MOR_MOSCRCF_S)))
+#define CKGR_MOR_MOSCRCF_4MHZ (0x0 << CKGR_MOR_MOSCRCF_S)
+#define CKGR_MOR_MOSCRCF_8MHZ (0x1 << CKGR_MOR_MOSCRCF_S)
+#define CKGR_MOR_MOSCRCF_12MHZ (0x2 << CKGR_MOR_MOSCRCF_S)
+#define CKGR_MOR_MOSCXTST_S 8
+#define CKGR_MOR_MOSCXTST_M (0xff << CKGR_MOR_MOSCXTST_S) ///< Main Crystal Oscillator Start-up Time
+#define CKGR_MOR_MOSCXTST(value) ((CKGR_MOR_MOSCXTST_M & ((value) << CKGR_MOR_MOSCXTST_S)))
+#define CKGR_MOR_KEY_S 16
+#define CKGR_MOR_KEY_M (0xffu << CKGR_MOR_KEY_S) ///< Password
+#define CKGR_MOR_KEY(value) ((CKGR_MOR_KEY_M & ((value) << CKGR_MOR_KEY_S)))
+#define CKGR_MOR_MOSCSEL BV(24) ///< Main Oscillator Selection
+#define CKGR_MOR_CFDEN BV(25) ///< Clock Failure Detector Enable
+/*\}*/
+
+/**
+ * Defines for bit fields in CKGR_MCFR register.
+ */
+/*\{*/
+#define CKGR_MCFR_MAINF_M 0xffffu ///< Main Clock Frequency mask
+#define CKGR_MCFR_MAINFRDY BV(16) ///< Main Clock Ready
+/*\}*/
+
+/**
+ * Defines for bit fields in CKGR_PLLR register.
+ */
+/*\{*/
+#define CKGR_PLLR_DIV_M 0xff ///< Divider mask
+#define CKGR_PLLR_DIV(value) ((CKGR_PLLR_DIV_M & (value))
+#define CKGR_PLLR_PLLCOUNT_S 8
+#define CKGR_PLLR_PLLCOUNT_M (0x3f << CKGR_PLLR_PLLCOUNT_S) ///< PLL Counter mask
+#define CKGR_PLLR_PLLCOUNT(value) ((CKGR_PLLR_PLLCOUNT_M & ((value) << CKGR_PLLR_PLLCOUNT_S)))
+#define CKGR_PLLR_MUL_S 16
+#define CKGR_PLLR_MUL_M (0x7ff << CKGR_PLLR_MUL_S) ///< PLL Multiplier mask
+#define CKGR_PLLR_MUL(value) ((CKGR_PLLR_MUL_M & ((value) << CKGR_PLLR_MUL_S)))
+#define CKGR_PLLR_STUCKTO1 BV(29)
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_MCKR register.
+ */
+/*\{*/
+#define PMC_MCKR_CSS_M 0x3 ///< Master Clock Source Selection mask
+#define PMC_MCKR_CSS_SLOW_CLK 0x0 ///< Slow Clock is selected
+#define PMC_MCKR_CSS_MAIN_CLK 0x1 ///< Main Clock is selected
+#define PMC_MCKR_CSS_PLL_CLK 0x2 ///< PLL Clock is selected
+#define PMC_MCKR_PRES_S 4
+#define PMC_MCKR_PRES_M (0x7u << PMC_MCKR_PRES_S) ///< Processor Clock Prescaler mask
+#define PMC_MCKR_PRES_CLK (0x0u << PMC_MCKR_PRES_S) ///< Selected clock
+#define PMC_MCKR_PRES_CLK_2 (0x1u << PMC_MCKR_PRES_S) ///< Selected clock divided by 2
+#define PMC_MCKR_PRES_CLK_4 (0x2u << PMC_MCKR_PRES_S) ///< Selected clock divided by 4
+#define PMC_MCKR_PRES_CLK_8 (0x3u << PMC_MCKR_PRES_S) ///< Selected clock divided by 8
+#define PMC_MCKR_PRES_CLK_16 (0x4u << PMC_MCKR_PRES_S) ///< Selected clock divided by 16
+#define PMC_MCKR_PRES_CLK_32 (0x5u << PMC_MCKR_PRES_S) ///< Selected clock divided by 32
+#define PMC_MCKR_PRES_CLK_64 (0x6u << PMC_MCKR_PRES_S) ///< Selected clock divided by 64
+#define PMC_MCKR_PRES_CLK_3 (0x7u << PMC_MCKR_PRES_S) ///< Selected clock divided by 3
+#define PMC_MCKR_PLLDIV2 BV(12) ///< PLL Divisor by 2
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_PCK[3] register.
+ */
+/*\{*/
+#define PMC_PCK_CSS_M 0x7 ///< Master Clock Source Selection mask
+#define PMC_PCK_CSS_SLOW 0x0 ///< Slow Clock is selected
+#define PMC_PCK_CSS_MAIN 0x1 ///< Main Clock is selected
+#define PMC_PCK_CSS_PLL 0x2 ///< PLL Clock is selected
+#define PMC_PCK_CSS_MCK 0x4 ///< Master Clock is selected
+#define PMC_PCK_PRES_S 4
+#define PMC_PCK_PRES_M (0x7u << PMC_PCK_PRES_S) ///< Programmable Clock Prescaler
+#define PMC_PCK_PRES_CLK (0x0u << PMC_PCK_PRES_S) ///< Selected clock
+#define PMC_PCK_PRES_CLK_2 (0x1u << PMC_PCK_PRES_S) ///< Selected clock divided by 2
+#define PMC_PCK_PRES_CLK_4 (0x2u << PMC_PCK_PRES_S) ///< Selected clock divided by 4
+#define PMC_PCK_PRES_CLK_8 (0x3u << PMC_PCK_PRES_S) ///< Selected clock divided by 8
+#define PMC_PCK_PRES_CLK_16 (0x4u << PMC_PCK_PRES_S) ///< Selected clock divided by 16
+#define PMC_PCK_PRES_CLK_32 (0x5u << PMC_PCK_PRES_S) ///< Selected clock divided by 32
+#define PMC_PCK_PRES_CLK_64 (0x6u << PMC_PCK_PRES_S) ///< Selected clock divided by 64
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_IER register.
+ */
+/*\{*/
+#define PMC_IER_MOSCXTS BV(0) ///< Main Crystal Oscillator Status Interrupt Enable
+#define PMC_IER_LOCK BV(1) ///< PLL Lock Interrupt Enable
+#define PMC_IER_MCKRDY BV(3) ///< Master Clock Ready Interrupt Enable
+#define PMC_IER_PCKRDY0 BV(8) ///< Programmable Clock Ready 0 Interrupt Enable
+#define PMC_IER_PCKRDY1 BV(9) ///< Programmable Clock Ready 1 Interrupt Enable
+#define PMC_IER_PCKRDY2 BV(10) ///< Programmable Clock Ready 2 Interrupt Enable
+#define PMC_IER_MOSCSELS BV(16) ///< Main Oscillator Selection Status Interrupt Enable
+#define PMC_IER_MOSCRCS BV(17) ///< Main On-Chip RC Status Interrupt Enable
+#define PMC_IER_CFDEV BV(18) ///< Clock Failure Detector Event Interrupt Enable
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_IDR register.
+ */
+/*\{*/
+#define PMC_IDR_MOSCXTS BV(0) ///< Main Crystal Oscillator Status Interrupt Disable
+#define PMC_IDR_LOCK BV(1) ///< PLL Lock Interrupt Disable
+#define PMC_IDR_MCKRDY BV(3) ///< Master Clock Ready Interrupt Disable
+#define PMC_IDR_PCKRDY0 BV(8) ///< Programmable Clock Ready 0 Interrupt Disable
+#define PMC_IDR_PCKRDY1 BV(9) ///< Programmable Clock Ready 1 Interrupt Disable
+#define PMC_IDR_PCKRDY2 BV(10) ///< Programmable Clock Ready 2 Interrupt Disable
+#define PMC_IDR_MOSCSELS BV(16) ///< Main Oscillator Selection Status Interrupt Disable
+#define PMC_IDR_MOSCRCS BV(17) ///< Main On-Chip RC Status Interrupt Disable
+#define PMC_IDR_CFDEV BV(18) ///< Clock Failure Detector Event Interrupt Disable
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_SR register.
+ */
+/*\{*/
+#define PMC_SR_MOSCXTS BV(0) ///< Main XTAL Oscillator Status
+#define PMC_SR_LOCK BV(1) ///< PLL Lock Status
+#define PMC_SR_MCKRDY BV(3) ///< Master Clock Status
+#define PMC_SR_OSCSELS BV(7) ///< Slow Clock Oscillator Selection
+#define PMC_SR_PCKRDY0 BV(8) ///< Programmable Clock Ready Status
+#define PMC_SR_PCKRDY1 BV(9) ///< Programmable Clock Ready Status
+#define PMC_SR_PCKRDY2 BV(10) ///< Programmable Clock Ready Status
+#define PMC_SR_MOSCSELS BV(16) ///< Main Oscillator Selection Status
+#define PMC_SR_MOSCRCS BV(17) ///< Main On-Chip RC Oscillator Status
+#define PMC_SR_CFDEV BV(18) ///< Clock Failure Detector Event
+#define PMC_SR_CFDS BV(19) ///< Clock Failure Detector Status
+#define PMC_SR_FOS BV(20) ///< Clock Failure Detector Fault Output Status
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_IMR register.
+ */
+/*\{*/
+#define PMC_IMR_MOSCXTS BV(0) ///< Main Crystal Oscillator Status Interrupt Mask
+#define PMC_IMR_LOCK BV(1) ///< PLL Lock Interrupt Mask
+#define PMC_IMR_MCKRDY BV(3) ///< Master Clock Ready Interrupt Mask
+#define PMC_IMR_PCKRDY0 BV(8) ///< Programmable Clock Ready 0 Interrupt Mask
+#define PMC_IMR_PCKRDY1 BV(9) ///< Programmable Clock Ready 1 Interrupt Mask
+#define PMC_IMR_PCKRDY2 BV(10) ///< Programmable Clock Ready 2 Interrupt Mask
+#define PMC_IMR_MOSCSELS BV(16) ///< Main Oscillator Selection Status Interrupt Mask
+#define PMC_IMR_MOSCRCS BV(17) ///< Main On-Chip RC Status Interrupt Mask
+#define PMC_IMR_CFDEV BV(18) ///< Clock Failure Detector Event Interrupt Mask
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_FSMR register.
+ */
+/*\{*/
+#define PMC_FSMR_FSTT0 BV(0) ///< Fast Startup Input Enable 0
+#define PMC_FSMR_FSTT1 BV(1) ///< Fast Startup Input Enable 1
+#define PMC_FSMR_FSTT2 BV(2) ///< Fast Startup Input Enable 2
+#define PMC_FSMR_FSTT3 BV(3) ///< Fast Startup Input Enable 3
+#define PMC_FSMR_FSTT4 BV(4) ///< Fast Startup Input Enable 4
+#define PMC_FSMR_FSTT5 BV(5) ///< Fast Startup Input Enable 5
+#define PMC_FSMR_FSTT6 BV(6) ///< Fast Startup Input Enable 6
+#define PMC_FSMR_FSTT7 BV(7) ///< Fast Startup Input Enable 7
+#define PMC_FSMR_FSTT8 BV(8) ///< Fast Startup Input Enable 8
+#define PMC_FSMR_FSTT9 BV(9) ///< Fast Startup Input Enable 9
+#define PMC_FSMR_FSTT10 BV(10) ///< Fast Startup Input Enable 10
+#define PMC_FSMR_FSTT11 BV(11) ///< Fast Startup Input Enable 11
+#define PMC_FSMR_FSTT12 BV(12) ///< Fast Startup Input Enable 12
+#define PMC_FSMR_FSTT13 BV(13) ///< Fast Startup Input Enable 13
+#define PMC_FSMR_FSTT14 BV(14) ///< Fast Startup Input Enable 14
+#define PMC_FSMR_FSTT15 BV(15) ///< Fast Startup Input Enable 15
+#define PMC_FSMR_RTTAL BV(16) ///< RTT Alarm Enable
+#define PMC_FSMR_RTCAL BV(17) ///< RTC Alarm Enable
+#define PMC_FSMR_LPM BV(20) ///< Low Power Mode
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_FSPR register.
+ */
+/*\{*/
+#define PMC_FSPR_FSTP0 BV(0) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP1 BV(1) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP2 BV(2) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP3 BV(3) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP4 BV(4) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP5 BV(5) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP6 BV(6) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP7 BV(7) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP8 BV(8) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP9 BV(9) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP10 BV(10) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP11 BV(11) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP12 BV(12) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP13 BV(13) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP14 BV(14) ///< Fast Startup Input Polarityx
+#define PMC_FSPR_FSTP15 BV(15) ///< Fast Startup Input Polarityx
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_FOCR register.
+ */
+/*\{*/
+#define PMC_FOCR_FOCLR BV(0) ///< Fault Output Clear
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_WPMR register.
+ */
+/*\{*/
+#define PMC_WPMR_WPEN BV(0) ///< Write Protect Enable
+#define PMC_WPMR_WPKEY_S 8
+#define PMC_WPMR_WPKEY_M (0xffffff << PMC_WPMR_WPKEY_S) ///< Write Protect key mask
+#define PMC_WPMR_WPKEY(value) ((PMC_WPMR_WPKEY_M & ((value) << PMC_WPMR_WPKEY_S)))
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_WPSR register.
+ */
+/*\{*/
+#define PMC_WPSR_WPVS BV(0) ///< Write Protect Violation Status
+#define PMC_WPSR_WPVSRC_S 8
+#define PMC_WPSR_WPVSRC_M (0xffff << PMC_WPSR_WPVSRC_S) ///< Write Protect Violation Source mask
+/*\}*/
+
+/**
+ * Defines for bit fields in PMC_OCR register.
+ */
+/*\{*/
+#define PMC_OCR_CAL4_M 0x7f ///< RC Oscillator Calibration bits for 4 MHz mask
+#define PMC_OCR_CAL4(value) (PMC_OCR_CAL4_M & (value))
+#define PMC_OCR_SEL4 BV(7) ///< Selection of RC Oscillator Calibration bits for 4 MHz
+#define PMC_OCR_CAL8_S 8
+#define PMC_OCR_CAL8_M (0x7f << PMC_OCR_CAL8_S) ///< RC Oscillator Calibration bits for 8 MHz mask
+#define PMC_OCR_CAL8(value) ((PMC_OCR_CAL8_M & ((value) << PMC_OCR_CAL8_S)))
+#define PMC_OCR_SEL8 BV(15) ///< Selection of RC Oscillator Calibration bits for 8 MHz
+#define PMC_OCR_CAL12_S 16
+#define PMC_OCR_CAL12_M (0x7f << PMC_OCR_CAL12_S) ///< RC Oscillator Calibration bits for 12 MHz mask
+#define PMC_OCR_CAL12(value) ((PMC_OCR_CAL12_M & ((value) << PMC_OCR_CAL12_S)))
+#define PMC_OCR_SEL12 BV(23) ///< Selection of RC Oscillator Calibration bits for 12 MHz
+/*\}*/
+
+
+#endif /* SAM3_PMC_H */
--- /dev/null
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction. Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License. This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \brief AT91SAM3 UART hardware.
+ */
+
+#ifndef SAM3_UART_H
+#define SAM3_UART_H
+
+/**
+ * UART registers base addresses.
+ */
+/*\{*/
+#define UART0_BASE 0x400E0600
+#ifndef CPU_CM3_AT91SAM3U
+ #define UART1_BASE 0x400E0800
+#endif
+/*\}*/
+
+/**
+ * UART register offsets.
+ */
+/*\{*/
+#define UART_CR 0x000 //< Control Register
+#define UART_MR 0x004 //< Mode Register
+#define UART_IER 0x008 //< Interrupt Enable Register
+#define UART_IDR 0x00C //< Interrupt Disable Register
+#define UART_IMR 0x010 //< Interrupt Mask Register
+#define UART_SR 0x014 //< Status Register
+#define UART_RHR 0x018 //< Receive Holding Register
+#define UART_THR 0x01C //< Transmit Holding Register
+#define UART_BRGR 0x020 //< Baud Rate Generator Register
+
+#define UART_RPR 0x100 //< Receive Pointer Register
+#define UART_RCR 0x104 //< Receive Counter Register
+#define UART_TPR 0x108 //< Transmit Pointer Register
+#define UART_TCR 0x10C //< Transmit Counter Register
+#define UART_RNPR 0x110 //< Receive Next Pointer Register
+#define UART_RNCR 0x114 //< Receive Next Counter Register
+#define UART_TNPR 0x118 //< Transmit Next Pointer Register
+#define UART_TNCR 0x11C //< Transmit Next Counter Register
+#define UART_PTCR 0x120 //< Transfer Control Register
+#define UART_PTSR 0x124 //< Transfer Status Register
+/*\}*/
+
+
+/**
+ * Bit fields in the UART_CR register.
+ */
+/*\{*/
+#define UART_CR_RSTRX BV(2) //< Reset Receiver
+#define UART_CR_RSTTX BV(3) //< Reset Transmitter
+#define UART_CR_RXEN BV(4) //< Receiver Enable
+#define UART_CR_RXDIS BV(5) //< Receiver Disable
+#define UART_CR_TXEN BV(6) //< Transmitter Enable
+#define UART_CR_TXDIS BV(7) //< Transmitter Disable
+#define UART_CR_RSTSTA BV(8) //< Reset Status Bits
+/*\}*/
+
+/**
+ * Bit fields in the UART_MR register.
+ */
+/*\{*/
+#define UART_MR_PAR_S 9 //< Parity Type shift
+#define UART_MR_PAR_M (0x7 << UART_MR_PAR_S) //< Parity Type mask
+#define UART_MR_PAR_EVEN (0x0 << UART_MR_PAR_S) //< Even parity
+#define UART_MR_PAR_ODD (0x1 << UART_MR_PAR_S) //< Odd parity
+#define UART_MR_PAR_SPACE (0x2 << UART_MR_PAR_S) //< Space: parity forced to 0
+#define UART_MR_PAR_MARK (0x3 << UART_MR_PAR_S) //< Mark: parity forced to 1
+#define UART_MR_PAR_NO (0x4 << UART_MR_PAR_S) //< No parity
+#define UART_MR_CHMODE_S 14 //< Channel Mode shift
+#define UART_MR_CHMODE_M (0x3 << UART_MR_CHMODE_S) //< Channel Mode mask
+#define UART_MR_CHMODE_NORMAL (0x0 << UART_MR_CHMODE_S) //< Normal Mode
+#define UART_MR_CHMODE_AUTOMATIC (0x1 << UART_MR_CHMODE_S) //< Automatic Echo
+#define UART_MR_CHMODE_LOCAL_LOOPBACK (0x2 << UART_MR_CHMODE_S) //< Local Loopback
+#define UART_MR_CHMODE_REMOTE_LOOPBACK (0x3 << UART_MR_CHMODE_S) //< Remote Loopback
+/*\}*/
+
+/**
+ * Bit fields in the UART_IER register.
+ */
+/*\{*/
+#define UART_IER_RXRDY BV(0) //< Enable RXRDY Interrupt
+#define UART_IER_TXRDY BV(1) //< Enable TXRDY Interrupt
+#define UART_IER_ENDRX BV(3) //< Enable End of Receive Transfer Interrupt
+#define UART_IER_ENDTX BV(4) //< Enable End of Transmit Interrupt
+#define UART_IER_OVRE BV(5) //< Enable Overrun Error Interrupt
+#define UART_IER_FRAME BV(6) //< Enable Framing Error Interrupt
+#define UART_IER_PARE BV(7) //< Enable Parity Error Interrupt
+#define UART_IER_TXEMPTY BV(9) //< Enable TXEMPTY Interrupt
+#define UART_IER_TXBUFE BV(11) //< Enable Buffer Empty Interrupt
+#define UART_IER_RXBUFF BV(12) //< Enable Buffer Full Interrupt
+/*\}*/
+
+/**
+ * Bit fields in the UART_IDR register.
+ */
+/*\{*/
+#define UART_IDR_RXRDY BV(0) //< Disable RXRDY Interrupt
+#define UART_IDR_TXRDY BV(1) //< Disable TXRDY Interrupt
+#define UART_IDR_ENDRX BV(3) //< Disable End of Receive Transfer Interrupt
+#define UART_IDR_ENDTX BV(4) //< Disable End of Transmit Interrupt
+#define UART_IDR_OVRE BV(5) //< Disable Overrun Error Interrupt
+#define UART_IDR_FRAME BV(6) //< Disable Framing Error Interrupt
+#define UART_IDR_PARE BV(7) //< Disable Parity Error Interrupt
+#define UART_IDR_TXEMPTY BV(9) //< Disable TXEMPTY Interrupt
+#define UART_IDR_TXBUFE BV(11) //< Disable Buffer Empty Interrupt
+#define UART_IDR_RXBUFF BV(12) //< Disable Buffer Full Interrupt
+/*\}*/
+
+/**
+ * Bit fields in the UART_IMR register.
+ */
+/*\{*/
+#define UART_IMR_RXRDY BV(0) //< Mask RXRDY Interrupt
+#define UART_IMR_TXRDY BV(1) //< Disable TXRDY Interrupt
+#define UART_IMR_ENDRX BV(3) //< Mask End of Receive Transfer Interrupt
+#define UART_IMR_ENDTX BV(4) //< Mask End of Transmit Interrupt
+#define UART_IMR_OVRE BV(5) //< Mask Overrun Error Interrupt
+#define UART_IMR_FRAME BV(6) //< Mask Framing Error Interrupt
+#define UART_IMR_PARE BV(7) //< Mask Parity Error Interrupt
+#define UART_IMR_TXEMPTY BV(9) //< Mask TXEMPTY Interrupt
+#define UART_IMR_TXBUFE BV(11) //< Mask TXBUFE Interrupt
+#define UART_IMR_RXBUFF BV(12) //< Mask RXBUFF Interrupt
+/*\}*/
+
+/**
+ * Bit fields in the UART_SR register.
+ */
+/*\{*/
+#define UART_SR_RXRDY BV(0) //< Receiver Ready
+#define UART_SR_TXRDY BV(1) //< Transmitter Ready
+#define UART_SR_ENDRX BV(3) //< End of Receiver Transfer
+#define UART_SR_ENDTX BV(4) //< End of Transmitter Transfer
+#define UART_SR_OVRE BV(5) //< Overrun Error
+#define UART_SR_FRAME BV(6) //< Framing Error
+#define UART_SR_PARE BV(7) //< Parity Error
+#define UART_SR_TXEMPTY BV(9) //< Transmitter Empty
+#define UART_SR_TXBUFE BV(11) //< Transmission Buffer Empty
+#define UART_SR_RXBUFF BV(12) //< Receive Buffer Full
+/*\}*/
+
+/**
+ * Bit fields in the UART_RHR register.
+ */
+/*\{*/
+#define UART_RHR_RXCHR_M 0xFF //< Received Character mask
+#define UART_RHR_RXCHR_S 0 //< Received Character shift
+/*\}*/
+
+/**
+ * Bit fields in the UART_THR register.
+ */
+/*\{*/
+#define UART_THR_TXCHR_M 0xFF //< Character to be Transmitted mask
+#define UART_THR_TXCHR_S 0 //< Character to be Transmitted shift
+/*\}*/
+
+/**
+ * Bit fields in the UART_BRGR register.
+ */
+/*\{*/
+#define UART_BRGR_CD_M 0xFFFF //< Clock Divisor mask
+#define UART_BRGR_CD_S 0 //< Clock Divisor shift
+/*\}*/
+
+/**
+ * Bit fields in the UART_RPR register.
+ */
+/*\{*/
+#define UART_RPR_RXPTR_M 0xFFFFFFFF //< Receive Pointer Register mask
+#define UART_RPR_RXPTR_S 0 //< Receive Pointer Register shift
+/*\}*/
+
+/**
+ * Bit fields in the UART_RCR register.
+ */
+/*\{*/
+#define UART_RCR_RXCTR_M 0xFFFF //< Receive Counter Register mask
+#define UART_RCR_RXCTR_S 0 //< Receive Counter Register shift
+/*\}*/
+
+/**
+ * Bit fields in the UART_TPR register.
+ */
+/*\{*/
+#define UART_TPR_TXPTR_M 0xFFFFFFFF //< Transmit Counter Register mask
+#define UART_TPR_TXPTR_S 0 //< Transmit Counter Register shift
+/*\}*/
+
+/**
+ * Bit fields in the UART_TCR register.
+ */
+/*\{*/
+#define UART_TCR_TXCTR_M 0xFFFF //< Transmit Counter Register mask
+#define UART_TCR_TXCTR_S 0 //< Transmit Counter Register shift
+/*\}*/
+
+/**
+ * Bit fields in the UART_RNPR register.
+ */
+/*\{*/
+#define UART_RNPR_RXNPTR_M 0xFFFFFFFF //< Receive Next Pointer mask
+#define UART_RNPR_RXNPTR_S 0 //< Receive Next Pointer shift
+/*\}*/
+
+/**
+ * Bit fields in the UART_RNCR register.
+ */
+/*\{*/
+#define UART_RNCR_RXNCTR_M 0xFFFF //< Receive Next Counter mask
+#define UART_RNCR_RXNCTR_S 0 //< Receive Next Counter shift
+/*\}*/
+
+/**
+ * Bit fields in the UART_TNPR register.
+ */
+/*\{*/
+#define UART_TNPR_TXNPTR_M 0xFFFFFFFF //< Transmit Next Pointer mask
+#define UART_TNPR_TXNPTR_S 0 //< Transmit Next Pointer shift
+/*\}*/
+
+/**
+ * Bit fields in the UART_TNCR register.
+ */
+/*\{*/
+#define UART_TNCR_TXNCTR_M 0xFFFF //< Transmit Counter Next mask
+#define UART_TNCR_TXNCTR_S 0 //< Transmit Counter Next shift
+/*\}*/
+
+/**
+ * Bit fields in the UART_PTCR register.
+ */
+/*\{*/
+#define UART_PTCR_RXTEN BV(0) //< Receiver Transfer Enable
+#define UART_PTCR_RXTDIS BV(1) //< Receiver Transfer Disable
+#define UART_PTCR_TXTEN BV(8) //< Transmitter Transfer Enable
+#define UART_PTCR_TXTDIS BV(9) //< Transmitter Transfer Disable
+/*\}*/
+
+/**
+ * Bit fields in the UART_PTSR register.
+ */
+/*\{*/
+#define UART_PTSR_RXTEN BV(0) //< Receiver Transfer Enable
+#define UART_PTSR_TXTEN BV(8) //< Transmitter Transfer Enable
+/*\}*/
+
+
+#endif /* SAM3_UART_H */
--- /dev/null
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction. Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License. This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2008 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \author Stefano Fedrigo <aleph@develer.com>
+ *
+ * \brief Linker script for AT91SAM3N4 Cortex M3 processor.
+ *
+ */
+
+/*
+ * Memory configuration for AT91SAM3N4.
+ */
+MEMORY
+{
+ rom(rx) : org = 0x0, len = 256k
+ ram(rwx) : org = 0x20000000, len = 24k
+}
+
+INCLUDE "bertos/cpu/cortex-m3/scripts/cortex-m3_ram.ld"
+
#define CPU_CM3_STM32F103RB 0
#endif
+ #if defined (__ARM_AT91SAM3N4__)
+ #define CPU_CM3_AT91SAM3 1
+ #define CPU_CM3_AT91SAM3N 1
+ #define CPU_CM3_AT91SAM3N4 1
+ #else
+ #define CPU_CM3_AT91SAM3N4 0
+ #endif
+
#if defined (CPU_CM3_LM3S)
#if CPU_CM3_LM3S1968 + CPU_CM3_LM3S8962 + 0 != 1
#error Luminary Cortex-M3 CPU configuration error
#endif
#define CPU_CM3_STM32 0
+ #define CPU_CM3_AT91SAM3 0
#elif defined (CPU_CM3_STM32)
#if CPU_CM3_STM32F103RB + 0 != 1
#error STM32 Cortex-M3 CPU configuration error
#endif
#define CPU_CM3_LM3S 0
+ #define CPU_CM3_AT91SAM3 0
+ #elif defined (CPU_CM3_AT91SAM3)
+ #if CPU_CM3_AT91SAM3N + 0 != 1
+ #error AT91SAM3 Cortex-M3 CPU configuration error
+ #endif
+ #if CPU_CM3_AT91SAM3N4 + 0 != 1
+ #error AT91SAM3 Cortex-M3 CPU configuration error
+ #endif
+ #define CPU_CM3_LM3S 0
+ #define CPU_CM3_STM32 0
/* #elif Add other Cortex-M3 families here */
#else
#define CPU_CM3_LM3S 0
#define CPU_CM3_STM32 0
+ #define CPU_CM3_AT91SAM3 0
#endif
- #if CPU_CM3_LM3S + CPU_CM3_STM32 + 0 /* Add other Cortex-M3 families here */ != 1
+ #if CPU_CM3_LM3S + CPU_CM3_STM32 + CPU_CM3_AT91SAM3 + 0 /* Add other Cortex-M3 families here */ != 1
#error Cortex-M3 CPU configuration error
#endif
#else
#define CPU_CM3 0
-
#define CPU_CM3_LM3S 0
-
#define CPU_CM3_LM3S1968 0
-
#define CPU_CM3_LM3S8968 0
#define CPU_CM3_STM32 0
-
#define CPU_CM3_STM32F103RB 0
+
+ #define CPU_CM3_AT91SAM3 0
+ #define CPU_CM3_AT91SAM3N 0
+ #define CPU_CM3_AT91SAM3N4 0
#endif
#if (defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)) \