soc: arm: atmel: Introduce sam4l SoC

Introduce SAM4L SoC initial files.

Signed-off-by: Gerson Fernando Budke <nandojve@gmail.com>
This commit is contained in:
Gerson Fernando Budke 2020-02-18 20:05:31 -03:00 committed by Maureen Helm
parent 18e608ee55
commit ab31a2e543
13 changed files with 1061 additions and 22 deletions

View file

@ -30,8 +30,10 @@
/soc/nios2/ @nashif @wentongwu
/soc/arm/ @MaureenHelm @galak @ioannisg
/soc/arm/arm/mps2/ @fvincenzo
/soc/arm/atmel_sam/common/*_sam4l_*.c @nandojve
/soc/arm/atmel_sam/sam3x/ @ioannisg
/soc/arm/atmel_sam/sam4e/ @nandojve
/soc/arm/atmel_sam/sam4l/ @nandojve
/soc/arm/atmel_sam/sam4s/ @fallrisk
/soc/arm/atmel_sam/same70/ @nandojve
/soc/arm/atmel_sam/samv71/ @nandojve

View file

@ -1,7 +1,8 @@
# SPDX-License-Identifier: Apache-2.0
zephyr_include_directories(.)
zephyr_sources(
soc_pmc.c
soc_gpio.c
)
zephyr_library_sources_ifndef(CONFIG_SOC_SERIES_SAM4L soc_pmc.c)
zephyr_library_sources_ifndef(CONFIG_SOC_SERIES_SAM4L soc_gpio.c)
zephyr_library_sources_ifdef(CONFIG_SOC_SERIES_SAM4L soc_sam4l_pm.c)
zephyr_library_sources_ifdef(CONFIG_SOC_SERIES_SAM4L soc_sam4l_gpio.c)

View file

@ -46,16 +46,32 @@
ATMEL_SAM_PIN_FLAG(inst, i, bias_pull_down) << SOC_GPIO_PULLUP_POS | \
ATMEL_SAM_PIN_FLAG(inst, i, drive_open_drain) << SOC_GPIO_OPENDRAIN_POS)
/* Construct a soc_gpio_pin element for pin cfg */
#define ATMEL_SAM_DT_PIN(inst, idx) \
/* Construct a soc_pio_pin element for pin cfg */
#define ATMEL_SAM_DT_PIO(inst, idx) \
{ \
1 << ATMEL_SAM_PIN(inst, idx), \
(Pio *)ATMEL_SAM_PIN_TO_PIO_REG_ADDR(inst, idx), \
ATMEL_SAM_PIN_2_PIO_PERIPH_ID(inst, idx), \
ATMEL_SAM_PIN_PERIPH(inst, idx) << 16 | \
ATMEL_SAM_PIN_PERIPH(inst, idx) << SOC_GPIO_FUNC_POS | \
ATMEL_SAM_PIN_FLAGS(inst, idx) \
}
/* Construct a soc_gpio_pin element for pin cfg */
#define ATMEL_SAM_DT_GPIO(inst, idx) \
{ \
1 << ATMEL_SAM_PIN(inst, idx), \
(Gpio *)ATMEL_SAM_PIN_TO_PIO_REG_ADDR(inst, idx), \
ATMEL_SAM_PIN_2_PIO_PERIPH_ID(inst, idx), \
ATMEL_SAM_PIN_PERIPH(inst, idx) << SOC_GPIO_FUNC_POS | \
ATMEL_SAM_PIN_FLAGS(inst, idx) \
}
#if defined(CONFIG_SOC_SERIES_SAM4L)
#define ATMEL_SAM_DT_PIN ATMEL_SAM_DT_GPIO
#else
#define ATMEL_SAM_DT_PIN ATMEL_SAM_DT_PIO
#endif
/* Get the number of pins for pinctrl-0 */
#define ATMEL_SAM_DT_NUM_PINS(inst) DT_INST_PROP_LEN(inst, pinctrl_0)

View file

