arch: Add Atmel SAM4S SoC support

Added support for Atmel SAM4S (Cortex-M4) MCU:
- Kconfig files
- Devicetree files

Signed-off-by: Justin Watson <jwatson5@gmail.com>
This commit is contained in:
fallrisk 2017-05-04 10:27:27 -07:00 committed by Anas Nashif
commit 20f41814de
9 changed files with 807 additions and 0 deletions

View file

@ -0,0 +1,30 @@
# Kconfig - Atmel SAM4S MCU series configuration options
#
# Copyright (c) 2017 Justin Watson
#
# SPDX-License-Identifier: Apache-2.0
#
if SOC_SERIES_SAM4S
config SOC_SERIES
string
default sam4s
config SOC_PART_NUMBER
string
default sam4s16c if SOC_PART_NUMBER_SAM4S16C
#
# SAM4S family has total 35 peripherals capable of
# generating interrupts.
#
config NUM_IRQS
int
default 35
config SYS_CLOCK_HW_CYCLES_PER_SEC
int
default 84000000
endif # SOC_SERIES_SAM4S

View file

@ -0,0 +1,17 @@
# Kconfig - Atmel SAM4S MCU series
#
# Copyright (c) 2017 Justin Watson
#
# SPDX-License-Identifier: Apache-2.0
#
config SOC_SERIES_SAM4S
bool "Atmel SAM4S MCU"
select CPU_CORTEX_M
select CPU_CORTEX_M4
select SOC_FAMILY_SAM
select SYS_POWER_LOW_POWER_STATE_SUPPORTED
select CPU_HAS_SYSTICK
help
Enable support for Atmel SAM4S Cortex-M4 microcontrollers.
Part No.: SAM4S16C

View file

@ -0,0 +1,109 @@
# Kconfig - Atmel SAM4S MCU series
#
# Copyright (c) 2017 Justin Watson
#
# SPDX-License-Identifier: Apache-2.0
#
choice
prompt "Atmel SAM4S MCU Selection"
depends on SOC_SERIES_SAM4S
config SOC_PART_NUMBER_SAM4S16C
bool "SAM4S16C"
endchoice
if SOC_SERIES_SAM4S
config SOC_ATMEL_SAM4S_EXT_SLCK
bool "Atmel SAM4S to use external crystal oscillator for slow clock"
default n
help
Says y if you want to use external 32 kHz crystal
oscillator to drive the slow clock. Note that this
adds a few seconds to boot time, as the crystal
needs to stabilize after power-up.
Says n if you do not need accurate and precise timers.
The slow clock will be driven by the internal fast
RC oscillator running at 32 kHz.
config SOC_ATMEL_SAM4S_EXT_MAINCK
bool "Atmel SAM4S to use external crystal oscillator for main clock"
default n
help
The main clock is being used to drive the PLL, and
thus driving the processor clock.
Says y if you want to use external crystal oscillator
to drive the main clock. Note that this adds about
a second to boot time, as the crystal needs to
stabilize after power-up.
The crystal used here can be from 3 to 20 MHz.
Says n here will use the internal fast RC oscillator
running at 12 MHz.
config SOC_ATMEL_SAM4S_PLLA_MULA
hex "PLL MULA"
default 0x06
help
This is the multiplier (MULA) used by the PLL.
The processor clock is (MAINCK * (MULA + 1) / DIVA).
Board config file can override this settings
for a particular board.
With default of MULA == 6, and DIVA == 1,
PLL is running at 7 times of main clock.
config SOC_ATMEL_SAM4S_PLLA_DIVA
hex "PLL DIVA"
default 0x01
help
This is the divider (DIVA) used by the PLL.
The processor clock is (MAINCK * (MULA + 1) / DIVA).
Board config file can override this settings
for a particular board.
With default of MULA == 6, and DIVA == 1,
PLL is running at 7 times of main clock.
config SOC_ATMEL_SAM4S_WAIT_MODE
bool "Atmel SAM4S goes to Wait mode instead of Sleep mode"
depends on SOC_ATMEL_SAM4S_EXT_MAINCK
default y if DEBUG
help
For JTAG debugging CPU clock (HCLK) should not stop. In order
to achieve this, make CPU go to Wait mode instead of Sleep
mode while using external crystal oscillator for main clock.
config SOC_ATMEL_SAM4S_PLLB_MULB
hex "PLL MULB"
default 0x03
help
This is the multiplier (MULA) used by the PLL.
The processor clock is (MAINCK * (MULA + 1) / DIVA).
Board config file can override this settings
for a particular board.
With default of MULA == 6, and DIVA == 1,
PLL is running at 7 times of main clock.
config SOC_ATMEL_SAM4S_PLLB_DIVB
hex "PLL DIVB"
default 0x01
help
This is the divider (DIVB) used by the PLL.
The processor clock is (MAINCK * (MULB + 1) / DIVB).
Board config file can override this settings
for a particular board.
With default of MULB == 6, and DIVB == 1,
PLL is running at 7 times of main clock.
endif # SOC_SERIES_SAM4S

