sam4e8e: Add the SAM4e8e port

This can be flashed to e.g. the duet wifi using bossac. It requires a
later version as is currently included in the klipper repo (1.8
vs. 1.2). Comms are currently via UART0 only, USB serial is still TBD

Signed-off-by: Florian Heilmann <Florian.Heilmann@gmx.net>
This commit is contained in:
Florian Heilmann
2018-08-07 01:03:54 +02:00
committed by Kevin O'Connor
parent d15c106288
commit 64e6d85898
16 changed files with 858 additions and 5 deletions

View File

@@ -98,9 +98,10 @@ represent total number of steps per second on the micro-controller.
| Arduino Due (ARM SAM3X8E) | 382K | 337K |
| Smoothieboard (ARM LPC1768) | 385K | 385K |
| Smoothieboard (ARM LPC1769) | 462K | 462K |
| Duet Wifi/Eth (ARM SAM4E8E) | 545K | 545K |
| Beaglebone PRU | 689K | 689K |
On AVR platforms, the highest achievable step rate is with just one
stepper stepping. On the STM32F103, Arduino Zero, and Due, the highest
step rate is with two simultaneous steppers stepping. On the PRU and
step rate is with two simultaneous steppers stepping. On the PRU, SAM4E8E and
LPC176x, the highest step rate is with three simultaneous steppers.

View File

