aboutsummaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
authorKevin O'Connor <kevin@koconnor.net>2016-06-14 14:27:30 -0400
committerKevin O'Connor <kevin@koconnor.net>2016-06-14 14:27:30 -0400
commitcc62a3dbf387dffe2d7e836c64cb5f5169971f05 (patch)
tree2ac823250c391a4883e7374616adf6d8eba33982
parent31c04261c14b7ab7cca2d191d294c3efa326c8f1 (diff)
downloadkutter-cc62a3dbf387dffe2d7e836c64cb5f5169971f05.tar.gz
kutter-cc62a3dbf387dffe2d7e836c64cb5f5169971f05.tar.xz
kutter-cc62a3dbf387dffe2d7e836c64cb5f5169971f05.zip
sam3x8e: Add initial support for Arduino Due boards
This adds basic support for running on the Atmel SAM3x8e micro-controllers that are found in the Arudino Due boards. Signed-off-by: Kevin O'Connor <kevin@koconnor.net>
-rw-r--r--klippy/pins.py13
-rw-r--r--src/Kconfig6
-rw-r--r--src/sam3x8e/Kconfig25
-rw-r--r--src/sam3x8e/Makefile28
-rw-r--r--src/sam3x8e/gpio.c115
-rw-r--r--src/sam3x8e/gpio.h23
-rw-r--r--src/sam3x8e/irq.h26
-rw-r--r--src/sam3x8e/main.c88
-rw-r--r--src/sam3x8e/serial.c148
-rw-r--r--src/sam3x8e/timer.c142
10 files changed, 606 insertions, 8 deletions
diff --git a/klippy/pins.py b/klippy/pins.py
index d2d884d1..d41d9cd6 100644
--- a/klippy/pins.py
+++ b/klippy/pins.py
@@ -6,23 +6,24 @@
import re
-def avr_pins(port_count):
+def port_pins(port_count, bit_count=8):
pins = {}
for port in range(port_count):
portchr = chr(65 + port)
if portchr == 'I':
continue
- for portbit in range(8):
- pins['P%c%d' % (portchr, portbit)] = port * 8 + portbit
+ for portbit in range(bit_count):
+ pins['P%c%d' % (portchr, portbit)] = port * bit_count + portbit
return pins
-PINS_atmega164 = avr_pins(4)
-PINS_atmega1280 = avr_pins(12)
+PINS_atmega164 = port_pins(4)
+PINS_atmega1280 = port_pins(12)
MCU_PINS = {
"atmega168": PINS_atmega164, "atmega644p": PINS_atmega164,
- "at90usb1286": avr_pins(5),
+ "at90usb1286": port_pins(5),
"atmega1280": PINS_atmega1280, "atmega2560": PINS_atmega1280,
+ "sam3x8e": port_pins(4, 32)
}
def mcu_to_pins(mcu):
diff --git a/src/Kconfig b/src/Kconfig
index 1a326d06..070d4495 100644
--- a/src/Kconfig
+++ b/src/Kconfig
@@ -6,11 +6,14 @@ choice
prompt "Micro-controller Architecture"
config MACH_AVR
bool "Atmega AVR"
+ config MACH_SAM3X8E
+ bool "SAM3x8e (Arduino Due)"
config MACH_SIMU
bool "Host simulator"
endchoice
source "src/avr/Kconfig"
+source "src/sam3x8e/Kconfig"
source "src/simulator/Kconfig"
# The HAVE_GPIO_x options allow boards to disable support for some
@@ -35,5 +38,4 @@ config NO_UNSTEP_DELAY
config INLINE_STEPPER_HACK
# Enables gcc to inline stepper_event() into the main timer irq handler
bool
- default y if MACH_AVR
- default n
+ default y
diff --git a/src/sam3x8e/Kconfig b/src/sam3x8e/Kconfig
new file mode 100644
index 00000000..2edc8f7c
--- /dev/null
+++ b/src/sam3x8e/Kconfig
@@ -0,0 +1,25 @@
+# Kconfig settings for SAM3x8e processors
+
+if MACH_SAM3X8E
+
+config BOARD_DIRECTORY
+ string
+ default "sam3x8e"
+
+config MCU
+ string
+ default "sam3x8e"
+
+config CLOCK_FREQ
+ int
+ default 42000000 # 84000000/2
+
+config SERIAL
+ bool
+ default y
+config SERIAL_BAUD
+ depends on SERIAL
+ int "Baud rate for serial port"
+ default 250000
+
+endif
diff --git a/src/sam3x8e/Makefile b/src/sam3x8e/Makefile
new file mode 100644
index 00000000..48acfb5c
--- /dev/null
+++ b/src/sam3x8e/Makefile
@@ -0,0 +1,28 @@
+# Additional sam3x8e build rules
+
+# Setup the toolchain
+CROSS_PREFIX=arm-none-eabi-
+
+dirs-y += src/sam3x8e src/generic
+dirs-y += lib/cmsis-sam3x8e/source lib/cmsis-sam3x8e/source/gcc
+
+CFLAGS-y += -mthumb -mcpu=cortex-m3
+CFLAGS-y += -Ilib/cmsis-sam3x8e/include -Ilib/cmsis-sam3x8e/cmsis-include
+CFLAGS-y += -D__SAM3X8E__
+
+LDFLAGS-y += -Llib/cmsis-sam3x8e/source/gcc
+LDFLAGS-y += -T lib/cmsis-sam3x8e/source/gcc/sam3x8e_flash.ld
+LDFLAGS-y += --specs=nano.specs --specs=nosys.specs
+
+# Add source files
+src-y += sam3x8e/main.c sam3x8e/timer.c sam3x8e/gpio.c generic/crc16_ccitt.c
+src-y += ../lib/cmsis-sam3x8e/source/system_sam3xa.c
+src-y += ../lib/cmsis-sam3x8e/source/gcc/startup_sam3xa.c
+src-$(CONFIG_SERIAL) += sam3x8e/serial.c
+
+# Build the additional hex output file
+target-y += $(OUT)klipper.bin
+
+$(OUT)klipper.bin: $(OUT)klipper.elf
+ @echo " Creating hex file $@"
+ $(Q)$(OBJCOPY) -O binary $< $@
diff --git a/src/sam3x8e/gpio.c b/src/sam3x8e/gpio.c
new file mode 100644
index 00000000..78fb0f05
--- /dev/null
+++ b/src/sam3x8e/gpio.c
@@ -0,0 +1,115 @@
+// GPIO functions on sam3x8e
+//
+// Copyright (C) 2016 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include <stdint.h> // uint32_t
+#include "command.h" // shutdown
+#include "compiler.h" // ARRAY_SIZE
+#include "gpio.h" // gpio_out_setup
+#include "irq.h" // irq_save
+#include "sam3x8e.h" // Pio
+#include "sched.h" // sched_shutdown
+
+
+/****************************************************************
+ * Pin mappings
+ ****************************************************************/
+
+#define GPIO(PORT, NUM) (((PORT)-'A') * 32 + (NUM))
+#define GPIO2PORT(PIN) ((PIN) / 32)
+#define GPIO2BIT(PIN) (1<<((PIN) % 32))
+
+static Pio * const digital_regs[] = {
+ PIOA, PIOB, PIOC, PIOD
+};
+
+
+/****************************************************************
+ * gpio functions
+ ****************************************************************/
+
+void
+gpio_peripheral(char bank, uint32_t bit, char ptype, uint32_t pull_up)
+{
+ Pio *regs = digital_regs[bank - 'A'];
+ if (ptype == 'A')
+ regs->PIO_ABSR &= ~bit;
+ else
+ regs->PIO_ABSR |= bit;
+ if (pull_up)
+ regs->PIO_PUER = bit;
+ else
+ regs->PIO_PUDR = bit;
+ regs->PIO_PDR = bit;
+}
+
+
+struct gpio_out
+gpio_out_setup(uint8_t pin, uint8_t val)
+{
+ if (GPIO2PORT(pin) >= ARRAY_SIZE(digital_regs))
+ goto fail;
+ Pio *regs = digital_regs[GPIO2PORT(pin)];
+ uint32_t bit = GPIO2BIT(pin);
+ irqstatus_t flag = irq_save();
+ if (val)
+ regs->PIO_SODR = bit;
+ else
+ regs->PIO_CODR = bit;
+ regs->PIO_OER = bit;
+ regs->PIO_OWER = bit;
+ regs->PIO_PER = bit;
+ irq_restore(flag);
+ return (struct gpio_out){ .regs=regs, .bit=bit };
+fail:
+ shutdown("Not an output pin");
+}
+
+void
+gpio_out_toggle(struct gpio_out g)
+{
+ Pio *regs = g.regs;
+ regs->PIO_ODSR ^= g.bit;
+}
+
+void
+gpio_out_write(struct gpio_out g, uint8_t val)
+{
+ Pio *regs = g.regs;
+ if (val)
+ regs->PIO_SODR = g.bit;
+ else
+ regs->PIO_CODR = g.bit;
+}
+
+
+struct gpio_in
+gpio_in_setup(uint8_t pin, int8_t pull_up)
+{
+ if (GPIO2PORT(pin) >= ARRAY_SIZE(digital_regs))
+ goto fail;
+ uint32_t port = GPIO2PORT(pin);
+ Pio *regs = digital_regs[port];
+ uint32_t bit = GPIO2BIT(pin);
+ irqstatus_t flag = irq_save();
+ PMC->PMC_PCER0 = 1 << (ID_PIOA + port);
+ if (pull_up)
+ regs->PIO_PUER = bit;
+ else
+ regs->PIO_PUDR = bit;
+ regs->PIO_ODR = bit;
+ regs->PIO_PER = bit;
+ irq_restore(flag);
+ return (struct gpio_in){ .regs=regs, .bit=bit };
+fail:
+ shutdown("Not an output pin");
+}
+
+uint8_t
+gpio_in_read(struct gpio_in g)
+{
+ Pio *regs = g.regs;
+ return !!(regs->PIO_PDSR & g.bit);
+}
diff --git a/src/sam3x8e/gpio.h b/src/sam3x8e/gpio.h
new file mode 100644
index 00000000..d8fdf569
--- /dev/null
+++ b/src/sam3x8e/gpio.h
@@ -0,0 +1,23 @@
+#ifndef __SAM3X8E_GPIO_H
+#define __SAM3X8E_GPIO_H
+
+#include <stdint.h>
+
+void gpio_peripheral(char bank, uint32_t bit, char ptype, uint32_t pull_up);
+
+struct gpio_out {
+ void *regs;
+ uint32_t bit;
+};
+struct gpio_out gpio_out_setup(uint8_t pin, uint8_t val);
+void gpio_out_toggle(struct gpio_out g);
+void gpio_out_write(struct gpio_out g, uint8_t val);
+
+struct gpio_in {
+ void *regs;
+ uint32_t bit;
+};
+struct gpio_in gpio_in_setup(uint8_t pin, int8_t pull_up);
+uint8_t gpio_in_read(struct gpio_in g);
+
+#endif // gpio.h
diff --git a/src/sam3x8e/irq.h b/src/sam3x8e/irq.h
new file mode 100644
index 00000000..26303195
--- /dev/null
+++ b/src/sam3x8e/irq.h
@@ -0,0 +1,26 @@
+#ifndef __SAM3X8E_IRQ_H
+#define __SAM3X8E_IRQ_H
+// Definitions for irq enable/disable on ARM Cortex-M
+
+static inline void irq_disable(void) {
+ asm volatile("cpsid i" ::: "memory");
+}
+
+static inline void irq_enable(void) {
+ asm volatile("cpsie i" ::: "memory");
+}
+
+typedef unsigned long irqstatus_t;
+
+static inline irqstatus_t irq_save(void) {
+ irqstatus_t flag;
+ asm volatile("mrs %0, primask" : "=r" (flag) :: "memory");
+ irq_disable();
+ return flag;
+}
+
+static inline void irq_restore(irqstatus_t flag) {
+ asm volatile("msr primask, %0" :: "r" (flag) : "memory");
+}
+
+#endif // irq.h
diff --git a/src/sam3x8e/main.c b/src/sam3x8e/main.c
new file mode 100644
index 00000000..ca002c91
--- /dev/null
+++ b/src/sam3x8e/main.c
@@ -0,0 +1,88 @@
+// Main starting point for SAM3x8e boards.
+//
+// Copyright (C) 2016 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "board/misc.h" // console_get_input
+#include "sam3x8e.h" // WDT
+#include "sched.h" // sched_main
+
+
+/****************************************************************
+ * watchdog handler
+ ****************************************************************/
+
+static void
+watchdog_reset(void)
+{
+ WDT->WDT_CR = 0xA5000001;
+}
+DECL_TASK(watchdog_reset);
+
+static void
+watchdog_init(void)
+{
+ uint32_t timeout = 32768 / 2; // 500ms timeout
+ WDT->WDT_MR = WDT_MR_WDRSTEN | WDT_MR_WDV(timeout) | WDT_MR_WDD(timeout);
+}
+DECL_INIT(watchdog_init);
+
+
+/****************************************************************
+ * irq clearing on fault
+ ****************************************************************/
+
+// Clear the active irq if a shutdown happened in an irq handler
+static void
+clear_active_irq(void)
+{
+ uint32_t psr;
+ asm volatile("mrs %0, psr" : "=r" (psr));
+ if (!(psr & 0x1ff))
+ // Shutdown did not occur in an irq - nothing to do.
+ return;
+ // Clear active irq status
+ psr &= ~0x1ff;
+ psr |= 1<<24; // T-bit
+ uint32_t temp;
+ asm volatile(
+ " push { %1 }\n"
+ " adr %0, 1f\n"
+ " push { %0 }\n"
+ " push { r0, r1, r2, r3, r12, lr }\n"
+ " bx %2\n"
+ "1:\n"
+ : "=&r"(temp) : "r"(psr), "r"(0xfffffff9));
+}
+DECL_SHUTDOWN(clear_active_irq);
+
+
+/****************************************************************
+ * misc functions
+ ****************************************************************/
+
+size_t
+alloc_maxsize(size_t reqsize)
+{
+ return reqsize;
+}
+
+void * __visible
+_sbrk(int nbytes)
+{
+ extern char _end;
+ static void *heap_ptr = (void *)&_end;
+ void *pos = heap_ptr;
+ heap_ptr = pos + nbytes;
+ return pos;
+}
+
+// Main entry point
+int
+main(void)
+{
+ SystemInit();
+ sched_main();
+ return 0;
+}
diff --git a/src/sam3x8e/serial.c b/src/sam3x8e/serial.c
new file mode 100644
index 00000000..42b92efe
--- /dev/null
+++ b/src/sam3x8e/serial.c
@@ -0,0 +1,148 @@
+// sam3x8e serial port
+//
+// Copyright (C) 2016 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include <string.h> // memmove
+#include "autoconf.h" // CONFIG_SERIAL_BAUD
+#include "board/gpio.h" // gpio_peripheral
+#include "board/io.h" // readb
+#include "board/misc.h" // console_get_input
+#include "sam3x8e.h" // UART
+#include "sched.h" // DECL_INIT
+#include "irq.h" // irq_save
+
+#define SERIAL_BUFFER_SIZE 96
+static char receive_buf[SERIAL_BUFFER_SIZE];
+static uint32_t receive_pos;
+static char transmit_buf[SERIAL_BUFFER_SIZE];
+static uint32_t transmit_pos, transmit_max;
+
+
+/****************************************************************
+ * Serial hardware
+ ****************************************************************/
+
+static void
+serial_init(void)
+{
+ gpio_peripheral('A', PIO_PA8A_URXD, 'A', 1);
+ gpio_peripheral('A', PIO_PA9A_UTXD, 'A', 0);
+
+ // Reset uart
+ PMC->PMC_PCER0 = 1 << ID_UART;
+ UART->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS;
+ UART->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS;
+ UART->UART_IDR = 0xFFFFFFFF;
+
+ // Enable uart
+ UART->UART_MR = (US_MR_CHRL_8_BIT | US_MR_NBSTOP_1_BIT | UART_MR_PAR_NO
+ | UART_MR_CHMODE_NORMAL);
+ UART->UART_BRGR = SystemCoreClock / (16 * CONFIG_SERIAL_BAUD);
+ UART->UART_IER = UART_IER_RXRDY;
+ NVIC_EnableIRQ(UART_IRQn);
+ NVIC_SetPriority(UART_IRQn, 0);
+ UART->UART_CR = UART_CR_RXEN | UART_CR_TXEN;
+}
+DECL_INIT(serial_init);
+
+void __visible
+UART_Handler(void)
+{
+ uint32_t status = UART->UART_SR;
+ if (status & UART_SR_RXRDY) {
+ uint8_t data = UART->UART_RHR;
+ if (receive_pos >= sizeof(receive_buf))
+ // Serial overflow - ignore it as crc error will force retransmit
+ return;
+ receive_buf[receive_pos++] = data;
+ return;
+ }
+ if (status & UART_SR_TXRDY) {
+ if (transmit_pos >= transmit_max)
+ UART->UART_IDR = UART_IDR_TXRDY;
+ else
+ UART->UART_THR = transmit_buf[transmit_pos++];
+ }
+}
+
+// Enable tx interrupts
+static void
+enable_tx_irq(void)
+{
+ UART->UART_IER = UART_IDR_TXRDY;
+}
+
+
+/****************************************************************
+ * Console access functions
+ ****************************************************************/
+
+// Return a buffer (and length) containing any incoming messages
+char *
+console_get_input(uint8_t *plen)
+{
+ *plen = readb(&receive_pos);
+ return receive_buf;
+}
+
+// Remove from the receive buffer the given number of bytes
+void
+console_pop_input(uint8_t len)
+{
+ uint32_t copied = 0;
+ for (;;) {
+ uint32_t rpos = readb(&receive_pos);
+ uint32_t needcopy = rpos - len;
+ if (needcopy) {
+ memmove(&receive_buf[copied], &receive_buf[copied + len]
+ , needcopy - copied);
+ copied = needcopy;
+ }
+ irqstatus_t flag = irq_save();
+ if (rpos != readb(&receive_pos)) {
+ // Raced with irq handler - retry
+ irq_restore(flag);
+ continue;
+ }
+ receive_pos = needcopy;
+ irq_restore(flag);
+ break;
+ }
+}
+
+// Return an output buffer that the caller may fill with transmit messages
+char *
+console_get_output(uint8_t len)
+{
+ uint32_t tpos = readb(&transmit_pos), tmax = readb(&transmit_max);
+ if (tpos == tmax) {
+ tpos = tmax = 0;
+ writeb(&transmit_max, 0);
+ writeb(&transmit_pos, 0);
+ }
+ if (tmax + len <= sizeof(transmit_buf))
+ return &transmit_buf[tmax];
+ if (tmax - tpos + len > sizeof(transmit_buf))
+ return NULL;
+ // Disable TX irq and move buffer
+ writeb(&transmit_max, 0);
+ barrier();
+ tpos = readb(&transmit_pos);
+ tmax -= tpos;
+ memmove(&transmit_buf[0], &transmit_buf[tpos], tmax);
+ writeb(&transmit_pos, 0);
+ barrier();
+ writeb(&transmit_max, tmax);
+ enable_tx_irq();
+ return &transmit_buf[tmax];
+}
+
+// Accept the given number of bytes added to the transmit buffer
+void
+console_push_output(uint8_t len)
+{
+ writeb(&transmit_max, readb(&transmit_max) + len);
+ enable_tx_irq();
+}
diff --git a/src/sam3x8e/timer.c b/src/sam3x8e/timer.c
new file mode 100644
index 00000000..e473be9f
--- /dev/null
+++ b/src/sam3x8e/timer.c
@@ -0,0 +1,142 @@
+// SAM3x8e timer interrupt scheduling
+//
+// Copyright (C) 2016 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 "board/misc.h" // timer_from_us
+#include "command.h" // shutdown
+#include "irq.h" // irq_disable
+#include "sam3x8e.h" // TC0
+#include "sched.h" // sched_timer_kick
+
+
+/****************************************************************
+ * Low level timer code
+ ****************************************************************/
+
+// Return the number of clock ticks for a given number of microseconds
+uint32_t
+timer_from_us(uint32_t us)
+{
+ return us * (CONFIG_CLOCK_FREQ / 1000000);
+}
+
+// IRQ handler
+void __visible
+TC0_Handler(void)
+{
+ TC0->TC_CHANNEL[0].TC_SR; // clear irq pending
+ irq_disable();
+ sched_timer_kick();
+ irq_enable();
+}
+
+static void
+timer_set(uint32_t value)
+{
+ TC0->TC_CHANNEL[0].TC_RA = value;
+}
+
+static void
+timer_init(void)
+{
+ TcChannel *tc = &TC0->TC_CHANNEL[0];
+ // Reset the timer
+ tc->TC_CCR = TC_CCR_CLKDIS;
+ tc->TC_IDR = 0xFFFFFFFF;
+ tc->TC_SR;
+ // Enable it
+ PMC->PMC_PCER0 = 1 << ID_TC0;
+ tc->TC_CMR = TC_CMR_WAVE | TC_CMR_WAVSEL_UP | TC_CMR_TCCLKS_TIMER_CLOCK1;
+ tc->TC_IER = TC_IER_CPAS;
+ NVIC_SetPriority(TC0_IRQn, 1);
+ NVIC_EnableIRQ(TC0_IRQn);
+ timer_set(1);
+ tc->TC_CCR = TC_CCR_CLKEN | TC_CCR_SWTRG;
+}
+DECL_INIT(timer_init);
+
+// Called by main code once every millisecond. (IRQs disabled.)
+void
+timer_periodic(void)
+{
+}
+
+// Return the current time (in absolute clock ticks).
+uint32_t
+timer_read_time(void)
+{
+ return TC0->TC_CHANNEL[0].TC_CV;
+}
+
+#define TIMER_MIN_TICKS 100
+
+// Set the next timer wake time (in absolute clock ticks). Caller
+// must disable irqs. The caller should not schedule a time more than
+// a few milliseconds in the future.
+uint8_t
+timer_set_next(uint32_t next)
+{
+ uint32_t cur = timer_read_time();
+ uint32_t mintime = cur + TIMER_MIN_TICKS;
+ if (sched_is_before(mintime, next)) {
+ timer_set(next);
+ return 0;
+ }
+ timer_set(mintime);
+ return 1;
+}
+
+static uint32_t timer_repeat;
+#define TIMER_MAX_REPEAT 400
+#define TIMER_MAX_NEXT_REPEAT 150
+
+#define TIMER_MIN_TRY_TICKS timer_from_us(1)
+#define TIMER_DEFER_REPEAT_TICKS timer_from_us(2)
+
+// Similar to timer_set_next(), but wait for the given time if it is
+// in the near future.
+uint8_t
+timer_try_set_next(uint32_t next)
+{
+ uint32_t now = timer_read_time();
+ int32_t diff = next - now;
+ if (diff > (int32_t)TIMER_MIN_TRY_TICKS)
+ // Schedule next timer normally.
+ goto done;
+
+ // Next timer is in the past or near future - can't reschedule to it
+ uint32_t tr = timer_repeat-1;
+ if (likely(tr)) {
+ irq_enable();
+ timer_repeat = tr;
+ while (diff >= 0) {
+ // Next timer is in the near future - wait for time to occur
+ now = timer_read_time();
+ diff = next - now;
+ }
+ irq_disable();
+ return 0;
+ }
+
+ // Too many repeat timers from a single interrupt - force a pause
+ timer_repeat = TIMER_MAX_NEXT_REPEAT;
+ next = now + TIMER_DEFER_REPEAT_TICKS;
+ if (diff < (int32_t)(-timer_from_us(1000)))
+ goto fail;
+
+done:
+ timer_set(next);
+ return 1;
+fail:
+ shutdown("Rescheduled timer in the past");
+}
+
+static void
+timer_task(void)
+{
+ timer_repeat = TIMER_MAX_REPEAT;
+}
+DECL_TASK(timer_task);