View file

@ -0,0 +1,10 @@
# Makefile - Atmel SAM4S MCU series
#
# Copyright (c) 2017 Justin Watson
#
# SPDX-License-Identifier: Apache-2.0
#
ZEPHYRINCLUDE += -I$(srctree)/arch/arm/soc/atmel_sam/common
obj-y += soc.o

View file

@ -0,0 +1,9 @@
/* linker.ld - Linker command/script file */
/*
* Copyright (c) 2014 Wind River Systems, Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <arch/arm/cortex_m/scripts/linker.ld>

View file

@ -0,0 +1,189 @@
/*
* Copyright (c) 2017 Justin Watson
* Copyright (c) 2016 Intel Corporation.
* Copyright (c) 2013-2015 Wind River Systems, Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief System/hardware module for Atmel SAM4S family processor
*
* This module provides routines to initialize and support board-level hardware
* for the Atmel SAM4S family processor.
*/
#include <kernel.h>
#include <device.h>
#include <init.h>
#include <soc.h>
#include <arch/cpu.h>
#include <cortex_m/exc.h>
/**
* @brief Setup various clock on SoC.
*
* Setup the SoC clocks according to section 28.12 in datasheet.
*
* Assumption:
* SLCK = 32.768kHz
*/
static ALWAYS_INLINE void clock_init(void)
{
u32_t tmp;
#ifdef CONFIG_SOC_ATMEL_SAM4S_EXT_SLCK
/* This part is to switch the slow clock to using
* the external 32 kHz crystal oscillator.
* SUPC is in section 18.5.3 page 340 for the Control Register.
*/
/* Select external crystal */
__SUPC->cr = SUPC_CR_KEY | SUPC_CR_XTALSEL;
/* Wait for oscillator to be stablized */
while (!(__SUPC->sr & SUPC_SR_OSCSEL))
;
#endif /* CONFIG_SOC_ATMEL_SAM4S_EXT_SLCK */
#ifdef CONFIG_SOC_ATMEL_SAM4S_EXT_MAINCK
/* Start the external main oscillator */
__PMC->ckgr_mor = PMC_CKGR_MOR_KEY | PMC_CKGR_MOR_MOSCRCF_4MHZ
| PMC_CKGR_MOR_MOSCRCEN | PMC_CKGR_MOR_MOSCXTEN
| PMC_CKGR_MOR_MOSCXTST;
/* Wait for main oscillator to be stablized */
while (!(__PMC->sr & PMC_INT_MOSCXTS))
;
/* Select main oscillator as source since it is more accurate
* according to datasheet.
*/
__PMC->ckgr_mor = PMC_CKGR_MOR_KEY | PMC_CKGR_MOR_MOSCRCF_4MHZ
| PMC_CKGR_MOR_MOSCRCEN | PMC_CKGR_MOR_MOSCXTEN
| PMC_CKGR_MOR_MOSCXTST | PMC_CKGR_MOR_MOSCSEL;
/* Wait for main oscillator to be selected */
while (!(__PMC->sr & PMC_INT_MOSCSELS))
;
#ifdef CONFIG_SOC_ATMEL_SAM4S_WAIT_MODE
/*
* Instruct CPU enter Wait mode instead of Sleep mode to
* keep Processor Clock (HCLK) and thus be able to debug
* CPU using JTAG
*/
__PMC->fsmr |= PMC_FSMR_LPM;
#endif
#else
/* Set main fast RC oscillator to 12 MHz */
__PMC->ckgr_mor = PMC_CKGR_MOR_KEY | PMC_CKGR_MOR_MOSCRCF_12MHZ
| PMC_CKGR_MOR_MOSCRCEN;
/* Wait for main fast RC oscillator to be stablized */
while (!(__PMC->sr & PMC_INT_MOSCRCS))
;
#endif /* CONFIG_SOC_ATMEL_SAM4S_EXT_MAINCK */
/* Use PLLA as master clock.
* According to datasheet, PMC_MCKR must not be programmed in
* a single write operation. So it seems the safe way is to
* get the system to use main clock (by setting CSS). Then set
* the prescaler (PRES). Finally setting it back to using PLL.
*/
/* Switch to main clock first so we can setup PLL */
tmp = __PMC->mckr & ~PMC_MCKR_CSS_MASK;
__PMC->mckr = tmp | PMC_MCKR_CSS_MAIN;
/* Wait for clock selection complete */
while (!(__PMC->sr & PMC_INT_MCKRDY))
;
/* Setup PLLA */
__PMC->ckgr_pllar = PMC_CKGR_PLLAR_DIVA | PMC_CKGR_PLLAR_ONE
| PMC_CKGR_PLLAR_MULA
| PMC_CKGR_PLLAR_PLLACOUNT;
/* Wait for PLL lock */
while (!(__PMC->sr & PMC_INT_LOCKA))
;
/* Setup PLLB */
__PMC->ckgr_pllbr = PMC_CKGR_PLLBR_DIVB
| PMC_CKGR_PLLBR_MULB
| PMC_CKGR_PLLBR_PLLBCOUNT;
/* Wait for PLL lock */
while (!(__PMC->sr & PMC_INT_LOCKB))
;
/* Setup prescaler */
tmp = __PMC->mckr & ~PMC_MCKR_PRES_MASK;
__PMC->mckr = tmp | PMC_MCKR_PRES_CLK;
/* Wait for main clock setup complete */
while (!(__PMC->sr & PMC_INT_MCKRDY))
;
/* Finally select PLL as clock source */
tmp = __PMC->mckr & ~PMC_MCKR_CSS_MASK;
__PMC->mckr = tmp | PMC_MCKR_CSS_PLLA;
/* Wait for main clock setup complete */
while (!(__PMC->sr & PMC_INT_MCKRDY))
;
}
/**
* @brief Perform basic hardware initialization at boot.
*
* This needs to be run from the very beginning.
* So the init priority has to be 0 (zero).
*
* @return 0
*/
static int atmel_sam4s_init(struct device *arg)
{
u32_t key;
ARG_UNUSED(arg);
/* Note:
* Magic numbers below are obtained by reading the registers
* when the SoC was running the SAM4S-BA bootloader
* (with reserved bits set to 0).
*/
key = irq_lock();
/* Setup the flash controller.
* The bootloader is running @ 48 MHz with
* FWS == 2.
* When running at 84 MHz, FWS == 4 seems
* to be more stable, and allows the board
* to boot.
*/
__EEFC0->fmr = (4 << EEFC_FMR_FWS_POS);
__EEFC1->fmr = (4 << EEFC_FMR_FWS_POS);
_ClearFaults();
/* Setup master clock */
clock_init();
/* Disable watchdog timer, not used by system */
__WDT->mr |= WDT_DISABLE;
/* Install default handler that simply resets the CPU
* if configured in the kernel, NOP otherwise
*/
NMI_INIT();
irq_unlock(key);
return 0;
}
SYS_INIT(atmel_sam4s_init, PRE_KERNEL_1, 0);