@ -1,5 +1,6 @@
/*
* Copyright (c) 2016-2017 Piotr Mienkowski
* Copyright (c) 2020 Gerson Fernando Budke <nandojve@gmail.com>
* SPDX-License-Identifier: Apache-2.0
*/
@ -24,6 +25,8 @@
#define SOC_GPIO_DEFAULT (0)
#define SOC_GPIO_FLAGS_POS (0)
#define SOC_GPIO_FLAGS_MASK (7 << SOC_GPIO_FLAGS_POS)
#define SOC_GPIO_PULLUP_POS (0)
#define SOC_GPIO_PULLUP (1 << SOC_GPIO_PULLUP_POS)
#define SOC_GPIO_PULLDOWN_POS (1)
@ -32,7 +35,7 @@
#define SOC_GPIO_OPENDRAIN (1 << SOC_GPIO_OPENDRAIN_POS)
/* Bit field: SOC_GPIO_IN_FILTER */
#define SOC_GPIO_IN_FILTER_POS 3
#define SOC_GPIO_IN_FILTER_POS (3)
#define SOC_GPIO_IN_FILTER_MASK (3 << SOC_GPIO_IN_FILTER_POS)
#define SOC_GPIO_IN_FILTER_NONE (0 << SOC_GPIO_IN_FILTER_POS)
#define SOC_GPIO_IN_FILTER_DEBOUNCE (1 << SOC_GPIO_IN_FILTER_POS)
@ -41,7 +44,7 @@
#define SOC_GPIO_INT_ENABLE (1 << 5)
/* Bit field: SOC_GPIO_INT_TRIG */
#define SOC_GPIO_INT_TRIG_POS 6
#define SOC_GPIO_INT_TRIG_POS (6)
#define SOC_GPIO_INT_TRIG_MASK (3 << SOC_GPIO_INT_TRIG_POS)
/** Interrupt is triggered by a level detection event. */
#define SOC_GPIO_INT_TRIG_LEVEL (0 << SOC_GPIO_INT_TRIG_POS)
@ -54,8 +57,8 @@
#define SOC_GPIO_INT_ACTIVE_HIGH (1 << 8)
/* Bit field: SOC_GPIO_FUNC */
#define SOC_GPIO_FUNC_POS 16
#define SOC_GPIO_FUNC_MASK (7 << SOC_GPIO_FUNC_POS)
#define SOC_GPIO_FUNC_POS (16)
#define SOC_GPIO_FUNC_MASK (15 << SOC_GPIO_FUNC_POS)
/** Connect pin to peripheral A. */
#define SOC_GPIO_FUNC_A (0 << SOC_GPIO_FUNC_POS)
/** Connect pin to peripheral B. */
@ -64,16 +67,28 @@
#define SOC_GPIO_FUNC_C (2 << SOC_GPIO_FUNC_POS)
/** Connect pin to peripheral D. */
#define SOC_GPIO_FUNC_D (3 << SOC_GPIO_FUNC_POS)
/** Connect pin to peripheral E. */
#define SOC_GPIO_FUNC_E (4 << SOC_GPIO_FUNC_POS)
/** Connect pin to peripheral F. */
#define SOC_GPIO_FUNC_F (5 << SOC_GPIO_FUNC_POS)
/** Connect pin to peripheral G. */
#define SOC_GPIO_FUNC_G (6 << SOC_GPIO_FUNC_POS)
/** Connect pin to peripheral H. */
#define SOC_GPIO_FUNC_H (7 << SOC_GPIO_FUNC_POS)
/** Configure pin as input. */
#define SOC_GPIO_FUNC_IN (4 << SOC_GPIO_FUNC_POS)
#define SOC_GPIO_FUNC_IN (8 << SOC_GPIO_FUNC_POS)
/** Configure pin as output and set it initial value to 0. */
#define SOC_GPIO_FUNC_OUT_0 (5 << SOC_GPIO_FUNC_POS)
#define SOC_GPIO_FUNC_OUT_0 (9 << SOC_GPIO_FUNC_POS)
/** Configure pin as output and set it initial value to 1. */
#define SOC_GPIO_FUNC_OUT_1 (6 << SOC_GPIO_FUNC_POS)
#define SOC_GPIO_FUNC_OUT_1 (10 << SOC_GPIO_FUNC_POS)
struct soc_gpio_pin {
uint32_t mask; /** pin(s) bit mask */
#ifdef ID_GPIO
Gpio *regs; /** pointer to registers of the GPIO controller */
#else
Pio *regs; /** pointer to registers of the PIO controller */
#endif
uint8_t periph_id; /** peripheral ID of the PIO controller */
uint32_t flags; /** pin flags/attributes */
};
@ -124,7 +139,11 @@ void soc_gpio_list_configure(const struct soc_gpio_pin pins[],
*/
static inline void soc_gpio_set(const struct soc_gpio_pin *pin)
{
#ifdef ID_GPIO
pin->regs->OVRS = pin->mask;
#else
pin->regs->PIO_SODR = pin->mask;
#endif
}
/**
@ -138,7 +157,11 @@ static inline void soc_gpio_set(const struct soc_gpio_pin *pin)
*/
static inline void soc_gpio_clear(const struct soc_gpio_pin *pin)
{
#ifdef ID_GPIO
pin->regs->OVRC = pin->mask;
#else
pin->regs->PIO_CODR = pin->mask;
#endif
}
/**
@ -152,7 +175,11 @@ static inline void soc_gpio_clear(const struct soc_gpio_pin *pin)
*/
static inline uint32_t soc_gpio_get(const struct soc_gpio_pin *pin)
{
#ifdef ID_GPIO
return pin->regs->PVR & pin->mask;
#else
return pin->regs->PIO_PDSR & pin->mask;
#endif
}
/**
@ -177,7 +204,15 @@ static inline uint32_t soc_gpio_get(const struct soc_gpio_pin *pin)
static inline void soc_gpio_debounce_length_set(const struct soc_gpio_pin *pin,
uint32_t div)
{
#ifdef ID_GPIO
if (div) {
pin->regs->STERS = pin->mask;
} else {
pin->regs->STERC = pin->mask;
}
#else
pin->regs->PIO_SCDR = PIO_SCDR_DIV(div);
#endif
}
#endif /* _ATMEL_SAM_SOC_GPIO_H_ */

View file

@ -0,0 +1,189 @@
/*
* Copyright (c) 2020 Gerson Fernando Budke <nandojve@gmail.com>
* SPDX-License-Identifier: Apache-2.0
*/
/** @file
* @brief Atmel SAM MCU family General-Purpose Input/Output Controller (GPIO)
* module HAL driver.
*/
#include <sys/__assert.h>
#include "soc_gpio.h"
static void configure_common_attr(volatile Gpio *gpio,
uint32_t mask, uint32_t flags)
{
flags &= SOC_GPIO_FLAGS_MASK;
/* Disable interrupts on the pin(s) */
gpio->IERC = mask;
/* Configure pull-up(s) */
if (flags & SOC_GPIO_PULLUP) {
gpio->PUERS = mask;
} else {
gpio->PUERC = mask;
}
/* Configure pull-down(s) */
if (flags & SOC_GPIO_PULLDOWN) {
gpio->PDERS = mask;
} else {
gpio->PDERC = mask;
}
/* Configure open drain (multi-drive) */
if (flags & SOC_GPIO_OPENDRAIN) {
gpio->ODMERS = mask;
} else {
gpio->ODMERC = mask;
}
}
static void configure_input_attr(volatile Gpio *gpio,
uint32_t mask, uint32_t flags)
{
/* Configure input filter */
if ((flags & SOC_GPIO_IN_FILTER_MASK) != 0U) {
if ((flags & SOC_GPIO_IN_FILTER_MASK) ==
SOC_GPIO_IN_FILTER_DEBOUNCE) {
/* Enable de-bounce, disable de-glitch */
gpio->GFERC = mask;
} else {
/* Disable de-bounce, enable de-glitch */
gpio->GFERS = mask;
}
} else {
gpio->GFERC = mask;
}
/* Configure interrupt */
if (flags & SOC_GPIO_INT_ENABLE) {
if ((flags & SOC_GPIO_INT_TRIG_MASK) ==
SOC_GPIO_INT_TRIG_DOUBLE_EDGE) {
gpio->IMR0C = mask;
gpio->IMR1C = mask;
} else {
if (flags & SOC_GPIO_INT_ACTIVE_HIGH) {
/* Rising Edge*/
gpio->IMR0S = mask;
gpio->IMR1C = mask;
} else {
/* Falling Edge */
gpio->IMR0C = mask;
gpio->IMR1S = mask;
}
}
/* Enable interrupts on the pin(s) */
gpio->IERS = mask;
} else {
gpio->IERC = mask;
}
}
void soc_gpio_configure(const struct soc_gpio_pin *pin)
{
uint32_t mask = pin->mask;
volatile Gpio *gpio = pin->regs;
uint8_t periph_id = pin->periph_id;
uint32_t flags = pin->flags;
uint32_t type = pin->flags & SOC_GPIO_FUNC_MASK;
/* Configure pin attributes common to all functions */
configure_common_attr(gpio, mask, flags);
switch (type) {
case SOC_GPIO_FUNC_A:
gpio->PMR0C = mask;
gpio->PMR1C = mask;
gpio->PMR2C = mask;
gpio->GPERC = mask;
break;
case SOC_GPIO_FUNC_B:
gpio->PMR0S = mask;
gpio->PMR1C = mask;
gpio->PMR2C = mask;
gpio->GPERC = mask;
break;
case SOC_GPIO_FUNC_C:
gpio->PMR0C = mask;
gpio->PMR1S = mask;
gpio->PMR2C = mask;
gpio->GPERC = mask;
break;
case SOC_GPIO_FUNC_D:
gpio->PMR0S = mask;
gpio->PMR1S = mask;
gpio->PMR2C = mask;
gpio->GPERC = mask;
break;
case SOC_GPIO_FUNC_E:
gpio->PMR0C = mask;
gpio->PMR1C = mask;
gpio->PMR2S = mask;
gpio->GPERC = mask;
break;
case SOC_GPIO_FUNC_F:
gpio->PMR0S = mask;
gpio->PMR1C = mask;
gpio->PMR2S = mask;
gpio->GPERC = mask;
break;
case SOC_GPIO_FUNC_G:
gpio->PMR0C = mask;
gpio->PMR1S = mask;
gpio->PMR2S = mask;
gpio->GPERC = mask;
break;
case SOC_GPIO_FUNC_H:
gpio->PMR0S = mask;
gpio->PMR1S = mask;
gpio->PMR2S = mask;
gpio->GPERC = mask;
break;
case SOC_GPIO_FUNC_IN:
soc_pmc_peripheral_enable(periph_id);
configure_input_attr(gpio, mask, flags);
gpio->ODERC = mask;
gpio->STERS = mask;
gpio->GPERS = mask;
break;
case SOC_GPIO_FUNC_OUT_1:
case SOC_GPIO_FUNC_OUT_0:
if (type == SOC_GPIO_FUNC_OUT_1) {
gpio->OVRS = mask;
} else {
gpio->OVRC = mask;
}
gpio->ODCR0S = mask;
gpio->ODCR1S = mask;
gpio->ODERS = mask;
gpio->STERC = mask;
gpio->GPERS = mask;
break;
default:
__ASSERT(0, "Unsupported pin function, check pin.flags value");
return;
}
}
void soc_gpio_list_configure(const struct soc_gpio_pin pins[],
unsigned int size)
{
for (int i = 0; i < size; i++) {
soc_gpio_configure(&pins[i]);
}
}

View file

@ -0,0 +1,122 @@
/*
* Copyright (c) 2020 Gerson Fernando Budke <nandojve@gmail.com>
* SPDX-License-Identifier: Apache-2.0
*/
/** @file
* @brief Atmel SAM4L MCU family Power Management (PM) module
* HAL driver.
*/
#include <soc.h>
#include <sys/__assert.h>
#include <sys/util.h>
/**
* SAM4L define peripheral-ids out of order. This maps peripheral-id group
* to right register index.
*/
static const uint32_t bridge_peripheral_ids[] = {
2, /* PBA GRP */
3, /* PBB GRP */
4, /* PBC GRP */
5, /* PBD GRP */
1, /* HSB GRP */
0, /* CPU GRP */
};
static const uint32_t bridge_peripheral_instances[] = {
1, /* CPU MASK Instances */
10, /* HSB MASK Instances */
24, /* PBA MASK Instances */
7, /* PBB MASK Instances */
5, /* PBC MASK Instances */
6, /* PBD MASK Instances */
};
void soc_pmc_peripheral_enable(uint32_t id)
{
uint32_t bus_grp = id >> 5;
uint32_t per_idx = id & 0x1F;
uint32_t bus_id;
uint32_t mask;
if (bus_grp >= 6) {
return;
}
bus_id = bridge_peripheral_ids[bus_grp];
if (per_idx >= bridge_peripheral_instances[bus_id]) {
return;
}
mask = *(&PM->CPUMASK + bus_id);
mask |= (1U << per_idx);
PM->UNLOCK = PM_UNLOCK_KEY(0xAAu) |
PM_UNLOCK_ADDR(((uint32_t)&PM->CPUMASK -
(uint32_t)PM) +
(4 * bus_id));
*(&PM->CPUMASK + bus_id) = mask;
}
void soc_pmc_peripheral_disable(uint32_t id)
{
uint32_t bus_grp = id >> 5;
uint32_t per_idx = id & 0x1F;
uint32_t bus_id;
uint32_t mask;
if (bus_grp >= 6) {
return;
}
bus_id = bridge_peripheral_ids[bus_grp];
if (per_idx >= bridge_peripheral_instances[bus_id]) {
return;
}
mask = *(&PM->CPUMASK + bus_id);
mask &= ~(1U << per_idx);
PM->UNLOCK = PM_UNLOCK_KEY(0xAAu) |
PM_UNLOCK_ADDR(((uint32_t)&PM->CPUMASK -
(uint32_t)PM) +
(4 * bus_id));
*(&PM->CPUMASK + bus_id) = mask;
}
uint32_t soc_pmc_peripheral_is_enabled(uint32_t id)
{
uint32_t bus_grp = id >> 5;
uint32_t per_idx = id & 0x1F;
uint32_t bus_id;
uint32_t mask;
if (bus_grp >= 6) {
return 0;
}
bus_id = bridge_peripheral_ids[bus_grp];
if (per_idx >= bridge_peripheral_instances[bus_id]) {
return 0;
}
mask = *(&PM->CPUMASK + bus_id);
return ((mask & (1U << per_idx)) > 0);
}
void soc_pm_enable_pba_divmask(uint32_t mask)
{
uint32_t temp_mask;
temp_mask = PM->PBADIVMASK;
temp_mask |= mask;
PM->UNLOCK = PM_UNLOCK_KEY(0xAAu) |
PM_UNLOCK_ADDR((uint32_t)&PM->PBADIVMASK -
(uint32_t)PM);
PM->PBADIVMASK = temp_mask;
}

View file

@ -0,0 +1,5 @@
# SPDX-License-Identifier: Apache-2.0
zephyr_sources(
soc.c
)

View file

@ -0,0 +1,55 @@
# Copyright (c) 2020 Gerson Fernando Budke <nandojve@gmail.com>
# SPDX-License-Identifier: Apache-2.0
if SOC_SERIES_SAM4L
config SOC_SERIES
default "sam4l"
config SOC_PART_NUMBER
default "sam4ls8c" if SOC_PART_NUMBER_SAM4LS8C
default "sam4ls8b" if SOC_PART_NUMBER_SAM4LS8B
default "sam4ls8a" if SOC_PART_NUMBER_SAM4LS8A
default "sam4ls4c" if SOC_PART_NUMBER_SAM4LS4C
default "sam4ls4b" if SOC_PART_NUMBER_SAM4LS4B
default "sam4ls4a" if SOC_PART_NUMBER_SAM4LS4A
default "sam4ls2c" if SOC_PART_NUMBER_SAM4LS2C
default "sam4ls2b" if SOC_PART_NUMBER_SAM4LS2B
default "sam4ls2a" if SOC_PART_NUMBER_SAM4LS2A
default "sam4lc8c" if SOC_PART_NUMBER_SAM4LC8C
default "sam4lc8b" if SOC_PART_NUMBER_SAM4LC8B
default "sam4lc8a" if SOC_PART_NUMBER_SAM4LC8A
default "sam4lc4c" if SOC_PART_NUMBER_SAM4LC4C
default "sam4lc4b" if SOC_PART_NUMBER_SAM4LC4B
default "sam4lc4a" if SOC_PART_NUMBER_SAM4LC4A
default "sam4lc2c" if SOC_PART_NUMBER_SAM4LC2C
default "sam4lc2b" if SOC_PART_NUMBER_SAM4LC2B
default "sam4lc2a" if SOC_PART_NUMBER_SAM4LC2A
#
# SAM4L family has total 43 peripherals capable of
# generating interrupts.
#
config NUM_IRQS
default 80
config SYS_CLOCK_HW_CYCLES_PER_SEC
default 48000000
# Configure default device drivers. If a feature is supported by more than one
# device driver the default configuration will be placed in the board defconfig
# file.
config ENTROPY_SAM_RNG
default y
depends on ENTROPY_GENERATOR
config SPI_SAM
default y
depends on SPI
config USART_SAM
default y
depends on SERIAL
endif # SOC_SERIES_SAM4L

View file

@ -0,0 +1,17 @@
# Copyright (c) 2020 Gerson Fernando Budke <nandojve@gmail.com>
# SPDX-License-Identifier: Apache-2.0
config SOC_SERIES_SAM4L
bool "Atmel SAM4L MCU"
select ARM
select CPU_CORTEX_M4
select CPU_CORTEX_M_HAS_DWT
select CPU_HAS_ARM_MPU
select SOC_FAMILY_SAM
select ASF
help
Enable support for Atmel SAM4L Cortex-M4 microcontrollers.
Part No.: SAM4LS8C, SAM4LS8B, SAM4LS8A, SAM4LS4C, SAM4LS4B,
SAM4LS4A, SAM4LS2C, SAM4LS2B, SAM4LS2A, SAM4LC8C, SAM4LC8B,
SAM4LC8A, SAM4LC4C, SAM4LC4B, SAM4LC4A SAM4LC2C, SAM4LC2B,
SAM4LC2A

View file

@ -0,0 +1,61 @@
# Copyright (c) 2020 Gerson Fernando Budke <nandojve@gmail.com>
# SPDX-License-Identifier: Apache-2.0
choice
prompt "Atmel SAM4L MCU Selection"
depends on SOC_SERIES_SAM4L
config SOC_PART_NUMBER_SAM4LS8C
bool "SAM4LS8C"
config SOC_PART_NUMBER_SAM4LS8B
bool "SAM4LS8B"
config SOC_PART_NUMBER_SAM4LS8A
bool "SAM4LS8A"
config SOC_PART_NUMBER_SAM4LS4C
bool "SAM4LS4C"
config SOC_PART_NUMBER_SAM4LS4B
bool "SAM4LS4B"
config SOC_PART_NUMBER_SAM4LS4A
bool "SAM4LS4A"
config SOC_PART_NUMBER_SAM4LS2C
bool "SAM4LS2C"
config SOC_PART_NUMBER_SAM4LS2B
bool "SAM4LS2B"
config SOC_PART_NUMBER_SAM4LS2A
bool "SAM4LS2A"
config SOC_PART_NUMBER_SAM4LC8C
bool "SAM4LC8C"
config SOC_PART_NUMBER_SAM4LC8B
bool "SAM4LC8B"
config SOC_PART_NUMBER_SAM4LC8A
bool "SAM4LC8A"
config SOC_PART_NUMBER_SAM4LC4C
bool "SAM4LC4C"
config SOC_PART_NUMBER_SAM4LC4B
bool "SAM4LC4B"
config SOC_PART_NUMBER_SAM4LC4A
bool "SAM4LC4A"
config SOC_PART_NUMBER_SAM4LC2C
bool "SAM4LC2C"
config SOC_PART_NUMBER_SAM4LC2B
bool "SAM4LC2B"
config SOC_PART_NUMBER_SAM4LC2A
bool "SAM4LC2A"
endchoice

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/aarch32/cortex_m/scripts/linker.ld>

View file

@ -0,0 +1,304 @@
/*
* Copyright (c) 2020 Gerson Fernando Budke <nandojve@gmail.com>
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief Atmel SAM4L MCU series initialization code
*
* This module provides routines to initialize and support board-level hardware
* for the Atmel SAM4L series processor.
*/
#include <device.h>
#include <init.h>
#include <soc.h>
#include <arch/cpu.h>
/** Watchdog control register first write keys */
#define WDT_FIRST_KEY 0x55ul
/** Watchdog control register second write keys */
#define WDT_SECOND_KEY 0xAAul
/**
* @brief Calculate \f$ \left\lceil \frac{a}{b} \right\rceil \f$ using
* integer arithmetic.
*
* @param a An integer
* @param b Another integer
*
* @return (\a a / \a b) rounded up to the nearest integer.
*/
#define div_ceil(a, b) (((a) + (b) - 1) / (b))
/**
* @brief Sets the WatchDog Timer Control register to the \a ctrl value thanks
* to the WatchDog Timer key.
*
* @param ctrl Value to set the WatchDog Timer Control register to.
*/
static ALWAYS_INLINE void wdt_set_ctrl(uint32_t ctrl)
{
volatile uint32_t dly;
/** Calculate delay for internal synchronization
* see 45.1.3 WDT errata
*/
dly = div_ceil(48000000 * 2, 115000);
dly >>= 3; /* ~8 cycles for one while loop */
while (dly--) {
;
};
WDT->CTRL = ctrl | WDT_CTRL_KEY(WDT_FIRST_KEY);
WDT->CTRL = ctrl | WDT_CTRL_KEY(WDT_SECOND_KEY);
}
#define XTAL_FREQ 12000000
#define NR_PLLS 1
#define PLL_MAX_STARTUP_CYCLES (SCIF_PLL_PLLCOUNT_Msk >> SCIF_PLL_PLLCOUNT_Pos)
/**
* Fcpu = 48MHz
* Fpll = (Fclk * PLL_mul) / PLL_div
*/
#define PLL0_MUL (192000000 / XTAL_FREQ)
#define PLL0_DIV 4
static inline bool pll_is_locked(uint32_t pll_id)
{
return !!(SCIF->PCLKSR & (1U << (6 + pll_id)));
}
static inline bool osc_is_ready(uint8_t id)
{
switch (id) {
case OSC_ID_OSC0:
return !!(SCIF->PCLKSR & SCIF_PCLKSR_OSC0RDY);
case OSC_ID_OSC32:
return !!(BSCIF->PCLKSR & BSCIF_PCLKSR_OSC32RDY);
case OSC_ID_RC32K:
return !!(BSCIF->RC32KCR & (BSCIF_RC32KCR_EN));
case OSC_ID_RC80M:
return !!(SCIF->RC80MCR & (SCIF_RC80MCR_EN));
case OSC_ID_RCFAST:
return !!(SCIF->RCFASTCFG & (SCIF_RCFASTCFG_EN));
case OSC_ID_RC1M:
return !!(BSCIF->RC1MCR & (BSCIF_RC1MCR_CLKOE));
case OSC_ID_RCSYS:
/* RCSYS is always ready */
return true;
default:
/* unhandled_case(id); */
return false;
}
}
/**
* The PLL options #PLL_OPT_VCO_RANGE_HIGH and #PLL_OPT_OUTPUT_DIV will
* be set automatically based on the calculated target frequency.
*/
static inline uint32_t pll_config_init(uint32_t divide, uint32_t mul)
{
#define SCIF0_PLL_VCO_RANGE1_MAX_FREQ 240000000
#define SCIF_PLL0_VCO_RANGE1_MIN_FREQ 160000000
#define SCIF_PLL0_VCO_RANGE0_MAX_FREQ 180000000
#define SCIF_PLL0_VCO_RANGE0_MIN_FREQ 80000000
/* VCO frequency range is 160-240 MHz (80-180 MHz if unset) */
#define PLL_OPT_VCO_RANGE_HIGH 0
/* Divide output frequency by two */
#define PLL_OPT_OUTPUT_DIV 1
/* The threshold above which to set the #PLL_OPT_VCO_RANGE_HIGH option */
#define PLL_VCO_LOW_THRESHOLD ((SCIF_PLL0_VCO_RANGE1_MIN_FREQ \
+ SCIF_PLL0_VCO_RANGE0_MAX_FREQ) / 2)
#define PLL_MIN_HZ 40000000
#define PLL_MAX_HZ 240000000
#define MUL_MIN 2
#define MUL_MAX 16
#define DIV_MIN 0
#define DIV_MAX 15
uint32_t pll_value;
uint32_t vco_hz;
/* Calculate internal VCO frequency */
vco_hz = XTAL_FREQ * mul;
vco_hz /= divide;
pll_value = 0;
/* Bring the internal VCO frequency up to the minimum value */
if ((vco_hz < PLL_MIN_HZ * 2) && (mul <= 8)) {
mul *= 2;
vco_hz *= 2;
pll_value |= (1U << (SCIF_PLL_PLLOPT_Pos +
PLL_OPT_OUTPUT_DIV));
}
/* Set VCO frequency range according to calculated value */
if (vco_hz >= PLL_VCO_LOW_THRESHOLD) {
pll_value |= 1U << (SCIF_PLL_PLLOPT_Pos +
PLL_OPT_VCO_RANGE_HIGH);
}
pll_value |= ((mul - 1) << SCIF_PLL_PLLMUL_Pos) |
(divide << SCIF_PLL_PLLDIV_Pos) |
(PLL_MAX_STARTUP_CYCLES << SCIF_PLL_PLLCOUNT_Pos);
return pll_value;
}
static inline void flashcalw_set_wait_state(uint32_t wait_state)
{
HFLASHC->FCR = (HFLASHC->FCR & ~FLASHCALW_FCR_FWS) |
(wait_state ?
FLASHCALW_FCR_FWS_1 :
FLASHCALW_FCR_FWS_0);
}
static inline bool flashcalw_is_ready(void)
{
return ((HFLASHC->FSR & FLASHCALW_FSR_FRDY) != 0);
}
static inline void flashcalw_issue_command(uint32_t command, int page_number)
{
uint32_t time;
flashcalw_is_ready();
time = HFLASHC->FCMD;
/* Clear the command bitfield. */
time &= ~FLASHCALW_FCMD_CMD_Msk;
if (page_number >= 0) {
time = (FLASHCALW_FCMD_KEY_KEY |
FLASHCALW_FCMD_PAGEN(page_number) | command);
} else {
time |= (FLASHCALW_FCMD_KEY_KEY | command);
}
HFLASHC->FCMD = time;
flashcalw_is_ready();
}
/**
* @brief Setup various clock on SoC at boot time.
*
* Setup the SoC clocks according to section 28.12 in datasheet.
*
* Setup Slow, Main, PLLA, Processor and Master clocks during the device boot.
* It is assumed that the relevant registers are at their reset value.
*/
static ALWAYS_INLINE void clock_init(void)
{
/* Disable PicoCache and Enable HRAMC1 as extended RAM */
soc_pmc_peripheral_enable(
PM_CLOCK_MASK(PM_CLK_GRP_HSB, SYSCLK_HRAMC1_DATA));
soc_pmc_peripheral_enable(
PM_CLOCK_MASK(PM_CLK_GRP_PBB, SYSCLK_HRAMC1_REGS));
HCACHE->CTRL = HCACHE_CTRL_CEN_NO;
while (HCACHE->SR & HCACHE_SR_CSTS_EN) {
;
};
/* Enable PLL */
if (!pll_is_locked(0)) {
/* This assumes external 12MHz Crystal */
SCIF->UNLOCK = SCIF_UNLOCK_KEY(0xAAu) |
SCIF_UNLOCK_ADDR((uint32_t)&SCIF->OSCCTRL0 -
(uint32_t)SCIF);
SCIF->OSCCTRL0 = SCIF_OSCCTRL0_STARTUP(2) |
SCIF_OSCCTRL0_GAIN(3) |
SCIF_OSCCTRL0_MODE |
SCIF_OSCCTRL0_OSCEN;
while (!osc_is_ready(OSC_ID_OSC0)) {
;
};
uint32_t pll_config = pll_config_init(PLL0_DIV,
PLL0_MUL);
SCIF->UNLOCK = SCIF_UNLOCK_KEY(0xAAu) |
SCIF_UNLOCK_ADDR((uint32_t)&SCIF->PLL[0] -
(uint32_t)SCIF);
SCIF->PLL[0] = pll_config | SCIF_PLL_PLLEN;
while (!pll_is_locked(0)) {
;
};
}
/** Set a flash wait state depending on the new cpu frequency.
*/
flashcalw_set_wait_state(1);
flashcalw_issue_command(FLASHCALW_FCMD_CMD_HSEN, -1);
/** Set Clock CPU/BUS dividers
*/
PM->UNLOCK = PM_UNLOCK_KEY(0xAAu) |
PM_UNLOCK_ADDR((uint32_t)&PM->CPUSEL - (uint32_t)PM);
PM->CPUSEL = PM_CPUSEL_CPUSEL(0);
PM->UNLOCK = PM_UNLOCK_KEY(0xAAu) |
PM_UNLOCK_ADDR((uint32_t)&PM->PBASEL - (uint32_t)PM);
PM->PBASEL = PM_PBASEL_PBSEL(0);
PM->UNLOCK = PM_UNLOCK_KEY(0xAAu) |
PM_UNLOCK_ADDR((uint32_t)&PM->PBBSEL - (uint32_t)PM);
PM->PBBSEL = PM_PBBSEL_PBSEL(0);
PM->UNLOCK = PM_UNLOCK_KEY(0xAAu) |
PM_UNLOCK_ADDR((uint32_t)&PM->PBCSEL - (uint32_t)PM);
PM->PBCSEL = PM_PBCSEL_PBSEL(0);
PM->UNLOCK = PM_UNLOCK_KEY(0xAAu) |
PM_UNLOCK_ADDR((uint32_t)&PM->PBDSEL - (uint32_t)PM);
PM->PBDSEL = PM_PBDSEL_PBSEL(0);
/** Set PLL0 as source clock
*/
PM->UNLOCK = PM_UNLOCK_KEY(0xAAu) |
PM_UNLOCK_ADDR((uint32_t)&PM->MCCTRL - (uint32_t)PM);
PM->MCCTRL = OSC_SRC_PLL0;
}
/**
* @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_sam4l_init(const struct device *arg)
{
uint32_t key;
ARG_UNUSED(arg);
key = irq_lock();
#if defined(CONFIG_WDT_DISABLE_AT_BOOT)
wdt_set_ctrl(WDT->CTRL & ~WDT_CTRL_EN);
while (WDT->CTRL & WDT_CTRL_EN) {
;
};
#endif
/* Setup system clocks. */
clock_init();
/*
* 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_sam4l_init, PRE_KERNEL_1, 0);

View file

@ -0,0 +1,223 @@
/*
* Copyright (c) 2020 Gerson Fernando Budke <nandojve@gmail.com>
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file SoC configuration macros for the Atmel SAM4L family processors.
*/
#ifndef _ATMEL_SAM4L_SOC_H_
#define _ATMEL_SAM4L_SOC_H_
#ifndef _ASMLANGUAGE
#define DONT_USE_CMSIS_INIT
#define DONT_USE_PREDEFINED_CORE_HANDLERS
#define DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS
#if defined(CONFIG_SOC_PART_NUMBER_SAM4LS8C)
#include <sam4ls8c.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LS8B)
#include <sam4ls8b.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LS8A)
#include <sam4ls8a.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LS4C)
#include <sam4ls4c.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LS4B)
#include <sam4ls4b.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LS4A)
#include <sam4ls4a.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LS2C)
#include <sam4ls2c.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LS2B)
#include <sam4ls2b.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LS2A)
#include <sam4ls2a.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LC8C)
#include <sam4lc8c.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LC8B)
#include <sam4lc8b.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LC8A)
#include <sam4lc8a.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LC4C)
#include <sam4lc4c.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LC4B)
#include <sam4lc4b.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LC4A)
#include <sam4lc4a.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LC2C)
#include <sam4lc2c.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LC2B)
#include <sam4lc2b.h>
#elif defined(CONFIG_SOC_PART_NUMBER_SAM4LC2A)
#include <sam4lc2a.h>
#else
#error Library does not support the specified device.
#endif
#include "../common/soc_pmc.h"
#include "../common/soc_gpio.h"
#include "../common/atmel_sam_dt.h"
/** Processor Clock (HCLK) Frequency */
#define SOC_ATMEL_SAM_HCLK_FREQ_HZ ATMEL_SAM_DT_CPU_CLK_FREQ_HZ
/** Master Clock (MCK) Frequency */
#define SOC_ATMEL_SAM_MCK_FREQ_HZ SOC_ATMEL_SAM_HCLK_FREQ_HZ
/** Oscillator identifiers
* External Oscillator 0
* External 32 kHz oscillator
* Internal 32 kHz RC oscillator
* Internal 80 MHz RC oscillator
* Internal 4-8-12 MHz RCFAST oscillator
* Internal 1 MHz RC oscillator
* Internal System RC oscillator
*/
#define OSC_ID_OSC0 0
#define OSC_ID_OSC32 1
#define OSC_ID_RC32K 2
#define OSC_ID_RC80M 3
#define OSC_ID_RCFAST 4
#define OSC_ID_RC1M 5
#define OSC_ID_RCSYS 6
/** System clock source
* System RC oscillator
* Oscillator 0
* Phase Locked Loop 0
* Digital Frequency Locked Loop
* 80 MHz RC oscillator
* 4-8-12 MHz RC oscillator
* 1 MHz RC oscillator
*/
#define OSC_SRC_RCSYS 0
#define OSC_SRC_OSC0 1
#define OSC_SRC_PLL0 2
#define OSC_SRC_DFLL 3
#define OSC_SRC_RC80M 4
#define OSC_SRC_RCFAST 5
#define OSC_SRC_RC1M 6
#define PM_CLOCK_MASK(bus, per) ((bus << 5) + per)
/** Bus index of maskable module clocks. Peripheral ids are defined out of
* order. It start from PBA up to PBD, then move to HSB, and finaly CPU.
*/
#define PM_CLK_GRP_CPU 5
#define PM_CLK_GRP_HSB 4
#define PM_CLK_GRP_PBA 0
#define PM_CLK_GRP_PBB 1
#define PM_CLK_GRP_PBC 2
#define PM_CLK_GRP_PBD 3
/** Clocks derived from the CPU clock
*/
#define SYSCLK_OCD 0
/** Clocks derived from the HSB clock
*/
#define SYSCLK_PDCA_HSB 0
#define SYSCLK_HFLASHC_DATA 1
#define SYSCLK_HRAMC1_DATA 2
#define SYSCLK_USBC_DATA 3
#define SYSCLK_CRCCU_DATA 4
#define SYSCLK_PBA_BRIDGE 5
#define SYSCLK_PBB_BRIDGE 6
#define SYSCLK_PBC_BRIDGE 7
#define SYSCLK_PBD_BRIDGE 8
#define SYSCLK_AESA_HSB 9
/** Clocks derived from the PBA clock
*/
#define SYSCLK_IISC 0
#define SYSCLK_SPI 1
#define SYSCLK_TC0 2
#define SYSCLK_TC1 3
#define SYSCLK_TWIM0 4
#define SYSCLK_TWIS0 5
#define SYSCLK_TWIM1 6
#define SYSCLK_TWIS1 7
#define SYSCLK_USART0 8
#define SYSCLK_USART1 9
#define SYSCLK_USART2 10
#define SYSCLK_USART3 11
#define SYSCLK_ADCIFE 12
#define SYSCLK_DACC 13
#define SYSCLK_ACIFC 14
#define SYSCLK_GLOC 15
#define SYSCLK_ABDACB 16
#define SYSCLK_TRNG 17
#define SYSCLK_PARC 18
#define SYSCLK_CATB 19
#define SYSCLK_TWIM2 21
#define SYSCLK_TWIM3 22
#define SYSCLK_LCDCA 23
/** Clocks derived from the PBB clock
*/
#define SYSCLK_HFLASHC_REGS 0
#define SYSCLK_HRAMC1_REGS 1
#define SYSCLK_HMATRIX 2
#define SYSCLK_PDCA_PB 3
#define SYSCLK_CRCCU_REGS 4
#define SYSCLK_USBC_REGS 5
#define SYSCLK_PEVC 6
/** Clocks derived from the PBC clock
*/
#define SYSCLK_PM 0
#define SYSCLK_CHIPID 1
#define SYSCLK_SCIF 2
#define SYSCLK_FREQM 3
#define SYSCLK_GPIO 4
/** Clocks derived from the PBD clock
*/
#define SYSCLK_BPM 0
#define SYSCLK_BSCIF 1
#define SYSCLK_AST 2
#define SYSCLK_WDT 3
#define SYSCLK_EIC 4
#define SYSCLK_PICOUART 5
/** Divided clock mask derived from the PBA clock
*/
#define PBA_DIVMASK_TIMER_CLOCK2 (1u << 0)
#define PBA_DIVMASK_TIMER_CLOCK3 (1u << 2)
#define PBA_DIVMASK_CLK_USART (1u << 2)
#define PBA_DIVMASK_TIMER_CLOCK4 (1u << 4)
#define PBA_DIVMASK_TIMER_CLOCK5 (1u << 6)
#define PBA_DIVMASK_Msk (0x7Fu << 0)
/** Generic Clock Instances
* 0- DFLLIF main reference and GCLK0 pin (CLK_DFLLIF_REF)
* 1- DFLLIF dithering and SSG reference and GCLK1 pin (CLK_DFLLIF_DITHER)
* 2- AST and GCLK2 pin
* 3- CATB and GCLK3 pin
* 4- AESA
* 5- GLOC, TC0 and RC32KIFB_REF
* 6- ABDACB and IISC
* 7- USBC
* 8- TC1 and PEVC[0]
* 9- PLL0 and PEVC[1]
* 10- ADCIFE
* 11- Master generic clock. Can be used as source for other generic clocks.
*/
#define GEN_CLK_DFLL_REF 0
#define GEN_CLK_DFLL_DITHER 1
#define GEN_CLK_AST 2
#define GEN_CLK_CATB 3
#define GEN_CLK_AESA 4
#define GEN_CLK_GLOC 5
#define GEN_CLK_ABDACB 6
#define GEN_CLK_USBC 7
#define GEN_CLK_TC1_PEVC0 8
#define GEN_CLK_PLL0_PEVC1 9
#define GEN_CLK_ADCIFE 10
#define GEN_CLK_MASTER_GEN 11
#endif /* !_ASMLANGUAGE */
#endif /* _ATMEL_SAM4L_SOC_H_ */