atsamd: Add support for SAMC21
Signed-off-by: Luke Vuksta <wulfstawulfsta@gmail.com>
This commit is contained in:
parent
06e5c577bd
commit
3b0729c949
|
@ -15,7 +15,7 @@ choice
|
|||
config MACH_ATSAM
|
||||
bool "SAM3/SAM4/SAM E70 (Due and Duet)"
|
||||
config MACH_ATSAMD
|
||||
bool "SAMD21/SAMD51/SAME5x"
|
||||
bool "SAMC21/SAMD21/SAMD51/SAME5x"
|
||||
config MACH_LPC176X
|
||||
bool "LPC176x (Smoothieboard)"
|
||||
config MACH_STM32
|
||||
|
|
|
@ -9,7 +9,7 @@ config ATSAMD_SELECT
|
|||
select HAVE_GPIO_ADC
|
||||
select HAVE_GPIO_I2C
|
||||
select HAVE_GPIO_SPI
|
||||
select HAVE_GPIO_HARD_PWM if MACH_SAMD21
|
||||
select HAVE_GPIO_HARD_PWM if MACH_SAMX2
|
||||
select HAVE_GPIO_BITBANGING
|
||||
select HAVE_STRICT_TIMING
|
||||
select HAVE_CHIPID
|
||||
|
@ -27,6 +27,9 @@ config BOARD_DIRECTORY
|
|||
|
||||
choice
|
||||
prompt "Processor model"
|
||||
config MACH_SAMC21G18
|
||||
bool "SAMC21G18 (Duet 3 Toolboard 1LC)"
|
||||
select MACH_SAMC21
|
||||
config MACH_SAMD21G18
|
||||
bool "SAMD21G18 (Arduino Zero)"
|
||||
select MACH_SAMD21
|
||||
|
@ -56,8 +59,14 @@ choice
|
|||
select MACH_SAME54
|
||||
endchoice
|
||||
|
||||
config MACH_SAMX2
|
||||
bool
|
||||
config MACH_SAMC21
|
||||
bool
|
||||
select MACH_SAMX2
|
||||
config MACH_SAMD21
|
||||
bool
|
||||
select MACH_SAMX2
|
||||
config MACH_SAMX5
|
||||
bool
|
||||
config MACH_SAMD51
|
||||
|
@ -71,10 +80,15 @@ config MACH_SAME54
|
|||
select MACH_SAMX5
|
||||
config HAVE_SAMD_CANBUS
|
||||
bool
|
||||
default y if MACH_SAME51 || MACH_SAME54
|
||||
default y if MACH_SAMC21 || MACH_SAME51 || MACH_SAME54
|
||||
config HAVE_SAMD_USB
|
||||
bool
|
||||
default n if MACH_SAMC21G18
|
||||
default y
|
||||
|
||||
config MCU
|
||||
string
|
||||
default "samc21g18a" if MACH_SAMC21G18
|
||||
default "samd21g18a" if MACH_SAMD21G18
|
||||
default "samd21e18a" if MACH_SAMD21E18
|
||||
default "samd21e15a" if MACH_SAMD21E15
|
||||
|
@ -88,7 +102,7 @@ config MCU
|
|||
config FLASH_SIZE
|
||||
hex
|
||||
default 0x8000 if MACH_SAMD21E15
|
||||
default 0x40000 if MACH_SAMD21G18 || MACH_SAMD21E18
|
||||
default 0x40000 if MACH_SAMC21G18 || MACH_SAMD21G18 || MACH_SAMD21E18
|
||||
default 0x80000 if MACH_SAMD51G19 || MACH_SAMD51J19 || MACH_SAMD51N19 || MACH_SAME51J19
|
||||
default 0x100000 if MACH_SAMD51P20 || MACH_SAME54P20
|
||||
|
||||
|
@ -103,7 +117,7 @@ config RAM_START
|
|||
config RAM_SIZE
|
||||
hex
|
||||
default 0x1000 if MACH_SAMD21E15
|
||||
default 0x8000 if MACH_SAMD21G18 || MACH_SAMD21E18
|
||||
default 0x8000 if MACH_SAMC21G18 || MACH_SAMD21G18 || MACH_SAMD21E18
|
||||
default 0x30000 if MACH_SAMD51G19 || MACH_SAMD51J19 || MACH_SAMD51N19 || MACH_SAME51J19
|
||||
default 0x40000 if MACH_SAMD51P20 || MACH_SAME54P20
|
||||
|
||||
|
@ -122,7 +136,7 @@ choice
|
|||
depends on MACH_SAMD21
|
||||
bool "8KiB bootloader (Arduino Zero)"
|
||||
config SAMD_FLASH_START_4000
|
||||
bool "16KiB bootloader (Arduino M0)"
|
||||
bool "16KiB bootloader (Arduino M0, Duet 3 Bootloader)"
|
||||
config SAMD_FLASH_START_0000
|
||||
bool "No bootloader"
|
||||
endchoice
|
||||
|
@ -140,11 +154,13 @@ config FLASH_APPLICATION_ADDRESS
|
|||
choice
|
||||
prompt "Clock Reference"
|
||||
config CLOCK_REF_X32K
|
||||
bool "32.768Khz crystal"
|
||||
bool "32.768Khz crystal" if !MACH_SAMC21
|
||||
config CLOCK_REF_X12M
|
||||
bool "12Mhz crystal" if MACH_SAMC21
|
||||
config CLOCK_REF_X25M
|
||||
bool "25Mhz crystal" if MACH_SAMX5
|
||||
bool "25Mhz crystal" if MACH_SAMC21 || MACH_SAMX5
|
||||
config CLOCK_REF_INTERNAL
|
||||
bool "Internal clock"
|
||||
bool "Internal clock" if !MACH_SAMC21
|
||||
endchoice
|
||||
|
||||
choice
|
||||
|
@ -162,7 +178,7 @@ endchoice
|
|||
|
||||
config CLOCK_FREQ
|
||||
int
|
||||
default 48000000 if MACH_SAMD21
|
||||
default 48000000 if MACH_SAMX2
|
||||
default 150000000 if SAMD51_FREQ_150
|
||||
default 180000000 if SAMD51_FREQ_180
|
||||
default 200000000 if SAMD51_FREQ_200
|
||||
|
@ -177,9 +193,11 @@ choice
|
|||
prompt "Communication interface"
|
||||
config ATSAMD_USB
|
||||
bool "USB"
|
||||
depends on HAVE_SAMD_USB
|
||||
select USBSERIAL
|
||||
config ATSAMD_SERIAL
|
||||
bool "Serial"
|
||||
depends on !MACH_SAMC21
|
||||
select SERIAL
|
||||
config ATSAMD_MMENU_CANBUS_PA23_PA22
|
||||
bool "CAN bus (on PA23/PA22)"
|
||||
|
@ -189,9 +207,13 @@ choice
|
|||
bool "CAN bus (on PA25/PA24)"
|
||||
depends on HAVE_SAMD_CANBUS
|
||||
select CANSERIAL
|
||||
config ATSAMD_MMENU_CANBUS_PB11_PB10
|
||||
bool "CAN bus (on PB11/PB10)"
|
||||
depends on HAVE_SAMD_CANBUS && MACH_SAMC21
|
||||
select CANSERIAL
|
||||
config ATSAMD_MMENU_CANBUS_PB13_PB12
|
||||
bool "CAN bus (on PB13/PB12)"
|
||||
depends on HAVE_SAMD_CANBUS
|
||||
depends on HAVE_SAMD_CANBUS && !MACH_SAMC21
|
||||
select CANSERIAL
|
||||
config ATSAMD_MMENU_CANBUS_PB15_PB14
|
||||
bool "CAN bus (on PB15/PB14)"
|
||||
|
@ -199,7 +221,7 @@ choice
|
|||
select CANSERIAL
|
||||
config ATSAMD_USBCANBUS
|
||||
bool "USB to CAN bus bridge"
|
||||
depends on HAVE_SAMD_CANBUS
|
||||
depends on HAVE_SAMD_CANBUS && HAVE_SAMD_USB
|
||||
select USBCANBUS
|
||||
endchoice
|
||||
choice
|
||||
|
@ -218,6 +240,9 @@ config ATSAMD_CANBUS_PA23_PA22
|
|||
config ATSAMD_CANBUS_PA25_PA24
|
||||
bool
|
||||
default y if ATSAMD_MMENU_CANBUS_PA25_PA24
|
||||
config ATSAMD_CANBUS_PB11_PB10
|
||||
bool
|
||||
default y if ATSAMD_MMENU_CANBUS_PB11_PB10
|
||||
config ATSAMD_CANBUS_PB13_PB12
|
||||
bool
|
||||
default y if ATSAMD_MMENU_CANBUS_PB13_PB12 || ATSAMD_CMENU_CANBUS_PB13_PB12
|
||||
|
|
|
@ -7,6 +7,7 @@ dirs-y += src/atsamd src/generic lib/fast-hash
|
|||
|
||||
MCU := $(shell echo $(CONFIG_MCU) | tr a-z A-Z)
|
||||
|
||||
CFLAGS-$(CONFIG_MACH_SAMC21) += -mcpu=cortex-m0plus -Ilib/samc21/samc21/include
|
||||
CFLAGS-$(CONFIG_MACH_SAMD21) += -mcpu=cortex-m0plus -Ilib/samd21/samd21a/include
|
||||
CFLAGS-$(CONFIG_MACH_SAMD51) += -Ilib/samd51/samd51a/include
|
||||
CFLAGS-$(CONFIG_MACH_SAME51) += -Ilib/same51/include
|
||||
|
@ -31,6 +32,8 @@ src-$(CONFIG_HAVE_GPIO_I2C) += atsamd/i2c.c
|
|||
src-$(CONFIG_HAVE_GPIO_SPI) += atsamd/spi.c
|
||||
src-$(CONFIG_HAVE_SERCOM) += atsamd/sercom.c
|
||||
src-$(CONFIG_HAVE_GPIO_HARD_PWM) += atsamd/hard_pwm.c
|
||||
src-$(CONFIG_MACH_SAMC21) += atsamd/samd51_watchdog.c
|
||||
src-$(CONFIG_MACH_SAMC21) += atsamd/samc21_clock.c atsamd/timer.c generic/timer_irq.c
|
||||
src-$(CONFIG_MACH_SAMD21) += atsamd/watchdog.c
|
||||
src-$(CONFIG_MACH_SAMD21) += atsamd/clock.c atsamd/timer.c generic/timer_irq.c
|
||||
src-$(CONFIG_MACH_SAMX5) += atsamd/samd51_watchdog.c
|
||||
|
|
|
@ -12,7 +12,26 @@
|
|||
#define ADC_TEMPERATURE_PIN 0xfe
|
||||
DECL_ENUMERATION("pin", "ADC_TEMPERATURE", ADC_TEMPERATURE_PIN);
|
||||
|
||||
#if CONFIG_MACH_SAMD21
|
||||
#if CONFIG_MACH_SAMC21
|
||||
|
||||
#define ADC_INPUTCTRL_MUXNEG_GND 0x18
|
||||
|
||||
#define SAMD51_ADC_SYNC(ADC, BIT) \
|
||||
while(ADC->SYNCBUSY.reg & ADC_SYNCBUSY_ ## BIT)
|
||||
static const uint8_t adc_pins[] = {
|
||||
/* ADC0 */
|
||||
GPIO('A', 2), GPIO('A', 3), GPIO('B', 8), GPIO('B', 9), GPIO('A', 4),
|
||||
GPIO('A', 5), GPIO('A', 6), GPIO('A', 7), GPIO('A', 8), GPIO('A', 9),
|
||||
GPIO('A', 10), GPIO('A', 11),
|
||||
/* Padding to 16 */
|
||||
255, 255, 255, 255,
|
||||
/* ADC1 */
|
||||
GPIO('B', 0), GPIO('B', 1), GPIO('B', 2), GPIO('B', 3), GPIO('B', 8),
|
||||
GPIO('B', 9), GPIO('B', 4), GPIO('B', 5), GPIO('B', 6), GPIO('B', 7),
|
||||
GPIO('A', 8), GPIO('A', 9)
|
||||
};
|
||||
|
||||
#elif CONFIG_MACH_SAMD21
|
||||
|
||||
#define SAMD51_ADC_SYNC(ADC, BIT)
|
||||
static const uint8_t adc_pins[] = {
|
||||
|
@ -21,6 +40,7 @@ static const uint8_t adc_pins[] = {
|
|||
GPIO('B', 2), GPIO('B', 3), GPIO('B', 4), GPIO('B', 5), GPIO('B', 6),
|
||||
GPIO('B', 7), GPIO('A', 8), GPIO('A', 9), GPIO('A', 10), GPIO('A', 11)
|
||||
};
|
||||
|
||||
#elif CONFIG_MACH_SAMX5
|
||||
|
||||
#define SAMD51_ADC_SYNC(ADC, BIT) \
|
||||
|
@ -53,7 +73,7 @@ static struct gpio_adc gpio_adc_pin_to_struct(uint8_t pin)
|
|||
}
|
||||
#if CONFIG_MACH_SAMD21
|
||||
Adc* reg = ADC;
|
||||
#elif CONFIG_MACH_SAMX5
|
||||
#elif CONFIG_MACH_SAMC21 || CONFIG_MACH_SAMX5
|
||||
Adc* reg = (chan < 16 ? ADC0 : ADC1);
|
||||
chan %= 16;
|
||||
#endif
|
||||
|
@ -69,7 +89,38 @@ adc_init(void)
|
|||
return;
|
||||
have_run_init = 1;
|
||||
|
||||
#if CONFIG_MACH_SAMD21
|
||||
#if CONFIG_MACH_SAMC21
|
||||
// Enable adc clock
|
||||
enable_pclock(ADC0_GCLK_ID, ID_ADC0);
|
||||
enable_pclock(ADC1_GCLK_ID, ID_ADC1);
|
||||
|
||||
// Load calibration info
|
||||
// ADC0
|
||||
uint32_t refbuf = GET_FUSE(ADC0_FUSES_BIASREFBUF);
|
||||
uint32_t comp = GET_FUSE(ADC0_FUSES_BIASCOMP);
|
||||
ADC0->CALIB.reg = (ADC0_FUSES_BIASREFBUF(refbuf)
|
||||
| ADC0_FUSES_BIASCOMP(comp));
|
||||
|
||||
// ADC1
|
||||
refbuf = GET_FUSE(ADC1_FUSES_BIASREFBUF);
|
||||
comp = GET_FUSE(ADC1_FUSES_BIASCOMP);
|
||||
ADC1->CALIB.reg = (ADC0_FUSES_BIASREFBUF(refbuf)
|
||||
| ADC0_FUSES_BIASCOMP(comp));
|
||||
|
||||
// Setup and enable
|
||||
// ADC0
|
||||
ADC0->REFCTRL.reg = ADC_REFCTRL_REFSEL_INTVCC1;
|
||||
ADC0->CTRLB.reg = ADC_CTRLB_PRESCALER_DIV128;
|
||||
ADC0->SAMPCTRL.reg = ADC_SAMPCTRL_SAMPLEN(63);
|
||||
ADC0->CTRLA.reg = ADC_CTRLA_ENABLE;
|
||||
|
||||
// ADC1
|
||||
ADC1->REFCTRL.reg = ADC_REFCTRL_REFSEL_INTVCC1;
|
||||
ADC1->CTRLB.reg = ADC_CTRLB_PRESCALER_DIV128;
|
||||
ADC1->SAMPCTRL.reg = ADC_SAMPCTRL_SAMPLEN(63);
|
||||
ADC1->CTRLA.reg = ADC_CTRLA_ENABLE;
|
||||
|
||||
#elif CONFIG_MACH_SAMD21
|
||||
// Enable adc clock
|
||||
enable_pclock(ADC_GCLK_ID, ID_ADC);
|
||||
// Load calibraiton info
|
||||
|
@ -135,7 +186,7 @@ gpio_adc_setup(uint8_t pin)
|
|||
SYSCTRL->VREF.reg |= SYSCTRL_VREF_TSEN;
|
||||
return (struct gpio_adc){ .regs=ADC,
|
||||
.chan=ADC_INPUTCTRL_MUXPOS_TEMP_Val };
|
||||
#else
|
||||
#elif CONFIG_MACH_SAMX5
|
||||
SUPC->VREF.reg |= SUPC_VREF_TSEN;
|
||||
return (struct gpio_adc){ .regs=ADC0,
|
||||
.chan=ADC_INPUTCTRL_MUXPOS_PTAT_Val };
|
||||
|
|
|
@ -30,7 +30,7 @@ chipid_init(void)
|
|||
return;
|
||||
|
||||
uint32_t id[4];
|
||||
if (CONFIG_MACH_SAMD21) {
|
||||
if (CONFIG_MACH_SAMX2) {
|
||||
id[0] = *(uint32_t*)0x0080A00C;
|
||||
id[1] = *(uint32_t*)0x0080A040;
|
||||
id[2] = *(uint32_t*)0x0080A044;
|
||||
|
|
|
@ -28,6 +28,11 @@
|
|||
#define GPIO_Rx GPIO('A', 25)
|
||||
#define GPIO_Tx GPIO('A', 24)
|
||||
#define CANx_GCLK_ID CAN0_GCLK_ID
|
||||
#elif CONFIG_ATSAMD_CANBUS_PB11_PB10
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_CAN", "PB11,PB10");
|
||||
#define GPIO_Rx GPIO('B', 11)
|
||||
#define GPIO_Tx GPIO('B', 10)
|
||||
#define CANx_GCLK_ID CAN1_GCLK_ID
|
||||
#elif CONFIG_ATSAMD_CANBUS_PB13_PB12
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_CAN", "PB13,PB12");
|
||||
#define GPIO_Rx GPIO('B', 13)
|
||||
|
@ -40,7 +45,17 @@
|
|||
#define CANx_GCLK_ID CAN1_GCLK_ID
|
||||
#endif
|
||||
|
||||
#if CANx_GCLK_ID == CAN0_GCLK_ID
|
||||
#if CANx_GCLK_ID == CAN0_GCLK_ID && CONFIG_MACH_SAMC21
|
||||
#define CAN_FUNCTION 'G'
|
||||
#define CANx CAN0
|
||||
#define CANx_IRQn CAN0_IRQn
|
||||
#define MCLK_AHBMASK_CANx MCLK_AHBMASK_CAN0
|
||||
#elif CANx_GCLK_ID == CAN1_GCLK_ID && CONFIG_MACH_SAMC21
|
||||
#define CAN_FUNCTION 'G'
|
||||
#define CANx CAN1
|
||||
#define CANx_IRQn CAN1_IRQn
|
||||
#define MCLK_AHBMASK_CANx MCLK_AHBMASK_CAN1
|
||||
#elif CANx_GCLK_ID == CAN0_GCLK_ID
|
||||
#define CAN_FUNCTION 'I'
|
||||
#define CANx CAN0
|
||||
#define CANx_IRQn CAN0_IRQn
|
||||
|
@ -234,13 +249,18 @@ compute_btr(uint32_t pclock, uint32_t bitrate)
|
|||
void
|
||||
can_init(void)
|
||||
{
|
||||
#if CONFIG_HAVE_SAMD_USB
|
||||
if (!CONFIG_USB) {
|
||||
// The FDCAN peripheral only seems to run if at least one
|
||||
// other peripheral is also enabled.
|
||||
enable_pclock(USB_GCLK_ID, ID_USB);
|
||||
USB->DEVICE.CTRLA.reg = USB_CTRLA_ENABLE;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if CONFIG_MACH_SAMC21
|
||||
MCLK->AHBMASK.reg |= MCLK_AHBMASK_CANx;
|
||||
#endif
|
||||
enable_pclock(CANx_GCLK_ID, -1);
|
||||
|
||||
gpio_peripheral(GPIO_Rx, CAN_FUNCTION, 1);
|
||||
|
|
|
@ -42,7 +42,7 @@ gpio_peripheral(uint32_t gpio, char ptype, int32_t pull_up)
|
|||
* General Purpose Input Output (GPIO) pins
|
||||
****************************************************************/
|
||||
|
||||
#if CONFIG_MACH_SAMD21
|
||||
#if CONFIG_MACH_SAMX2
|
||||
#define NUM_PORT 2
|
||||
DECL_ENUMERATION_RANGE("pin", "PA0", GPIO('A', 0), 32);
|
||||
DECL_ENUMERATION_RANGE("pin", "PB0", GPIO('B', 0), 32);
|
||||
|
|
|
@ -92,7 +92,13 @@ gpio_pwm_setup(uint8_t pin, uint32_t cycle_time, uint8_t val)
|
|||
}
|
||||
|
||||
// Set initial value
|
||||
struct gpio_pwm g = (struct gpio_pwm) { (void*)&tcc->CCB[p->channel].reg };
|
||||
struct gpio_pwm g = (struct gpio_pwm) {
|
||||
#if CONFIG_MACH_SAMD21
|
||||
(void*)&tcc->CCB[p->channel].reg
|
||||
#elif CONFIG_MACH_SAMC21
|
||||
(void*)&tcc->CCBUF[p->channel].reg
|
||||
#endif
|
||||
};
|
||||
gpio_pwm_write(g, val);
|
||||
|
||||
// Route output to pin
|
||||
|
|
|
@ -5,7 +5,9 @@
|
|||
#include <stdint.h> // uint32_t
|
||||
#include "autoconf.h" // CONFIG_MACH_SAMD21A
|
||||
|
||||
#if CONFIG_MACH_SAMD21
|
||||
#if CONFIG_MACH_SAMC21
|
||||
#include "samc21.h"
|
||||
#elif CONFIG_MACH_SAMD21
|
||||
#include "samd21.h"
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
#include "samd51.h"
|
||||
|
|
|
@ -0,0 +1,148 @@
|
|||
// Code to setup peripheral clocks on the SAMC21
|
||||
//
|
||||
// Copyright (C) 2018-2023 Kevin O'Connor <kevin@koconnor.net>
|
||||
// Copyright (C) 2023 Luke Vuksta <wulfstawulfsta@gmail.com>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "command.h" // DECL_CONSTANT_STR
|
||||
#include "compiler.h" // DIV_ROUND_CLOSEST
|
||||
#include "internal.h" // enable_pclock
|
||||
|
||||
// The "generic clock generators" that are configured
|
||||
#define CLKGEN_MAIN 0
|
||||
|
||||
#define FREQ_MAIN CONFIG_CLOCK_FREQ
|
||||
#define FREQ_48M 48000000
|
||||
|
||||
// Configure a clock generator using a given source as input
|
||||
static inline void
|
||||
gen_clock(uint32_t clkgen_id, uint32_t flags)
|
||||
{
|
||||
GCLK->GENCTRL[clkgen_id].reg = flags | GCLK_GENCTRL_GENEN;
|
||||
while (GCLK->SYNCBUSY.reg & GCLK_SYNCBUSY_GENCTRL(1 << clkgen_id))
|
||||
;
|
||||
}
|
||||
|
||||
// Route a peripheral clock to a given clkgen
|
||||
static inline void
|
||||
route_pclock(uint32_t pclk_id, uint32_t clkgen_id)
|
||||
{
|
||||
uint32_t val = GCLK_PCHCTRL_GEN(clkgen_id) | GCLK_PCHCTRL_CHEN;
|
||||
// Don't do anything if already enabled (Timer Counter).
|
||||
if (GCLK->PCHCTRL[pclk_id].reg != val) {
|
||||
GCLK->PCHCTRL[pclk_id].reg = val;
|
||||
while (GCLK->PCHCTRL[pclk_id].reg != val)
|
||||
;
|
||||
}
|
||||
}
|
||||
|
||||
// Enable a peripheral clock and power to that peripheral
|
||||
void
|
||||
enable_pclock(uint32_t pclk_id, int32_t pm_id)
|
||||
{
|
||||
route_pclock(pclk_id, CLKGEN_MAIN);
|
||||
if (pm_id >= 0) {
|
||||
uint32_t pm_port = pm_id / 32, pm_bit = 1 << (pm_id % 32);
|
||||
(&MCLK->APBAMASK.reg)[pm_port] |= pm_bit;
|
||||
}
|
||||
}
|
||||
|
||||
// Return the frequency of the given peripheral clock
|
||||
uint32_t
|
||||
get_pclock_frequency(uint32_t pclk_id)
|
||||
{
|
||||
return FREQ_MAIN;
|
||||
}
|
||||
|
||||
// Configure a dpll to a given clock multiplier
|
||||
static void
|
||||
config_dpll(uint32_t mul, uint32_t ctrlb)
|
||||
{
|
||||
OSCCTRL->DPLLCTRLA.reg = 0;
|
||||
while (OSCCTRL->DPLLSYNCBUSY.reg & OSCCTRL_DPLLSYNCBUSY_ENABLE)
|
||||
;
|
||||
OSCCTRL->DPLLRATIO.reg = OSCCTRL_DPLLRATIO_LDR(mul - 1);
|
||||
while (OSCCTRL->DPLLSYNCBUSY.reg & OSCCTRL_DPLLSYNCBUSY_DPLLRATIO)
|
||||
;
|
||||
OSCCTRL->DPLLCTRLB.reg = ctrlb | OSCCTRL_DPLLCTRLB_LBYPASS;
|
||||
OSCCTRL->DPLLCTRLA.reg = OSCCTRL_DPLLCTRLA_ENABLE;
|
||||
uint32_t mask = OSCCTRL_DPLLSTATUS_CLKRDY | OSCCTRL_DPLLSTATUS_LOCK;
|
||||
while ((OSCCTRL->DPLLSTATUS.reg & mask) != mask)
|
||||
;
|
||||
}
|
||||
|
||||
#if CONFIG_CLOCK_REF_X12M
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_crystal", "PA14,PA15");
|
||||
#endif
|
||||
|
||||
// Initialize the clocks using an external 12M crystal
|
||||
static void
|
||||
clock_init_12m(void)
|
||||
{
|
||||
// Enable XOSC1
|
||||
uint32_t freq_xosc = 12000000;
|
||||
uint32_t val = (OSCCTRL_XOSCCTRL_ENABLE | OSCCTRL_XOSCCTRL_XTALEN
|
||||
| OSCCTRL_XOSCCTRL_GAIN(3) | OSCCTRL_XOSCCTRL_AMPGC);
|
||||
OSCCTRL->XOSCCTRL.reg = val;
|
||||
while (!(OSCCTRL->STATUS.reg & OSCCTRL_STATUS_XOSCRDY))
|
||||
;
|
||||
|
||||
// Generate 48Mhz clock on PLL (with XOSC as reference)
|
||||
uint32_t p0div = 24, p0mul = DIV_ROUND_CLOSEST(FREQ_MAIN, freq_xosc/p0div);
|
||||
uint32_t p0ctrlb = OSCCTRL_DPLLCTRLB_DIV(p0div / 2 - 1);
|
||||
config_dpll(p0mul, p0ctrlb | OSCCTRL_DPLLCTRLB_REFCLK(1));
|
||||
|
||||
// Switch main clock to 48Mhz PLL
|
||||
gen_clock(CLKGEN_MAIN, GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DPLL96M_Val));
|
||||
}
|
||||
|
||||
|
||||
#if CONFIG_CLOCK_REF_X25M
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_crystal", "PA14,PA15");
|
||||
#endif
|
||||
|
||||
// Initialize the clocks using an external 25M crystal
|
||||
static void
|
||||
clock_init_25m(void)
|
||||
{
|
||||
// Enable XOSC1
|
||||
uint32_t freq_xosc = 25000000;
|
||||
uint32_t val = (OSCCTRL_XOSCCTRL_ENABLE | OSCCTRL_XOSCCTRL_XTALEN
|
||||
| OSCCTRL_XOSCCTRL_GAIN(4) | OSCCTRL_XOSCCTRL_AMPGC);
|
||||
OSCCTRL->XOSCCTRL.reg = val;
|
||||
while (!(OSCCTRL->STATUS.reg & OSCCTRL_STATUS_XOSCRDY))
|
||||
;
|
||||
|
||||
// Generate 48Mhz clock on PLL (with XOSC as reference)
|
||||
uint32_t p0div = 50, p0mul = DIV_ROUND_CLOSEST(FREQ_MAIN, freq_xosc/p0div);
|
||||
uint32_t p0ctrlb = OSCCTRL_DPLLCTRLB_DIV(p0div / 2 - 1);
|
||||
config_dpll(p0mul, p0ctrlb | OSCCTRL_DPLLCTRLB_REFCLK(1));
|
||||
|
||||
// Switch main clock to 48Mhz PLL
|
||||
gen_clock(CLKGEN_MAIN, GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DPLL96M_Val));
|
||||
}
|
||||
|
||||
void
|
||||
SystemInit(void)
|
||||
{
|
||||
// Set NVM wait states for 48MHz. This might need to be set higher if
|
||||
// running at a lower voltage.
|
||||
NVMCTRL->CTRLB.reg |= (NVMCTRL_CTRLB_SLEEPPRM_WAKEUPINSTANT
|
||||
| NVMCTRL_CTRLB_RWS(2));
|
||||
|
||||
OSCCTRL->OSC48MDIV.reg = OSCCTRL_OSC48MDIV_DIV(0);
|
||||
while (OSCCTRL->OSC48MSYNCBUSY.reg & OSCCTRL_OSC48MSYNCBUSY_OSC48MDIV)
|
||||
;
|
||||
|
||||
// Reset GCLK
|
||||
GCLK->CTRLA.reg = GCLK_CTRLA_SWRST;
|
||||
while (GCLK->SYNCBUSY.reg & GCLK_SYNCBUSY_SWRST)
|
||||
;
|
||||
|
||||
// Init clocks
|
||||
if (CONFIG_CLOCK_REF_X12M)
|
||||
clock_init_12m();
|
||||
else
|
||||
clock_init_25m();
|
||||
}
|
|
@ -18,7 +18,11 @@ DECL_TASK(watchdog_reset);
|
|||
void
|
||||
watchdog_init(void)
|
||||
{
|
||||
#if CONFIG_MACH_SAMC21
|
||||
WDT->CONFIG.reg = WDT_CONFIG_PER_CYC512; // 500ms timeout
|
||||
#elif CONFIG_MACH_SAMX5
|
||||
WDT->CONFIG.reg = WDT_CONFIG_PER(6); // 500ms timeout
|
||||
#endif
|
||||
WDT->CTRLA.reg = WDT_CTRLA_ENABLE;
|
||||
}
|
||||
DECL_INIT(watchdog_init);
|
||||
|
|
|
@ -64,7 +64,7 @@ struct sercom_pad {
|
|||
};
|
||||
|
||||
static const struct sercom_pad sercom_pads[] = {
|
||||
#if CONFIG_MACH_SAMD21
|
||||
#if CONFIG_MACH_SAMX2
|
||||
{ 0, GPIO('A', 8), 0, 'C'},
|
||||
{ 0, GPIO('A', 9), 1, 'C'},
|
||||
{ 0, GPIO('A', 10), 2, 'C'},
|
||||
|
@ -326,7 +326,7 @@ struct sercom_spi_map {
|
|||
static const struct sercom_spi_map sercom_spi[] = {
|
||||
{ 0, 1, 0 },
|
||||
{ 3, 1, 2 },
|
||||
#if CONFIG_MACH_SAMD21
|
||||
#if CONFIG_MACH_SAMX2
|
||||
{ 2, 3, 1 },
|
||||
{ 0, 3, 3 },
|
||||
#endif
|
||||
|
|
|
@ -11,19 +11,40 @@
|
|||
#include "internal.h" // enable_pclock
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
#if CONFIG_MACH_SAMC21
|
||||
#define TCp TC0
|
||||
#define TCp_IRQn TC0_IRQn
|
||||
#define TCp_GCLK_ID TC0_GCLK_ID
|
||||
#define ID_TCp ID_TC0
|
||||
#define TCd_GCLK_ID TC1_GCLK_ID
|
||||
#define ID_TCd ID_TC1
|
||||
#else
|
||||
#define TCp TC4
|
||||
#define TCp_IRQn TC4_IRQn
|
||||
#define TCp_GCLK_ID TC4_GCLK_ID
|
||||
#define ID_TCp ID_TC4
|
||||
#define TCd_GCLK_ID TC3_GCLK_ID
|
||||
#define ID_TCd ID_TC3
|
||||
#endif
|
||||
|
||||
// Set the next irq time
|
||||
static void
|
||||
timer_set(uint32_t value)
|
||||
{
|
||||
TC4->COUNT32.CC[0].reg = value;
|
||||
TC4->COUNT32.INTFLAG.reg = TC_INTFLAG_MC0;
|
||||
TCp->COUNT32.CC[0].reg = value;
|
||||
TCp->COUNT32.INTFLAG.reg = TC_INTFLAG_MC0;
|
||||
}
|
||||
|
||||
// Return the current time (in absolute clock ticks).
|
||||
uint32_t
|
||||
timer_read_time(void)
|
||||
{
|
||||
return TC4->COUNT32.COUNT.reg;
|
||||
#if CONFIG_MACH_SAMC21
|
||||
TCp->COUNT32.CTRLBSET.reg |= TC_CTRLBSET_CMD(TC_CTRLBCLR_CMD_READSYNC_Val);
|
||||
while (TCp->COUNT32.SYNCBUSY.reg & TC_SYNCBUSY_COUNT)
|
||||
;
|
||||
#endif
|
||||
return TCp->COUNT32.COUNT.reg;
|
||||
}
|
||||
|
||||
// Activate timer dispatch as soon as possible
|
||||
|
@ -35,7 +56,7 @@ timer_kick(void)
|
|||
|
||||
// IRQ handler
|
||||
void __aligned(16) // aligning helps stabilize perf benchmarks
|
||||
TC4_Handler(void)
|
||||
TCp_Handler(void)
|
||||
{
|
||||
irq_disable();
|
||||
uint32_t next = timer_dispatch_many();
|
||||
|
@ -47,15 +68,15 @@ void
|
|||
timer_init(void)
|
||||
{
|
||||
// Supply power and clock to the timer
|
||||
enable_pclock(TC3_GCLK_ID, ID_TC3);
|
||||
enable_pclock(TC4_GCLK_ID, ID_TC4);
|
||||
enable_pclock(TCd_GCLK_ID, ID_TCd);
|
||||
enable_pclock(TCp_GCLK_ID, ID_TCp);
|
||||
|
||||
// Configure the timer
|
||||
TcCount32 *tc = &TC4->COUNT32;
|
||||
TcCount32 *tc = &TCp->COUNT32;
|
||||
irqstatus_t flag = irq_save();
|
||||
tc->CTRLA.reg = 0;
|
||||
tc->CTRLA.reg = TC_CTRLA_MODE_COUNT32;
|
||||
armcm_enable_irq(TC4_Handler, TC4_IRQn, 2);
|
||||
armcm_enable_irq(TCp_Handler, TCp_IRQn, 2);
|
||||
tc->INTENSET.reg = TC_INTENSET_MC0;
|
||||
tc->COUNT.reg = 0;
|
||||
timer_kick();
|
||||
|
|
Loading…
Reference in New Issue