@@ -41,6 +41,7 @@ MCU_PINS = {
"atmega1280": port_pins(12), "atmega2560": port_pins(12),
"sam3x8e": port_pins(4, 32),
"samd21g": port_pins(2, 32),
"sam4e8e" : port_pins(5,32),
"stm32f103": port_pins(5, 16),
"lpc176x": lpc_pins(),
"pru": beaglebone_pins(),

View File

@@ -25,6 +25,14 @@ version 1.3.304 (extracted on 20180725). It has been modified to
compile with gcc's LTO feature and to work with chips that have a
bootloader. See samd21.patch for the modifications.
The cmsis-sam4e8e directory contains code from the
Atmel.SAM4E_DFP.1.1.57.atpack zip file found at:
http://packs.download.atmel.com/
version 1.1.57 (extracted on 20180806). It has been modified to compile
with gcc's LTO feature. Also, some AFEC register RW accesses have been modified
to comply with the SAM4E datasheet. Finally, the interrupt vector table has
been slightly modified to allow the code to run. See cmsis-sam4e8e.patch for the modifications.
The lpc176x directory contains code from the mbed project:
https://github.com/ARMmbed/mbed-os
version mbed-os-5.8.3 (c05d72c3c005fbb7e92c3994c32bda45218ae7fe).

View File

@@ -0,0 +1,56 @@
--- a/lib/cmsis-sam4e/gcc/gcc/startup_sam4e.c
+++ b/lib/cmsis-sam4e/gcc/gcc/startup_sam4e.c
@@ -104,7 +105,7 @@ void GMAC_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler")));
void UART1_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler")));
/* Exception Table */
-__attribute__ ((section(".vectors")))
+__attribute__ ((section(".vectors"))) __attribute__((externally_visible))
const DeviceVectors exception_table = {
/* Configure Initial Stack Pointer, using linker-generated symbols */
@@ -135,6 +136,7 @@ const DeviceVectors exception_table = {
(void*) PMC_Handler, /* 5 Power Management Controller */
(void*) EFC_Handler, /* 6 Enhanced Embedded Flash Controller */
(void*) UART0_Handler, /* 7 UART 0 */
+ (void*) Dummy_Handler, /* 8 Dummy */
(void*) PIOA_Handler, /* 9 Parallel I/O Controller A */
(void*) PIOB_Handler, /* 10 Parallel I/O Controller B */
(void*) PIOC_Handler, /* 11 Parallel I/O Controller C */
@@ -166,6 +168,10 @@ const DeviceVectors exception_table = {
(void*) CAN0_Handler, /* 37 CAN0 */
(void*) CAN1_Handler, /* 38 CAN1 */
(void*) AES_Handler, /* 39 AES */
+ (void*) Dummy_Handler, /* 40 Dummy */
+ (void*) Dummy_Handler, /* 41 Dummy */
+ (void*) Dummy_Handler, /* 42 Dummy */
+ (void*) Dummy_Handler, /* 43 Dummy */
(void*) GMAC_Handler, /* 44 EMAC */
(void*) UART1_Handler /* 45 UART */
};
@@ -198,7 +204,7 @@ void Reset_Handler(void)
SCB->VTOR = ((uint32_t) pSrc & SCB_VTOR_TBLOFF_Msk);
/* Initialize the C library */
- __libc_init_array();
+ // __libc_init_array();
/* Branch to main function */
main();
diff --git a/lib/cmsis-sam4e/include/component/afec.h b/lib/cmsis-sam4e/include/component/afec.h
index 34c4e61d..9a4f8f96 100644
--- a/lib/cmsis-sam4e/include/component/afec.h
+++ b/lib/cmsis-sam4e/include/component/afec.h
@@ -59,9 +59,9 @@ typedef struct {
RoReg Reserved2[1];
RwReg AFE_CDOR; /**< \brief (Afec Offset: 0x5C) Channel DC Offset Register */
RwReg AFE_DIFFR; /**< \brief (Afec Offset: 0x60) Channel Differential Register */
- RoReg AFE_CSELR; /**< \brief (Afec Offset: 0x64) Channel Register Selection */
+ RwReg AFE_CSELR; /**< \brief (Afec Offset: 0x64) Channel Register Selection */
RoReg AFE_CDR; /**< \brief (Afec Offset: 0x68) Channel Data Register */
- RoReg AFE_COCR; /**< \brief (Afec Offset: 0x6C) Channel Offset Compensation Register */
+ RwReg AFE_COCR; /**< \brief (Afec Offset: 0x6C) Channel Offset Compensation Register */
RwReg AFE_TEMPMR; /**< \brief (Afec Offset: 0x70) Temperature Sensor Mode Register */
RwReg AFE_TEMPCWR; /**< \brief (Afec Offset: 0x74) Temperature Compare Window Register */
RoReg Reserved3[7];

View File

@@ -104,7 +104,7 @@ void GMAC_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler")));
void UART1_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler")));
/* Exception Table */
__attribute__ ((section(".vectors")))
__attribute__ ((section(".vectors"))) __attribute__((externally_visible))
const DeviceVectors exception_table = {
/* Configure Initial Stack Pointer, using linker-generated symbols */
@@ -135,6 +135,7 @@ const DeviceVectors exception_table = {
(void*) PMC_Handler, /* 5 Power Management Controller */
(void*) EFC_Handler, /* 6 Enhanced Embedded Flash Controller */
(void*) UART0_Handler, /* 7 UART 0 */
(void*) Dummy_Handler, /* 8 Dummy */
(void*) PIOA_Handler, /* 9 Parallel I/O Controller A */
(void*) PIOB_Handler, /* 10 Parallel I/O Controller B */
(void*) PIOC_Handler, /* 11 Parallel I/O Controller C */
@@ -166,6 +167,10 @@ const DeviceVectors exception_table = {
(void*) CAN0_Handler, /* 37 CAN0 */
(void*) CAN1_Handler, /* 38 CAN1 */
(void*) AES_Handler, /* 39 AES */
(void*) Dummy_Handler, /* 40 Dummy */
(void*) Dummy_Handler, /* 41 Dummy */
(void*) Dummy_Handler, /* 42 Dummy */
(void*) Dummy_Handler, /* 43 Dummy */
(void*) GMAC_Handler, /* 44 EMAC */
(void*) UART1_Handler /* 45 UART */
};
@@ -198,7 +203,7 @@ void Reset_Handler(void)
SCB->VTOR = ((uint32_t) pSrc & SCB_VTOR_TBLOFF_Msk);
/* Initialize the C library */
__libc_init_array();
// __libc_init_array();
/* Branch to main function */
main();

View File

@@ -59,9 +59,9 @@ typedef struct {
RoReg Reserved2[1];
RwReg AFE_CDOR; /**< \brief (Afec Offset: 0x5C) Channel DC Offset Register */
RwReg AFE_DIFFR; /**< \brief (Afec Offset: 0x60) Channel Differential Register */
RoReg AFE_CSELR; /**< \brief (Afec Offset: 0x64) Channel Register Selection */
RwReg AFE_CSELR; /**< \brief (Afec Offset: 0x64) Channel Register Selection */
RoReg AFE_CDR; /**< \brief (Afec Offset: 0x68) Channel Data Register */
RoReg AFE_COCR; /**< \brief (Afec Offset: 0x6C) Channel Offset Compensation Register */
RwReg AFE_COCR; /**< \brief (Afec Offset: 0x6C) Channel Offset Compensation Register */
RwReg AFE_TEMPMR; /**< \brief (Afec Offset: 0x70) Temperature Sensor Mode Register */
RwReg AFE_TEMPCWR; /**< \brief (Afec Offset: 0x74) Temperature Compare Window Register */
RoReg Reserved3[7];

View File

@@ -10,6 +10,8 @@ choice
bool "SAM3x8e (Arduino Due)"
config MACH_SAMD21
bool "SAMD21 (Arduino Zero)"
config MACH_SAM4E8E
bool "SAM4e8e (Duet Wifi/Eth)"
config MACH_LPC176X
bool "LPC176x (Smoothieboard)"
config MACH_STM32F1
@@ -25,12 +27,15 @@ endchoice
source "src/avr/Kconfig"
source "src/sam3x8e/Kconfig"
source "src/samd21/Kconfig"
source "src/sam4e8e/Kconfig"
source "src/lpc176x/Kconfig"
source "src/stm32f1/Kconfig"
source "src/pru/Kconfig"
source "src/linux/Kconfig"
source "src/simulator/Kconfig"
# The HAVE_GPIO_x options allow boards to disable support for some
# commands if the hardware does not support the feature.
config HAVE_GPIO

30
src/sam4e8e/Kconfig Normal file
View File

@@ -0,0 +1,30 @@
# Kconfig settings for SAM4e8e processors
if MACH_SAM4E8E
config SAM_SELECT
bool
default y
select HAVE_GPIO
# select HAVE_GPIO_I2C
select HAVE_GPIO_ADC
select HAVE_GPIO_SPI
select HAVE_USER_INTERFACE
config BOARD_DIRECTORY
string
default "sam4e8e"
config CLOCK_FREQ
int
default 60000000 # 120000000/2
config SERIAL
bool
default y
config SERIAL_BAUD
depends on SERIAL
int "Baud rate for serial port"
default 250000
endif

37
src/sam4e8e/Makefile Normal file
View File

@@ -0,0 +1,37 @@
# Additional sam4e8e build rules
# Setup the toolchain
CROSS_PREFIX=arm-none-eabi-
dirs-y += src/sam4e8e src/generic
CFLAGS += -mthumb -mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard
CFLAGS += -D__SAM4E8E__
CFLAGS_klipper.elf += -L lib/cmsis-sam4e/gcc/gcc
CFLAGS_klipper.elf += -T lib/cmsis-sam4e/gcc/gcc/sam4e8e_flash.ld
CFLAGS_klipper.elf += --specs=nano.specs --specs=nosys.specs
dirs-y += lib/cmsis-sam4e/gcc \
lib/cmsis-sam4e/gcc/gcc
CFLAGS += -Ilib/cmsis-sam4e/include \
-Ilib/cmsis-core
src-y += ../lib/cmsis-sam4e/gcc/system_sam4e.c \
../lib/cmsis-sam4e/gcc/gcc/startup_sam4e.c
src-$(CONFIG_HAVE_GPIO_SPI) += sam4e8e/spi.c
src-$(CONFIG_SERIAL) += sam4e8e/serial.c generic/serial_irq.c
src-$(CONFIG_HAVE_GPIO) += sam4e8e/gpio.c
src-y += generic/crc16_ccitt.c generic/alloc.c
src-y += generic/armcm_irq.c generic/timer_irq.c
src-y += sam4e8e/main.c sam4e8e/timer.c
# Build the additional hex output file
target-y += $(OUT)klipper.bin
$(OUT)klipper.bin: $(OUT)klipper.elf
@echo " Creating bin file $@"
$(Q)$(OBJCOPY) -O binary $< $@
flash: $(OUT)klipper.bin
@echo " Flashing $^ to $(FLASH_DEVICE) via bossac"
$(Q)tools/bossa/bin/bossac --port="$(FLASH_DEVICE)" -b -U -e -w -v $(OUT)klipper.bin -R

361
src/sam4e8e/gpio.c Normal file
View File

@@ -0,0 +1,361 @@
// SAM4e8e GPIO port
//
// Copyright (C) 2018 Florian Heilmann <Florian.Heilmann@gmx.net>
//
// This file may be distributed under the terms of the GNU GPLv3 license.
#include "gpio.h"
#include "sam4e.h"
#include "autoconf.h" // CONFIG_CLOCK_FREQ
#include "board/irq.h" // irq_save
#include "command.h" // shutdown
#include "sched.h" // sched_shutdown
#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, PIOE
};
void
gpio_set_peripheral(char bank, const uint32_t bit, char ptype, uint32_t pull_up) {
Pio *regs = digital_regs[bank - 'A'];
regs ->PIO_IDR = bit;
// Enable peripheral for pin
uint32_t sr;
switch (ptype) {
case 'A':
sr = regs->PIO_ABCDSR[0];
regs->PIO_ABCDSR[0] &= (~bit & sr);
sr = regs->PIO_ABCDSR[1];
regs->PIO_ABCDSR[1] &= (~bit & sr);
break;
case 'B':
sr = regs->PIO_ABCDSR[0];
regs->PIO_ABCDSR[0] = (bit | sr);
sr = regs->PIO_ABCDSR[1];
regs->PIO_ABCDSR[1] &= (~bit & sr);
break;
case 'C':
sr = regs->PIO_ABCDSR[0];
regs->PIO_ABCDSR[0] &= (~bit & sr);
sr = regs->PIO_ABCDSR[1];
regs->PIO_ABCDSR[1] = (bit | sr);
break;
case 'D':
sr = regs->PIO_ABCDSR[0];
regs->PIO_ABCDSR[0] = (bit | sr);
sr = regs->PIO_ABCDSR[1];
regs->PIO_ABCDSR[1] = (bit | sr);
break;
}
// Disable pin in IO controller
regs->PIO_PDR = bit;
// Set pullup
if (pull_up) {
regs->PIO_PUER = bit;
} else {
regs->PIO_PUDR = 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);
uint32_t bank_id = ID_PIOA + GPIO2BIT(pin);
irqstatus_t flag = irq_save();
if ((PMC->PMC_PCSR0 & (1u << bank_id)) == 0) {
PMC->PMC_PCER0 = 1 << bank_id;
}
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){ .pin=pin, .regs=regs, .bit=bit };
fail:
shutdown("Not an output pin");
}
void
gpio_out_toggle_noirq(struct gpio_out g)
{
Pio *regs = g.regs;
regs->PIO_ODSR ^= g.bit;
}
void
gpio_out_toggle(struct gpio_out g)
{
irqstatus_t flag = irq_save();
gpio_out_toggle_noirq(g);
irq_restore(flag);
}
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);
regs->PIO_IDR = bit;
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){ .pin=pin, .regs=regs, .bit=bit };
fail:
shutdown("Not an input pin");
}
uint8_t
gpio_in_read(struct gpio_in g)
{
Pio *regs = g.regs;
return !!(regs->PIO_PDSR & g.bit);
}
/****************************************************************
* Analog Front-End Converter (AFEC) pins (see datasheet sec. 43.5)
****************************************************************/
static const uint8_t afec0_pins[] = {
//remove first channel, since it offsets the channel number: GPIO('A', 8),
GPIO('A', 17), GPIO('A', 18), GPIO('A', 19),
GPIO('A', 20), GPIO('B', 0), GPIO('B', 1), GPIO('C', 13),
GPIO('C', 15), GPIO('C', 12), GPIO('C', 29), GPIO('C', 30),
GPIO('C', 31), GPIO('C', 26), GPIO('C', 27), GPIO('C',0)
};
static const uint8_t afec1_pins[] = {
GPIO('B', 2), GPIO('B', 3), GPIO('A', 21), GPIO('A', 22),
GPIO('C', 1), GPIO('C', 2), GPIO('C', 3), GPIO('C', 4),
/* Artificially pad this array so we can safely iterate over it */
GPIO('B', 2), GPIO('B', 2), GPIO('B', 2), GPIO('B', 2),
GPIO('B', 2), GPIO('B', 2), GPIO('B', 2), GPIO('B', 2)
};
#define ADC_FREQ_MAX 6000000UL
DECL_CONSTANT(ADC_MAX, 4095);
inline struct gpio_adc
gpio_pin_to_afec(uint8_t pin)
{
int chan;
Afec* afec_device;
for (chan=0; ; chan++) {
if (chan >= ARRAY_SIZE(afec0_pins))
shutdown("Not a valid ADC pin");
if (afec0_pins[chan] == pin) {
afec_device = AFEC0;
break;
}
if (afec1_pins[chan] == pin) {
afec_device = AFEC1;
break;
}
}
return (struct gpio_adc){.pin=pin, .chan=chan, .afec=afec_device};
}
int
init_afec(Afec* afec) {
// Enable PMC
if (afec == AFEC0)
PMC->PMC_PCER0 = 1 << ID_AFEC0;
else
PMC->PMC_PCER0 = 1 << ID_AFEC1;
// If busy, return busy
if ((afec->AFE_ISR & AFE_ISR_DRDY) == AFE_ISR_DRDY) {
return -1;
}
// Reset
afec->AFE_CR = AFE_CR_SWRST;
// Configure afec
afec->AFE_MR = AFE_MR_ANACH_ALLOWED | \
AFE_MR_PRESCAL (SystemCoreClock / (2 * ADC_FREQ_MAX) -1) | \
AFE_MR_SETTLING_AST3 | \
AFE_MR_TRACKTIM(2) | \
AFE_MR_TRANSFER(1) | \
AFE_MR_STARTUP_SUT64;
afec->AFE_EMR = AFE_EMR_TAG | \
AFE_EMR_RES_NO_AVERAGE | \
AFE_EMR_STM;
afec->AFE_ACR = AFE_ACR_IBCTL(1);
// Disable interrupts
afec->AFE_IDR = 0xDF00803F;
// Disable SW triggering
uint32_t mr = afec->AFE_MR;
mr &= ~(AFE_MR_TRGSEL_Msk | AFE_MR_TRGEN | AFE_MR_FREERUN_ON);
mr |= AFE_MR_TRGEN_DIS;
afec->AFE_MR = mr;
return 0;
}
void
gpio_afec_init(void) {
while(init_afec(AFEC0) != 0) {
(void)(AFEC0->AFE_LCDR & AFE_LCDR_LDATA_Msk);
}
while(init_afec(AFEC1) != 0) {
(void)(AFEC1->AFE_LCDR & AFE_LCDR_LDATA_Msk);
}
}
DECL_INIT(gpio_afec_init);
struct gpio_adc
gpio_adc_setup(uint8_t pin)
{
struct gpio_adc adc_pin = gpio_pin_to_afec(pin);
Afec *afec = adc_pin.afec;
//config channel
uint32_t reg = afec->AFE_DIFFR;
reg &= ~(1u << adc_pin.chan);
afec->AFE_DIFFR = reg;
reg = afec->AFE_CGR;
reg &= ~(0x03u << (2 * adc_pin.chan));
reg |= 1 << (2 * adc_pin.chan);
afec->AFE_CGR = reg;
// Configure channel
// afec_ch_get_config_defaults(&ch_cfg);
// afec_ch_set_config(adc_pin.afec, adc_pin.chan, &ch_cfg);
// Remove default internal offset from channel
// See Atmel Appnote AT03078 Section 1.5
afec->AFE_CSELR = adc_pin.chan;
afec->AFE_COCR = (0x800 & AFE_COCR_AOFF_Msk);
// Enable and calibrate Channel
afec->AFE_CHER = 1 << adc_pin.chan;
reg = afec->AFE_CHSR;
afec->AFE_CDOR = reg;
afec->AFE_CR = AFE_CR_AUTOCAL;
return adc_pin;
}
enum { AFE_DUMMY=0xff };
uint8_t active_channel_afec0 = AFE_DUMMY;
uint8_t active_channel_afec1 = AFE_DUMMY;
inline uint8_t
get_active_afec_channel(Afec* afec) {
if (afec == AFEC0) {
return active_channel_afec0;
}
return active_channel_afec1;
}
inline void
set_active_afec_channel(Afec* afec, uint8_t chan) {
if (afec == AFEC0) {
active_channel_afec0 = chan;
} else {
active_channel_afec1 = chan;
}
}
// Try to sample a value. Returns zero if sample ready, otherwise
// returns the number of clock ticks the caller should wait before
// retrying this function.
uint32_t
gpio_adc_sample(struct gpio_adc g)
{
Afec* afec = g.afec;
if (get_active_afec_channel(afec) == g.chan) {
if ((afec->AFE_ISR & AFE_ISR_DRDY) && (afec->AFE_ISR & (1 << g.chan))) {
// Sample now ready
return 0;
} else {
// Busy
goto need_delay;
}
} else if (get_active_afec_channel(g.afec) != AFE_DUMMY) {
goto need_delay;
}
afec->AFE_CHDR = 0x803F; // Disable all channels
afec->AFE_CHER = 1 << g.chan;
set_active_afec_channel(afec, g.chan);
for (uint32_t chan = 0; chan < 16; ++chan)
{
if ((afec->AFE_ISR & (1 << chan)) != 0)
{
afec->AFE_CSELR = chan;
(void)(afec->AFE_CDR);
}
}
afec->AFE_CR = AFE_CR_START;
need_delay:
return ADC_FREQ_MAX * 10000ULL / CONFIG_CLOCK_FREQ; // about 400 mcu clock cycles or 40 afec cycles
}
// Read a value; use only after gpio_adc_sample() returns zero
uint16_t
gpio_adc_read(struct gpio_adc g)
{
Afec *afec = g.afec;
set_active_afec_channel(g.afec, AFE_DUMMY);
afec->AFE_CSELR = g.chan;
return afec->AFE_CDR;
}
// Cancel a sample that may have been started with gpio_adc_sample()
void
gpio_adc_cancel_sample(struct gpio_adc g)
{
if (get_active_afec_channel(g.afec) == g.chan) {
set_active_afec_channel(g.afec, AFE_DUMMY);
}
}

47
src/sam4e8e/gpio.h Normal file
View File

@@ -0,0 +1,47 @@
#ifndef __SAM4E8E_GPIO_H
#define __SAM4E8E_GPIO_H
#include <stdint.h>
struct gpio_out {
uint8_t pin;
void *regs;
uint32_t bit;
};
void gpio_set_peripheral(char bank, uint32_t bit, char ptype, uint32_t pull_up);
struct gpio_out gpio_out_setup(uint8_t pin, uint8_t val);
void gpio_out_toggle_noirq(struct gpio_out g);
void gpio_out_toggle(struct gpio_out g);
void gpio_out_write(struct gpio_out g, uint8_t val);
struct gpio_in {
uint8_t pin;
void *regs;
uint32_t bit;
};
struct gpio_adc {
uint8_t pin;
void *afec;
uint32_t chan;
};
struct gpio_in gpio_in_setup(uint8_t pin, int8_t pull_up);
uint8_t gpio_in_read(struct gpio_in g);
struct gpio_adc gpio_pin_to_afec(uint8_t pin);
struct gpio_adc gpio_adc_setup(uint8_t pin);
uint32_t gpio_adc_sample(struct gpio_adc g);
uint16_t gpio_adc_read(struct gpio_adc g);
void gpio_adc_cancel_sample(struct gpio_adc g);
struct spi_config {
void *sspi;
uint32_t cfg;
};
struct spi_config spi_setup(uint32_t bus, uint8_t mode, uint32_t rate);
void spi_transfer(struct spi_config config, uint8_t receive_data
, uint8_t len, uint8_t *data);
void spi_prepare(struct spi_config config);
#endif // gpio.h

48
src/sam4e8e/main.c Normal file
View File

@@ -0,0 +1,48 @@
// SAM4e8e port main entry
//
// Copyright (C) 2018 Florian Heilmann <Florian.Heilmann@gmx.net>
//
// This file may be distributed under the terms of the GNU GPLv3 license.
// CMSIS
#include "sam.h"
// Klipper
#include "command.h" // DECL_CONSTANT
#include "sched.h" // sched_main
DECL_CONSTANT(MCU, "sam4e8e");
#define WDT_PASSWORD 0xA5000000
#define WDT_SLOW_CLOCK_DIV 128
void
watchdog_reset(void)
{
WDT->WDT_CR = WDT_PASSWORD | WDT_CR_WDRSTT;
}
DECL_TASK(watchdog_reset);
void
watchdog_init(void)
{
uint32_t timeout = 500000 / (WDT_SLOW_CLOCK_DIV * 1000000 / 32768UL);
WDT->WDT_MR = WDT_MR_WDRSTEN | WDT_MR_WDV(timeout) | WDT_MR_WDD(timeout);
}
DECL_INIT(watchdog_init);
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;
}

59
src/sam4e8e/serial.c Normal file
View File

@@ -0,0 +1,59 @@
// SAM4e8e serial port
//
// Copyright (C) 2018 Florian Heilmann <Florian.Heilmann@gmx.net>
//
// This file may be distributed under the terms of the GNU GPLv3 license.
// CMSIS
#include "sam.h" // UART
// Klipper
#include "autoconf.h" // CONFIG_SERIAL_BAUD
#include "board/gpio.h" // gpio_peripheral
#include "board/serial_irq.h" // serial_rx_data
#include "sched.h" // DECL_INIT
void
serial_init(void)
{
gpio_set_peripheral('A', PIO_PA9A_URXD0, 'A', 1);
gpio_set_peripheral('A', PIO_PA10A_UTXD0, 'A', 0);
// Reset uart
PMC->PMC_PCER0 = 1 << ID_UART0;
UART0->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS;
UART0->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS;
UART0->UART_IDR = 0xFFFFFFFF;
// Enable uart
UART0->UART_MR = (US_MR_CHRL_8_BIT | US_MR_NBSTOP_1_BIT | UART_MR_PAR_NO
| UART_MR_CHMODE_NORMAL);
UART0->UART_BRGR = SystemCoreClock / (16 * CONFIG_SERIAL_BAUD);
UART0->UART_IER = UART_IER_RXRDY;
NVIC_EnableIRQ(UART0_IRQn);
NVIC_SetPriority(UART0_IRQn, 0);
UART0->UART_CR = UART_CR_RXEN | UART_CR_TXEN;
}
DECL_INIT(serial_init);
void __visible
UART0_Handler(void)
{
uint32_t status = UART0->UART_SR;
if (status & UART_SR_RXRDY)
serial_rx_byte(UART0->UART_RHR);
if (status & UART_SR_TXRDY) {
uint8_t data;
int ret = serial_get_tx_byte(&data);
if (ret)
UART0->UART_IDR = UART_IDR_TXRDY;
else
UART0->UART_THR = data;
}
}
void
serial_enable_tx_irq(void)
{
UART0->UART_IER = UART_IDR_TXRDY;
}

126
src/sam4e8e/spi.c Normal file
View File

@@ -0,0 +1,126 @@
// SAM4e8e SPI port
//
// Copyright (C) 2018 Florian Heilmann <Florian.Heilmann@gmx.net>
//
// This file may be distributed under the terms of the GNU GPLv3 license.
// Klipper
#include "command.h" // shutdown
#include "sched.h"
#include "autoconf.h" // CONFIG_CLOCK_FREQ
// SAM4E port
#include "sam.h"
#include "gpio.h"
#define SSPI_USART0 0
#define SSPI_USART1 1
#define SSPI_SPI 2
struct spi_config
spi_setup(uint32_t bus, uint8_t mode, uint32_t rate)
{
Usart *p_usart = USART0;
if (bus > 2 || mode > 3) {
shutdown("Invalid spi_setup parameters");
}
if (bus == SSPI_USART0) {
// DUET_USART0_SCK as per dc42 CoreNG
gpio_set_peripheral('B', PIO_PB13C_SCK0, 'C', 0);
// DUET_USART0_MOSI as per dc42 CoreNG
gpio_set_peripheral('B', PIO_PB1C_TXD0, 'C', 0);
// DUET_USART0_MISO as per dc42 CoreNG
gpio_set_peripheral('B', PIO_PB0C_RXD0, 'C', 1);
if ((PMC->PMC_PCSR0 & (1u << ID_USART0)) == 0) {
PMC->PMC_PCER0 = 1 << ID_USART0;
}
p_usart = USART0;
} else if (bus == SSPI_USART1) {
// DUET_USART1_SCK as per dc42 CoreNG
gpio_set_peripheral('A', PIO_PA23A_SCK1, 'A', 0);
// DUET_USART1_MOSI as per dc42 CoreNG
gpio_set_peripheral('A', PIO_PA22A_TXD1, 'A', 0);
// DUET_USART1_MISO as per dc42 CoreNG
gpio_set_peripheral('A', PIO_PA21A_RXD1, 'A', 1);
if ((PMC->PMC_PCSR0 & (1u << ID_USART1)) == 0) {
PMC->PMC_PCER0 = 1 << ID_USART1;
}
p_usart = USART1;
}
if (bus < 2) {
p_usart->US_MR = 0;
p_usart->US_RTOR = 0;
p_usart->US_TTGR = 0;
p_usart->US_CR = US_CR_RSTTX | US_CR_RSTRX | US_CR_TXDIS | US_CR_RXDIS;
uint32_t br = (CONFIG_CLOCK_FREQ + rate / 2) / rate;
p_usart-> US_BRGR = br << US_BRGR_CD_Pos;
uint32_t reg = US_MR_CHRL_8_BIT |
US_MR_USART_MODE_SPI_MASTER |
US_MR_CLKO |
US_MR_CHMODE_NORMAL;
switch (mode) {
case 0:
reg |= US_MR_CPHA;
reg &= ~US_MR_CPOL;
break;
case 1:
reg &= ~US_MR_CPHA;
reg &= ~US_MR_CPOL;
break;
case 2:
reg |= US_MR_CPHA;
reg |= US_MR_CPOL;
break;
case 3:
reg &= ~US_MR_CPHA;
reg |= US_MR_CPOL;
break;
}
p_usart->US_MR |= reg;
p_usart->US_CR = US_CR_RXEN | US_CR_TXEN;
return (struct spi_config){ .sspi=p_usart, .cfg=p_usart->US_MR };
}
// True SPI implementation still ToDo
return (struct spi_config){ .sspi = 0, .cfg=0};
}
void
spi_transfer(struct spi_config config, uint8_t receive_data
, uint8_t len, uint8_t *data)
{
if ((config.sspi == USART0) || (config.sspi == USART1)) {
Usart *p_usart = config.sspi;
if (receive_data) {
for (uint32_t i = 0; i < len; ++i) {
uint32_t co = (uint32_t)*data & 0x000000FF;
while(!(p_usart->US_CSR & US_CSR_TXRDY)) {}
p_usart->US_THR = US_THR_TXCHR(co);
uint32_t ci = 0;
while(!(p_usart->US_CSR & US_CSR_RXRDY)) {}
ci = p_usart->US_RHR & US_RHR_RXCHR_Msk;
*data++ = (uint8_t)ci;
}
} else {
for (uint32_t i = 0; i < len; ++i) {
uint32_t co = (uint32_t)*data & 0x000000FF;
while(!(p_usart->US_CSR & US_CSR_TXRDY)) {}
p_usart->US_THR = US_THR_TXCHR(co);
while(!(p_usart->US_CSR & US_CSR_RXRDY)) {}
(void)(p_usart->US_RHR & US_RHR_RXCHR_Msk);
(void)*data++;
}
}
}
}
void
spi_prepare(struct spi_config config) {}

67
src/sam4e8e/timer.c Normal file
View File

@@ -0,0 +1,67 @@
// SAM4e8e timer port
//
// Copyright (C) 2018 Florian Heilmann <Florian.Heilmann@gmx.net>
//
// This file may be distributed under the terms of the GNU GPLv3 license.
// CMSIS
#include "sam.h"
// Klipper
#include "board/irq.h" // irq_disable
#include "board/misc.h" // timer_read_time
#include "board/timer_irq.h" // timer_dispatch_many
#include "sched.h" // DECL_INIT
// Set the next irq time
static void
timer_set(uint32_t value)
{
TC0->TC_CHANNEL[0].TC_RA = value;
}
// Return the current time (in absolute clock ticks).
uint32_t
timer_read_time(void)
{
return TC0->TC_CHANNEL[0].TC_CV;
}
// Activate timer dispatch as soon as possible
void
timer_kick(void)
{
timer_set(timer_read_time() + 50);
TC0->TC_CHANNEL[0].TC_SR;
}
void
timer_init(void)
{
if ((PMC->PMC_PCSR0 & (1u << ID_TC0)) == 0) {
PMC->PMC_PCER0 = 1 << ID_TC0;
}
TcChannel *tc_channel = &TC0->TC_CHANNEL[0];
tc_channel->TC_CCR = TC_CCR_CLKDIS;
tc_channel->TC_IDR = 0xFFFFFFFF;
tc_channel->TC_SR;
tc_channel->TC_CMR = TC_CMR_WAVE | TC_CMR_WAVSEL_UP | TC_CMR_TCCLKS_TIMER_CLOCK1;
tc_channel->TC_IER = TC_IER_CPAS;
NVIC_SetPriority(TC0_IRQn, 1);
NVIC_EnableIRQ(TC0_IRQn);
timer_kick();
tc_channel->TC_CCR = TC_CCR_CLKEN | TC_CCR_SWTRG;
}
DECL_INIT(timer_init);
// IRQ handler
void __visible __aligned(16) // aligning helps stabilize perf benchmarks
TC0_Handler(void)
{
irq_disable();
uint32_t status = TC0->TC_CHANNEL[0].TC_SR;
if (likely(status & TC_SR_CPAS)) {
uint32_t next = timer_dispatch_many();
timer_set(next);
}
irq_enable();
}

View File

@@ -0,0 +1,2 @@
# Base config file for Atmel SAM4E8E ARM processor
CONFIG_MACH_SAM4E8E=y