View file

@ -0,0 +1,219 @@
/*
* Copyright (c) 2017 Justin Watson
* Copyright (c) 2016 Intel Corporation.
* Copyright (c) 2013-2015 Wind River Systems, Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file SoC configuration macros for the Atmel SAM4S family processors.
*/
#ifndef _ATMEL_SAM4S_SOC_H_
#define _ATMEL_SAM4S_SOC_H_
/* IRQ numbers (from section 11.1, Peripheral Identifiers). */
#define IRQ_SUPC 0 /* Supply Controller */
#define IRQ_RSTC 1 /* Reset Controller */
#define IRQ_RTC 2 /* Real-time Clock */
#define IRQ_RTT 3 /* Real-time Timer */
#define IRQ_WDG 4 /* Watchdog Timer */
#define IRQ_PMC 5 /* Power Management Controller */
#define IRQ_EEFC0 6 /* Enhanced Embedded Flash Controller 0 */
#define IRQ_EEFC1 7 /* Enhanced Embedded Flash Controller 1 */
#define IRQ_UART0 8 /* UART */
#define IRQ_UART1 9 /* UART */
#define IRQ_SMC 10 /* */
#define IRQ_PIOA 11 /* Parallel IO Controller A */
#define IRQ_PIOB 12 /* Parallel IO Controller B */
#define IRQ_PIOC 13 /* Parallel IO Controller C */
#define IRQ_USART0 14 /* USART #0 */
#define IRQ_USART1 15 /* USART #1 */
#define IRQ_HSMCI 18 /* High Speed Multimedia Card Interface */
#define IRQ_TWI0 19 /* Two-wire Interface #0 */
#define IRQ_TWI1 20 /* Two-wire Interface #1 */
#define IRQ_SPI 21 /* SPI */
#define IRQ_SSC 22 /* Synchronous Serial Controller */
#define IRQ_TC0 23 /* Timer Counter Channel #0 */
#define IRQ_TC1 24 /* Timer Counter Channel #1 */
#define IRQ_TC2 25 /* Timer Counter Channel #2 */
#define IRQ_TC3 26 /* Timer Counter Channel #3 */
#define IRQ_TC4 27 /* Timer Counter Channel #4 */
#define IRQ_TC5 28 /* Timer Counter Channel #5 */
#define IRQ_ADC 29 /* ADC Controller */
#define IRQ_DACC 30 /* DAC Controller */
#define IRQ_PWM 31 /* PWM Controller */
#define IRQ_CRCCU 32 /* CRC Controller */
#define IRQ_ACC 33 /* */
#define IRQ_UDP 34 /* USB Device Port */
/* PID: Peripheral IDs (from section 11.1, Peripheral Identifiers).
* PMC uses PIDs to enable clock for peripherals.
*/
#define PID_UART0 8 /* UART */
#define PID_UART1 9 /* UART */
#define PID_SMC 10 /* */
#define PID_PIOA 11 /* Parallel IO Controller A */
#define PID_PIOB 12 /* Parallel IO Controller B */
#define PID_PIOC 13 /* Parallel IO Controller C */
#define PID_USART0 14 /* USART #0 */
#define PID_USART1 15 /* USART #1 */
#define PID_HSMCI 18 /* High Speed Multimedia Card Interface */
#define PID_TWI0 19 /* Two-wire Interface #0 */
#define PID_TWI1 20 /* Two-wire Interface #1 */
#define PID_SPI 21 /* SPI */
#define PID_SSC 22 /* Synchronous Serial Controller */
#define PID_TC0 23 /* Timer Counter Channel #0 */
#define PID_TC1 24 /* Timer Counter Channel #1 */
#define PID_TC2 25 /* Timer Counter Channel #2 */
#define PID_TC3 26 /* Timer Counter Channel #3 */
#define PID_TC4 27 /* Timer Counter Channel #4 */
#define PID_TC5 28 /* Timer Counter Channel #5 */
#define PID_ADC 29 /* ADC Controller */
#define PID_DACC 30 /* DAC Controller */
#define PID_PWM 31 /* PWM Controller */
#define PID_CRCCU 32 /* */
#define PID_ACC 33 /* USB OTG High Speed */
#define PID_UDP 34 /* USB Device Port */
/* Power Manager Controller */
#define PMC_ADDR 0x400E0400
#define PMC_CKGR_UCKR_UPLLEN (1 << 16)
#define PMC_CKGR_UCKR_UPLLCOUNT (3 << 20)
#define PMC_CKGR_MOR_KEY (0x37 << 16)
#define PMC_CKGR_MOR_MOSCXTST (0xFF << 8)
#define PMC_CKGR_MOR_MOSCXTEN (1 << 0)
#define PMC_CKGR_MOR_MOSCRCEN (1 << 3)
#define PMC_CKGR_MOR_MOSCRCF_4MHZ (0 << 4)
#define PMC_CKGR_MOR_MOSCRCF_8MHZ (1 << 4)
#define PMC_CKGR_MOR_MOSCRCF_12MHZ (2 << 4)
#define PMC_CKGR_MOR_MOSCSEL (1 << 24)
#define PMC_CKGR_PLLAR_PLLACOUNT (0x3F << 8)
#define PMC_CKGR_PLLAR_ONE (1 << 29)
#define PMC_CKGR_PLLBR_PLLBCOUNT (0x3F << 8)
/*
* PLL clock = Main * (MULA + 1) / DIVA
*
* By default, MULA == 6, DIVA == 1.
* With main crystal running at 12 MHz,
* PLL = 12 * (6 + 1) / 1 = 84 MHz
*
* With processor clock prescaler at 1,
* the processor clock is at 84 MHz.
*/
#define PMC_CKGR_PLLAR_MULA \
((CONFIG_SOC_ATMEL_SAM4S_PLLA_MULA) << 16)
#define PMC_CKGR_PLLAR_DIVA \
((CONFIG_SOC_ATMEL_SAM4S_PLLA_DIVA) << 0)
/*
* PLL clock = Main * (MULB + 1) / DIVB
*
* By default, MULB == 6, DIVB == 1.
* With main crystal running at 12 MHz,
* PLL = 12 * (6 + 1) / 1 = 84 MHz
*
* With processor clock prescaler at 1,
* the processor clock is at 84 MHz.
*/
#define PMC_CKGR_PLLBR_MULB \
((CONFIG_SOC_ATMEL_SAM4S_PLLB_MULB) << 16)
#define PMC_CKGR_PLLBR_DIVB \
((CONFIG_SOC_ATMEL_SAM4S_PLLB_DIVB) << 0)
#define PMC_MCKR_CSS_MASK (0x3)
#define PMC_MCKR_CSS_SLOW (0 << 0)
#define PMC_MCKR_CSS_MAIN (1 << 0)
#define PMC_MCKR_CSS_PLLA (2 << 0)
#define PMC_MCKR_CSS_UPLL (3 << 0)
#define PMC_MCKR_PRES_MASK (0x70)
#define PMC_MCKR_PRES_CLK (0 << 4)
#define PMC_MCKR_PRES_DIV2 (1 << 4)
#define PMC_MCKR_PRES_DIV4 (2 << 4)
#define PMC_MCKR_PRES_DIV8 (3 << 4)
#define PMC_MCKR_PRES_DIV16 (4 << 4)
#define PMC_MCKR_PRES_DIV32 (5 << 4)
#define PMC_MCKR_PRES_DIV64 (6 << 4)
#define PMC_MCKR_PRES_DIV3 (7 << 4)
#define PMC_MCKR_PLLADIV2 (1 << 12)
#define PMC_MCKR_UPLLDIV2 (1 << 13)
#define PMC_FSMR_LPM (1 << 20)
#define PMC_INT_MOSCXTS (1 << 0)
#define PMC_INT_LOCKA (1 << 1)
#define PMC_INT_LOCKB (2 << 1)
#define PMC_INT_MCKRDY (1 << 3)
#define PMC_INT_LOCKU (1 << 6)
#define PMC_INT_OSCSELS (1 << 7)
#define PMC_INT_PCKRDY0 (1 << 8)
#define PMC_INT_PCKRDY1 (1 << 9)
#define PMC_INT_PCKRDY2 (1 << 10)
#define PMC_INT_MOSCSELS (1 << 16)
#define PMC_INT_MOSCRCS (1 << 17)
#define PMC_INT_CFDEV (1 << 18)
#define PMC_INT_CFDS (1 << 19)
#define PMC_INT_FOS (1 << 20)
/* EEFC */
#define EEFC_BANK0_ADDR 0x400E0A00
#define EEFC_BANK1_ADDR 0x400E0C00
#define EEFC_FMR_CLOR (1 << 26)
#define EEFC_FMR_FAME (1 << 24)
#define EEFC_FMR_SCOR (1 << 16)
#define EEFC_FMR_FWS_POS (8)
#define EEFC_FMR_FRDY (1 << 0)
/* PIO Controllers */
#define PIOA_ADDR 0x400E0E00
#define PIOB_ADDR 0x400E1000
#define PIOC_ADDR 0x400E1200
/* Supply Controller (SUPC) */
#define SUPC_ADDR 0x400E1410
#define SUPC_CR_KEY (0xA5 << 24)
#define SUPC_CR_XTALSEL (1 << 3)
#define SUPC_SR_OSCSEL (1 << 7)
/* Watchdog timer (WDT) */
#define WDT_ADDR 0x400E1450
#define WDT_DISABLE (1 << 15)
#ifndef _ASMLANGUAGE
#include <device.h>
#include <misc/util.h>
#include <drivers/rand32.h>
#include "soc_registers.h"
/* EEFC Register struct */
#define __EEFC0 ((volatile struct __eefc *)EEFC_BANK0_ADDR)
#define __EEFC1 ((volatile struct __eefc *)EEFC_BANK1_ADDR)
/* PMC Register struct */
#define __PMC ((volatile struct __pmc *)PMC_ADDR)
/* PIO Registers struct */
#define __PIOA ((volatile struct __pio *)PIOA_ADDR)
#define __PIOB ((volatile struct __pio *)PIOB_ADDR)
#define __PIOC ((volatile struct __pio *)PIOC_ADDR)
/* Supply Controller Register struct */
#define __SUPC ((volatile struct __supc *)SUPC_ADDR)
/* Watchdog timer (WDT) */
#define __WDT ((volatile struct __wdt *)WDT_ADDR)
#endif /* !_ASMLANGUAGE */
#endif /* _ATMEL_SAM4S_SOC_H_ */

