aboutsummaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
-rw-r--r--src/Kconfig3
-rw-r--r--src/samd21/Kconfig41
-rw-r--r--src/samd21/Makefile43
-rw-r--r--src/samd21/clock.c73
-rw-r--r--src/samd21/gpio.c22
-rw-r--r--src/samd21/internal.h10
-rw-r--r--src/samd21/main.c32
-rw-r--r--src/samd21/serial.c61
-rw-r--r--src/samd21/timer.c66
9 files changed, 351 insertions, 0 deletions
diff --git a/src/Kconfig b/src/Kconfig
index 0a135637..9f598453 100644
--- a/src/Kconfig
+++ b/src/Kconfig
@@ -8,6 +8,8 @@ choice
bool "Atmega AVR"
config MACH_SAM3X8E
bool "SAM3x8e (Arduino Due)"
+ config MACH_SAMD21
+ bool "SAMD21 (Arduino Zero)"
config MACH_LPC176X
bool "LPC176x (Smoothieboard)"
config MACH_STM32F1
@@ -22,6 +24,7 @@ endchoice
source "src/avr/Kconfig"
source "src/sam3x8e/Kconfig"
+source "src/samd21/Kconfig"
source "src/lpc176x/Kconfig"
source "src/stm32f1/Kconfig"
source "src/pru/Kconfig"
diff --git a/src/samd21/Kconfig b/src/samd21/Kconfig
new file mode 100644
index 00000000..afdd3dc0
--- /dev/null
+++ b/src/samd21/Kconfig
@@ -0,0 +1,41 @@
+# Kconfig settings for SAMD21 processors
+
+if MACH_SAMD21
+
+config SAMD_SELECT
+ bool
+ default y
+
+config BOARD_DIRECTORY
+ string
+ default "samd21"
+
+config CLOCK_FREQ
+ int
+ default 48000000
+
+choice
+ prompt "Bootloader offset"
+ config FLASH_START_0000
+ bool "No bootloader"
+ config FLASH_START_2000
+ bool "2K bootloader (Arduino Zero)"
+ config FLASH_START_4000
+ bool "4K bootloader (Arduino M0)"
+endchoice
+
+config FLASH_START
+ hex
+ default 0x4000 if FLASH_START_4000
+ default 0x2000 if FLASH_START_2000
+ default 0x0000
+
+config SERIAL
+ bool
+ default y
+config SERIAL_BAUD
+ depends on SERIAL
+ int "Baud rate for serial port"
+ default 250000
+
+endif
diff --git a/src/samd21/Makefile b/src/samd21/Makefile
new file mode 100644
index 00000000..49311b0d
--- /dev/null
+++ b/src/samd21/Makefile
@@ -0,0 +1,43 @@
+# Additional samd21 build rules
+
+# Setup the toolchain
+CROSS_PREFIX=arm-none-eabi-
+
+dirs-y += src/samd21 src/generic
+dirs-y += lib/samd21/samd21a/gcc/gcc/
+
+CFLAGS += -mthumb -mcpu=cortex-m0plus
+CFLAGS += -Ilib/cmsis-core -Ilib/samd21/samd21a/include
+CFLAGS += -D__SAMD21G18A__
+
+CFLAGS_klipper.elf += -T $(OUT)samd21.ld
+CFLAGS_klipper.elf += --specs=nano.specs --specs=nosys.specs
+
+# Add source files
+src-y += samd21/main.c samd21/timer.c samd21/clock.c samd21/gpio.c
+src-y += generic/crc16_ccitt.c generic/alloc.c
+src-y += generic/armcm_irq.c generic/timer_irq.c
+src-y += ../lib/samd21/samd21a/gcc/gcc/startup_samd21.c
+src-$(CONFIG_SERIAL) += samd21/serial.c generic/serial_irq.c
+
+# Support bootloader offset address
+target-y := $(OUT)samd21.ld $(target-y)
+
+$(OUT)samd21.ld: lib/samd21/samd21a/gcc/gcc/samd21g18a_flash.ld $(OUT)board-link
+ @echo " Preprocessing $@"
+ $(Q)$(CPP) -P -MD -MT $@ -DFLASH_START=$(CONFIG_FLASH_START) $< -o $@
+
+# Build the additional hex and bin output files
+target-y += $(OUT)klipper.bin $(OUT)klipper.elf.hex
+
+$(OUT)klipper.bin: $(OUT)klipper.elf
+ @echo " Creating hex file $@"
+ $(Q)$(OBJCOPY) -O binary $< $@
+
+$(OUT)klipper.elf.hex: $(OUT)klipper.elf
+ @echo " Creating hex file $@"
+ $(Q)$(OBJCOPY) -j .text -j .relocate -O ihex $< $@
+
+flash: $(OUT)klipper.bin
+ @echo ""
+ @echo " The SAMD21 build does not currently support 'make flash'"
diff --git a/src/samd21/clock.c b/src/samd21/clock.c
new file mode 100644
index 00000000..da95ffb0
--- /dev/null
+++ b/src/samd21/clock.c
@@ -0,0 +1,73 @@
+// Code to setup peripheral clocks on the SAMD21
+//
+// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "autoconf.h" // CONFIG_CLOCK_FREQ
+#include "compiler.h" // DIV_ROUND_CLOSEST
+#include "internal.h" // enable_pclock
+#include "samd21.h" // GCLK
+
+void
+enable_pclock(uint32_t clock_id, uint32_t pmask)
+{
+ GCLK->CLKCTRL.reg = (GCLK_CLKCTRL_ID(clock_id) | GCLK_CLKCTRL_GEN_GCLK0
+ | GCLK_CLKCTRL_CLKEN);
+ while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY)
+ ;
+ PM->APBCMASK.reg |= pmask;
+}
+
+#define CLK_MAIN 0
+#define CLK_32K 1
+#define MCLK_DFLL48M 0
+
+#define CLK_32K_FREQ 32768
+
+void
+SystemInit(void)
+{
+ // Setup flash to work with 48Mhz clock
+ NVMCTRL->CTRLB.reg = NVMCTRL_CTRLB_RWS_HALF;
+
+ // Enable external 32Khz crystal
+ uint32_t val = (SYSCTRL_XOSC32K_STARTUP(6)
+ | SYSCTRL_XOSC32K_XTALEN | SYSCTRL_XOSC32K_EN32K);
+ SYSCTRL->XOSC32K.reg = val;
+ SYSCTRL->XOSC32K.reg = val | SYSCTRL_XOSC32K_ENABLE;
+ while (!(SYSCTRL->PCLKSR.reg & SYSCTRL_PCLKSR_XOSC32KRDY))
+ ;
+
+ // Reset GCLK
+ GCLK->CTRL.reg = GCLK_CTRL_SWRST;
+ while (GCLK->CTRL.reg & GCLK_CTRL_SWRST)
+ ;
+
+ // Route 32Khz clock to DFLL48M
+ GCLK->GENDIV.reg = GCLK_GENDIV_ID(CLK_32K);
+ GCLK->GENCTRL.reg = (GCLK_GENCTRL_ID(CLK_32K)
+ | GCLK_GENCTRL_SRC_XOSC32K | GCLK_GENCTRL_GENEN);
+ GCLK->CLKCTRL.reg = (GCLK_CLKCTRL_ID(MCLK_DFLL48M)
+ | GCLK_CLKCTRL_GEN(CLK_32K) | GCLK_CLKCTRL_CLKEN);
+
+ // Configure DFLL48M clock
+ SYSCTRL->DFLLCTRL.reg = 0;
+ uint32_t mul = DIV_ROUND_CLOSEST(CONFIG_CLOCK_FREQ, CLK_32K_FREQ);
+ SYSCTRL->DFLLMUL.reg = (SYSCTRL_DFLLMUL_CSTEP(31)
+ | SYSCTRL_DFLLMUL_FSTEP(511)
+ | SYSCTRL_DFLLMUL_MUL(mul));
+ SYSCTRL->DFLLCTRL.reg = (SYSCTRL_DFLLCTRL_MODE | SYSCTRL_DFLLCTRL_WAITLOCK
+ | SYSCTRL_DFLLCTRL_QLDIS
+ | SYSCTRL_DFLLCTRL_ENABLE);
+ uint32_t ready = (SYSCTRL_PCLKSR_DFLLRDY | SYSCTRL_PCLKSR_DFLLLCKC
+ | SYSCTRL_PCLKSR_DFLLLCKF);
+ while ((SYSCTRL->PCLKSR.reg & ready) != ready)
+ ;
+
+ // Switch main clock to DFLL48M clock
+ GCLK->GENDIV.reg = GCLK_GENDIV_ID(CLK_MAIN);
+ GCLK->GENCTRL.reg = (GCLK_GENCTRL_ID(CLK_MAIN)
+ | GCLK_GENCTRL_SRC_DFLL48M
+ | GCLK_GENCTRL_IDC | GCLK_GENCTRL_GENEN);
+}
diff --git a/src/samd21/gpio.c b/src/samd21/gpio.c
new file mode 100644
index 00000000..3ae51f74
--- /dev/null
+++ b/src/samd21/gpio.c
@@ -0,0 +1,22 @@
+// samd21 gpio functions
+//
+// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "internal.h" // gpio_peripheral
+#include "samd21.h" // PORT
+
+void
+gpio_peripheral(char bank, uint32_t bit, char ptype, uint32_t pull_up)
+{
+ int group = bank == 'A' ? 0 : 1;
+ PortGroup *pg = &PORT->Group[group];
+ if (ptype) {
+ volatile uint8_t *pmux = &pg->PMUX[bit/2].reg;
+ uint8_t shift = (bit & 1) ? 4 : 0, mask = ~(0xf << shift);
+ *pmux = (*pmux & mask) | ((ptype - 'A') << shift);
+ }
+ pg->PINCFG[bit].reg = ((ptype ? PORT_PINCFG_PMUXEN : 0)
+ | (pull_up ? PORT_PINCFG_PULLEN : 0));
+}
diff --git a/src/samd21/internal.h b/src/samd21/internal.h
new file mode 100644
index 00000000..34c74815
--- /dev/null
+++ b/src/samd21/internal.h
@@ -0,0 +1,10 @@
+#ifndef __SAMD21_INTERNAL_H
+#define __SAMD21_INTERNAL_H
+// Local definitions for samd21 code
+
+#include <stdint.h> // uint32_t
+
+void enable_pclock(uint32_t clock_id, uint32_t pmask);
+void gpio_peripheral(char bank, uint32_t bit, char ptype, uint32_t pull_up);
+
+#endif // internal.h
diff --git a/src/samd21/main.c b/src/samd21/main.c
new file mode 100644
index 00000000..a9da6324
--- /dev/null
+++ b/src/samd21/main.c
@@ -0,0 +1,32 @@
+// Main starting point for SAMD21 boards
+//
+// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "command.h" // DECL_CONSTANT
+#include "samd21.h" // SystemInit
+#include "sched.h" // sched_main
+
+DECL_CONSTANT(MCU, "samd21g");
+
+
+/****************************************************************
+ * misc functions
+ ****************************************************************/
+
+void
+command_reset(uint32_t *args)
+{
+ NVIC_SystemReset();
+}
+DECL_COMMAND_FLAGS(command_reset, HF_IN_SHUTDOWN, "reset");
+
+// Main entry point
+int
+main(void)
+{
+ SystemInit();
+ sched_main();
+ return 0;
+}
diff --git a/src/samd21/serial.c b/src/samd21/serial.c
new file mode 100644
index 00000000..3c321e47
--- /dev/null
+++ b/src/samd21/serial.c
@@ -0,0 +1,61 @@
+// samd21 serial port
+//
+// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "autoconf.h" // CONFIG_SERIAL_BAUD
+#include "board/serial_irq.h" // serial_rx_data
+#include "internal.h" // enable_pclock
+#include "samd21.h" // SERCOM0
+#include "sched.h" // DECL_INIT
+
+void
+serial_init(void)
+{
+ // Enable serial clock
+ enable_pclock(SERCOM0_GCLK_ID_CORE, PM_APBCMASK_SERCOM0);
+ // Enable pins
+ gpio_peripheral('A', 10, 'C', 0);
+ gpio_peripheral('A', 11, 'C', 0);
+ // Configure serial
+ SercomUsart *su = &SERCOM0->USART;
+ su->CTRLA.reg = 0;
+ uint32_t areg = (SERCOM_USART_CTRLA_MODE_USART_INT_CLK
+ | SERCOM_USART_CTRLA_DORD
+ | SERCOM_USART_CTRLA_SAMPR(1)
+ | SERCOM_USART_CTRLA_TXPO(1)
+ | SERCOM_USART_CTRLA_RXPO(3));
+ su->CTRLA.reg = areg;
+ su->CTRLB.reg = SERCOM_USART_CTRLB_TXEN | SERCOM_USART_CTRLB_RXEN;
+ uint32_t baud8 = CONFIG_CLOCK_FREQ / (2 * CONFIG_SERIAL_BAUD);
+ su->BAUD.reg = (SERCOM_USART_BAUD_FRAC_BAUD(baud8 / 8)
+ | SERCOM_USART_BAUD_FRAC_FP(baud8 % 8));
+ NVIC_SetPriority(SERCOM0_IRQn, 0);
+ NVIC_EnableIRQ(SERCOM0_IRQn);
+ su->INTENSET.reg = SERCOM_USART_INTENSET_RXC;
+ su->CTRLA.reg = areg | SERCOM_USART_CTRLA_ENABLE;
+}
+DECL_INIT(serial_init);
+
+void __visible
+SERCOM0_Handler(void)
+{
+ uint32_t status = SERCOM0->USART.INTFLAG.reg;
+ if (status & SERCOM_USART_INTFLAG_RXC)
+ serial_rx_byte(SERCOM0->USART.DATA.reg);
+ if (status & SERCOM_USART_INTFLAG_DRE) {
+ uint8_t data;
+ int ret = serial_get_tx_byte(&data);
+ if (ret)
+ SERCOM0->USART.INTENCLR.reg = SERCOM_USART_INTENSET_DRE;
+ else
+ SERCOM0->USART.DATA.reg = data;
+ }
+}
+
+void
+serial_enable_tx_irq(void)
+{
+ SERCOM0->USART.INTENSET.reg = SERCOM_USART_INTENSET_DRE;
+}
diff --git a/src/samd21/timer.c b/src/samd21/timer.c
new file mode 100644
index 00000000..a69979e3
--- /dev/null
+++ b/src/samd21/timer.c
@@ -0,0 +1,66 @@
+// SAMD21 timer interrupt scheduling
+//
+// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "board/irq.h" // irq_disable
+#include "board/misc.h" // timer_read_time
+#include "board/timer_irq.h" // timer_dispatch_many
+#include "internal.h" // enable_pclock
+#include "samd21.h" // TC4
+#include "sched.h" // DECL_INIT
+
+// 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;
+}
+
+// Return the current time (in absolute clock ticks).
+uint32_t
+timer_read_time(void)
+{
+ return TC4->COUNT32.COUNT.reg;
+}
+
+// Activate timer dispatch as soon as possible
+void
+timer_kick(void)
+{
+ timer_set(timer_read_time() + 50);
+}
+
+void
+timer_init(void)
+{
+ // Supply power and clock to the timer
+ enable_pclock(TC3_GCLK_ID, PM_APBCMASK_TC3);
+ enable_pclock(TC4_GCLK_ID, PM_APBCMASK_TC4);
+
+ // Configure the timer
+ TcCount32 *tc = &TC4->COUNT32;
+ irqstatus_t flag = irq_save();
+ tc->CTRLA.reg = 0;
+ tc->CTRLA.reg = TC_CTRLA_MODE_COUNT32;
+ NVIC_SetPriority(TC4_IRQn, 2);
+ NVIC_EnableIRQ(TC4_IRQn);
+ TC4->COUNT32.INTENSET.reg = TC_INTENSET_MC0;
+ TC4->COUNT32.COUNT.reg = 0;
+ timer_kick();
+ tc->CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_ENABLE;
+ irq_restore(flag);
+}
+DECL_INIT(timer_init);
+
+// IRQ handler
+void __visible __aligned(16) // aligning helps stabilize perf benchmarks
+TC4_Handler(void)
+{
+ irq_disable();
+ uint32_t next = timer_dispatch_many();
+ timer_set(next);
+ irq_enable();
+}