View file

@ -0,0 +1,195 @@
/*
* Copyright (c) 2017 Justin Watson
* Copyright (c) 2016 Intel Corporation.
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file SoC configuration macros for the Atmel SAM4S family processors.
*
* Refer to the datasheet for more information about these registers.
*/
#ifndef _ATMEL_SAM4S_SOC_REGS_H_
#define _ATMEL_SAM4S_SOC_REGS_H_
/* Enhanced Embedded Flash Controller */
struct __eefc {
u32_t fmr; /* 0x00 Flash Mode Register */
u32_t fcr; /* 0x04 Flash Command Register */
u32_t fsr; /* 0x08 Flash Status Register */
u32_t frr; /* 0x0C Flash Result Register */
};
/* PIO Controller */
struct __pio {
u32_t per; /* 0x00 Enable */
u32_t pdr; /* 0x04 Disable */
u32_t psr; /* 0x08 Status */
u32_t res0; /* 0x0C reserved */
u32_t oer; /* 0x10 Output Enable */
u32_t odr; /* 0x14 Output Disable */
u32_t osr; /* 0x18 Output Status */
u32_t res1; /* 0x1C reserved */
u32_t ifer; /* 0x20 Glitch Input Filter Enable */
u32_t ifdr; /* 0x24 Glitch Input Filter Disable */
u32_t ifsr; /* 0x28 Glitch Input Fitler Status */
u32_t res2; /* 0x2C reserved */
u32_t sodr; /* 0x30 Set Output Data */
u32_t codr; /* 0x34 Clear Output Data */
u32_t odsr; /* 0x38 Output Data Status */
u32_t pdsr; /* 0x3C Pin Data Status */
u32_t ier; /* 0x40 Interrupt Enable */
u32_t idr; /* 0x44 Interrupt Disable */
u32_t imr; /* 0x48 Interrupt Mask */
u32_t isr; /* 0x4C Interrupt Status */
u32_t mder; /* 0x50 Multi-driver Enable */
u32_t mddr; /* 0x54 Multi-driver Disable */
u32_t mdsr; /* 0x58 Multi-driver Status */
u32_t res3; /* 0x5C reserved */
u32_t pudr; /* 0x60 Pull-up Disable */
u32_t puer; /* 0x64 Pull-up Enable */
u32_t pusr; /* 0x68 Pad Pull-up Status */
u32_t res4; /* 0x6C reserved */
u32_t abcdsr1; /* 0x70 Peripheral ABCD Select 1 */
u32_t abcdsr2; /* 0x74 Peripheral ABCD Select 2 */
u32_t res5[2]; /* 0x78-0x7C reserved */
u32_t scifsr; /* 0x80 System Clock Glitch Input */
/* Filter Select */
u32_t difsr; /* 0x84 Debouncing Input Filter */
/* Select */
u32_t ifdgsr; /* 0x88 Glitch or Debouncing Input */
/* Filter Clock Selection */
/* Status */
u32_t scdr; /* 0x8C Slow Clock Divider Debounce */
u32_t res6[4]; /* 0x90-0x9C reserved */
u32_t ower; /* 0xA0 Output Write Enable */
u32_t owdr; /* 0xA4 Output Write Disable */
u32_t owsr; /* 0xA8 Output Write Status */
u32_t res7; /* 0xAC reserved */
u32_t aimer; /* 0xB0 Additional Interrupt Modes */
/* Enable */
u32_t aimdr; /* 0xB4 Additional Interrupt Modes */
/* Disable */
u32_t aimmr; /* 0xB8 Additional Interrupt Modes */
/* Mask */
u32_t res8; /* 0xBC reserved */
u32_t esr; /* 0xC0 Edge Select */
u32_t lsr; /* 0xC4 Level Select */
u32_t elsr; /* 0xC8 Edge/Level Status */
u32_t res9; /* 0xCC reserved */
u32_t fellsr; /* 0xD0 Falling Edge/Low Level Sel */
u32_t rehlsr; /* 0xD4 Rising Edge/High Level Sel */
u32_t frlhsr; /* 0xD8 Fall/Rise - Low/High Status */
u32_t res10; /* 0xDC reserved */
u32_t locksr; /* 0xE0 Lock Status */
u32_t wpmr; /* 0xE4 Write Protect Mode */
u32_t wpsr; /* 0xE8 Write Protect Status */
};
/* Power Management Controller */
struct __pmc {
u32_t scer; /* 0x00 System Clock Enable */
u32_t scdr; /* 0x04 System Clock Disable */
u32_t scsr; /* 0x08 System Clock Status */
u32_t res0; /* 0x0C reserved */
u32_t pcer0; /* 0x10 Peripheral Clock Enable 0 */
u32_t pcdr0; /* 0x14 Peripheral Clock Disable 0 */
u32_t pcsr0; /* 0x18 Peripheral Clock Status 0 */
u32_t ckgr_uckr; /* 0x1C UTMI Clock */
u32_t ckgr_mor; /* 0x20 Main Oscillator */
u32_t ckgr_mcfr; /* 0x24 Main Clock Freq. */
u32_t ckgr_pllar; /* 0x28 PLLA */
u32_t ckgr_pllbr; /* 0x2C PLLB */
u32_t mckr; /* 0x30 Master Clock */
u32_t res2; /* 0x34 reserved */
u32_t usb; /* 0x38 USB Clock */
u32_t res3; /* 0x3C reserved */
u32_t pck0; /* 0x40 Programmable Clock 0 */
u32_t pck1; /* 0x44 Programmable Clock 1 */
u32_t pck2; /* 0x48 Programmable Clock 2 */
u32_t res4[5]; /* 0x4C-0x5C reserved */
u32_t ier; /* 0x60 Interrupt Enable */
u32_t idr; /* 0x64 Interrupt Disable */
u32_t sr; /* 0x68 Status */
u32_t imr; /* 0x6C Interrupt Mask */
u32_t fsmr; /* 0x70 Fast Startup Mode */
u32_t fspr; /* 0x74 Fast Startup Polarity */
u32_t focr; /* 0x78 Fault Outpu Clear */
u32_t res5[26]; /* 0x7C-0xE0 reserved */
u32_t wpmr; /* 0xE4 Write Protect Mode */
u32_t wpsr; /* 0xE8 Write Protect Status */
u32_t res6[5]; /* 0xEC-0xFC reserved */
u32_t pcer1; /* 0x100 Peripheral Clock Enable 1 */
u32_t pcdr1; /* 0x104 Peripheral Clock Disable 1 */
u32_t pcsr1; /* 0x108 Peripheral Clock Status 1 */
u32_t pcr; /* 0x10C Peripheral Control */
};
/*
* Supply Controller (SUPC)
* Table 18-2 Section 18.5.2 Page 339
*/
struct __supc {
u32_t cr; /* 0x00 Control */
u32_t smmr; /* 0x04 Supply Monitor Mode */
u32_t mr; /* 0x08 Mode */
u32_t wumr; /* 0x0C Wake Up Mode */
u32_t wuir; /* 0x10 Wake Up Inputs */
u32_t sr; /* 0x14 Status */
};
/* Watchdog timer (WDT) */
struct __wdt {
u32_t cr; /* 0x00 Control Register */
u32_t mr; /* 0x04 Mode Register */
u32_t sr; /* 0x08 Status Register */
};
#endif /* _ATMEL_SAM4S_SOC_REGS_H_ */

29
dts/arm/atmel/sam4s.dtsi Normal file
View file

@ -0,0 +1,29 @@
/*
* Copyright (c) 2017 Justin Watson
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <arm/armv7-m.dtsi>
/ {
cpus {
cpu@0 {
compatible = "arm,cortex-m4";
};
};
sram0: memory {
compatible = "sram";
reg = <0x20100000 0x20000>;
};
flash0: flash {
compatible = "flash";
reg = <0x00400000 0x100000>;
};
};
&nvic {
arm,num-irq-priority-bits = <3>;
};