From b7978d37b360fb270782a8db5d690342654e6977 Mon Sep 17 00:00:00 2001 From: Elias Bakken Date: Tue, 21 Feb 2023 02:15:01 +0100 Subject: ar100: Support for ar100 (#6054) Add files to support AR100 Signed-off-by: Elias Bakken --- src/Kconfig | 3 + src/ar100/Kconfig | 21 +++++++ src/ar100/Makefile | 45 +++++++++++++++ src/ar100/ar100.ld | 58 +++++++++++++++++++ src/ar100/gpio.c | 127 +++++++++++++++++++++++++++++++++++++++++ src/ar100/gpio.h | 43 ++++++++++++++ src/ar100/internal.h | 34 +++++++++++ src/ar100/main.c | 157 +++++++++++++++++++++++++++++++++++++++++++++++++++ src/ar100/serial.c | 53 +++++++++++++++++ src/ar100/serial.h | 50 ++++++++++++++++ src/ar100/timer.c | 52 +++++++++++++++++ src/ar100/timer.h | 12 ++++ src/ar100/util.c | 34 +++++++++++ src/ar100/util.h | 17 ++++++ 14 files changed, 706 insertions(+) create mode 100644 src/ar100/Kconfig create mode 100644 src/ar100/Makefile create mode 100644 src/ar100/ar100.ld create mode 100644 src/ar100/gpio.c create mode 100644 src/ar100/gpio.h create mode 100644 src/ar100/internal.h create mode 100644 src/ar100/main.c create mode 100644 src/ar100/serial.c create mode 100644 src/ar100/serial.h create mode 100644 src/ar100/timer.c create mode 100644 src/ar100/timer.h create mode 100644 src/ar100/util.c create mode 100644 src/ar100/util.h (limited to 'src') diff --git a/src/Kconfig b/src/Kconfig index 283639b7..aad59e6d 100644 --- a/src/Kconfig +++ b/src/Kconfig @@ -26,6 +26,8 @@ choice bool "Raspberry Pi RP2040" config MACH_PRU bool "Beaglebone PRU" + config MACH_AR100 + bool "Allwinner A64 AR100" config MACH_LINUX bool "Linux process" config MACH_SIMU @@ -40,6 +42,7 @@ source "src/stm32/Kconfig" source "src/hc32f460/Kconfig" source "src/rp2040/Kconfig" source "src/pru/Kconfig" +source "src/ar100/Kconfig" source "src/linux/Kconfig" source "src/simulator/Kconfig" diff --git a/src/ar100/Kconfig b/src/ar100/Kconfig new file mode 100644 index 00000000..fc7743da --- /dev/null +++ b/src/ar100/Kconfig @@ -0,0 +1,21 @@ +# Kconfig settings for AR100 + +if MACH_AR100 + +config AR100_SELECT + bool + default y + select HAVE_GPIO + select HAVE_GPIO_SPI + select HAVE_GPIO_BITBANGING + select HAVE_STEPPER_BOTH_EDGE + +config BOARD_DIRECTORY + string + default "ar100" + +config CLOCK_FREQ + int + default 300000000 + +endif diff --git a/src/ar100/Makefile b/src/ar100/Makefile new file mode 100644 index 00000000..d1203a0e --- /dev/null +++ b/src/ar100/Makefile @@ -0,0 +1,45 @@ +CROSS_PREFIX=or1k-linux-musl- +dirs-y += src/generic src/ar100 lib/ar100 + +CFLAGS += -O3 +CFLAGS += -fno-builtin +CFLAGS += -fno-pie +CFLAGS += -ffreestanding +CFLAGS += -msfimm -mshftimm -msoft-div -msoft-mul +CFLAGS += -Ilib/ar100 +CFLAGS_klipper.elf := $(CFLAGS) -T src/ar100/ar100.ld +CFLAGS_klipper.elf += -Wl,--gc-sections -static +CFLAGS_klipper.elf += -Wl,--no-dynamic-linker + +SFLAGS = -nostdinc -MMD +SFLAGS += -Ilib/ar100 + +# Add source files +src-y += ar100/main.c ar100/gpio.c ar100/serial.c +src-y += ar100/util.c ar100/timer.c +src-y += generic/crc16_ccitt.c generic/timer_irq.c + +# Remove files that are not needed to save space +src-y := $(filter-out lcd_hd44780.c,$(src-y)) +src-y := $(filter-out lcd_st7920.c,$(src-y)) +src-y := $(filter-out sensor_angle.c,$(src-y)) +src-y := $(filter-out thermocouple.c,$(src-y)) + +OBJS_klipper.elf += $(OUT)lib/ar100/start.o +OBJS_klipper.elf += $(OUT)lib/ar100/runtime.o + +# Build the AR100 binary +target-y += $(OUT)ar100.bin + +$(OUT)lib/ar100/start.o: + @echo " Compiling $@" + $(Q)$(CC) $(SFLAGS) -c $(PWD)/lib/ar100/start.S -o $@ + +$(OUT)lib/ar100/runtime.o: + @echo " Compiling $@" + $(Q)$(CC) $(SFLAGS) -c $(PWD)/lib/ar100/runtime.S -o $@ + +$(OUT)ar100.bin: $(OUT)klipper.elf + @echo " Object copy $@" + $(OBJCOPY) -O binary -S --reverse-bytes 4 $(OUT)klipper.elf $@ + truncate -s %8 $@ diff --git a/src/ar100/ar100.ld b/src/ar100/ar100.ld new file mode 100644 index 00000000..903620b5 --- /dev/null +++ b/src/ar100/ar100.ld @@ -0,0 +1,58 @@ +OUTPUT_ARCH(or1k) +OUTPUT_FORMAT(elf32-or1k) +ENTRY (start) + +STACK_SIZE = 0x200; +SRAM_A2_SIZE = 64K; +ORIG = 0x4000; +MEMORY { + SRAM_A2 (rwx): ORIGIN = ORIG, LENGTH = SRAM_A2_SIZE +} + +SECTIONS +{ + . = ORIG; + + .text . : ALIGN(4) { + KEEP(*(.text.start)) + *(SORT_BY_ALIGNMENT(SORT_BY_NAME(.text*))) + . = ALIGN(4); + } >SRAM_A2 + + .data . : ALIGN(4) { + *(SORT_BY_ALIGNMENT(SORT_BY_NAME(.rodata*))) + __data_start = .; + *(SORT_BY_ALIGNMENT(SORT_BY_NAME(.data*))) + . = ALIGN(4); + __data_end = .; + } >SRAM_A2 + + .copy . : ALIGN(4) { + __copy_start = .; + . += __data_end - __data_start; + __copy_end = .; + . = ALIGN(4); + } >SRAM_A2 + + .bss . : ALIGN(4) { + __bss_start = .; + *(SORT_BY_ALIGNMENT(SORT_BY_NAME(.bss*))) + . = ALIGN(4); + __bss_end = .; + + __stack_start = .; + . += STACK_SIZE; + __stack_end = .; + } >SRAM_A2 + + ASSERT(. <= (SRAM_A2_SIZE), "Klipper image is too large") + + /DISCARD/ : { + *(.comment*) + *(.eh_frame_hdr*) + *(.iplt*) + *(.note*) + *(.rela*) + *( .compile_time_request ) + } +} diff --git a/src/ar100/gpio.c b/src/ar100/gpio.c new file mode 100644 index 00000000..96a731d4 --- /dev/null +++ b/src/ar100/gpio.c @@ -0,0 +1,127 @@ +// GPIO functions on ar100 +// +// Copyright (C) 2020-2021 Elias Bakken +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include "gpio.h" +#include "command.h" +#include "internal.h" +#include "util.h" + +DECL_ENUMERATION_RANGE("pin", "PL0", 0*32, 13); +DECL_ENUMERATION_RANGE("pin", "PB0", 1*32, 10); +DECL_ENUMERATION_RANGE("pin", "PC0", 2*32, 17); +DECL_ENUMERATION_RANGE("pin", "PD0", 3*32, 25); +DECL_ENUMERATION_RANGE("pin", "PE0", 4*32, 18); +DECL_ENUMERATION_RANGE("pin", "PF0", 5*32, 7); +DECL_ENUMERATION_RANGE("pin", "PG0", 6*32, 14); +DECL_ENUMERATION_RANGE("pin", "PH0", 7*32, 12); + +#define BANK(x) (x/32) +#define PIN(x) (x%32) +#define CFG_REG(x) ((x/8)*4) +#define CFG_OFF(x) ((x%8)*4) +#define PULLUP_REG(x) 0x1C + ((x/16)*4) +#define PULLUP_OFF(x) ((x%16)*2) + +volatile uint32_t data_regs[8]; + +struct gpio_mux gpio_mux_setup(uint8_t pin, enum pin_func func){ + uint8_t bank = BANK(pin); + uint8_t p = PIN(pin); + uint32_t data_reg = PIO_BASE + bank*0x24 + 0x10; + uint32_t cfg_reg = PIO_BASE + bank*0x24 + CFG_REG(p); + uint8_t cfg_off = CFG_OFF(p); + + if(bank == 0) { // Handle R_PIO + data_reg = R_PIO_BASE + 0x10; + cfg_reg = R_PIO_BASE + CFG_REG(p); + } + + uint32_t curr_val = read_reg(cfg_reg) & ~(0xF< + +struct gpio_out { + uint8_t pin; + uint8_t bank; + uint32_t reg; +}; + +struct gpio_in { + uint8_t pin; + uint8_t bank; + uint32_t reg; +}; + +extern volatile uint32_t data_regs[8]; + + +struct gpio_in gpio_in_setup(uint8_t pin, int8_t pull_up); +void gpio_in_reset(struct gpio_in pin, int8_t pull_up); +uint8_t gpio_in_read(struct gpio_in pin); + +struct gpio_out gpio_out_setup(uint8_t pin, uint8_t val); +void gpio_out_write(struct gpio_out pin, uint8_t val); +void gpio_out_reset(struct gpio_out pin, uint8_t val); +void gpio_out_toggle_noirq(struct gpio_out pin); +void gpio_out_toggle(struct gpio_out pin); +struct gpio_in gpio_in_setup(uint8_t pin, int8_t pull_up); +void gpio_in_reset(struct gpio_in pin, int8_t pull_up); +uint8_t gpio_in_read(struct gpio_in pin); + +struct spi_config { + void *spi; + uint32_t spi_cr1; +}; +struct spi_config spi_setup(uint32_t bus, uint8_t mode, uint32_t rate); +void spi_prepare(struct spi_config config); +void spi_transfer(struct spi_config config, uint8_t receive_data + , uint8_t len, uint8_t *data); + +#endif diff --git a/src/ar100/internal.h b/src/ar100/internal.h new file mode 100644 index 00000000..406a4cd2 --- /dev/null +++ b/src/ar100/internal.h @@ -0,0 +1,34 @@ +#ifndef __AR100_INTERNAL_H +#define __AR100_INTERNAL_H + +#define R_PIO_BASE 0x01F02C00 +#define PIO_BASE 0x01C20800 + +enum pin_func { + PIO_INPUT, + PIO_OUTPUT, + PIO_ALT1, + PIO_ALT2, + PIO_ALT3, + PIO_ALT4, + PIO_ALT5, + PIO_DISABLE +}; + +struct gpio_mux { + uint32_t pin; + uint8_t bank; + uint32_t reg; +}; + +struct gpio_mux gpio_mux_setup(uint8_t pin, enum pin_func func); +static inline unsigned long mfspr(unsigned long add){ + unsigned long ret; + __asm__ __volatile__ ("l.mfspr %0,r0,%1" : "=r" (ret) : "K" (add)); + return ret; +} +static inline void mtspr(unsigned long add, unsigned long val){ + __asm__ __volatile__ ("l.mtspr r0,%1,%0" : : "K" (add), "r" (val)); +} + +#endif // internal.h diff --git a/src/ar100/main.c b/src/ar100/main.c new file mode 100644 index 00000000..2704144f --- /dev/null +++ b/src/ar100/main.c @@ -0,0 +1,157 @@ +// Main entry point for ar100 +// +// Copyright (C) 2020-2021 Elias Bakken +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include // uint32_t +#include +#include "board/misc.h" // dynmem_start +#include "board/irq.h" // irq_disable +#include "command.h" // shutdown +#include "generic/timer_irq.h" // timer_dispatch_many +#include "sched.h" // sched_main + +#include "asm/spr.h" +#include "util.h" +#include "gpio.h" +#include "serial.h" +#include "timer.h" + +DECL_CONSTANT_STR("MCU", "ar100"); + +#define RESET_VECTOR 0x0100 + +static struct task_wake console_wake; +static uint8_t receive_buf[192]; +static int receive_pos; +static char dynmem_pool[8 * 1024]; + +void * +dynmem_start(void) +{ + return dynmem_pool; +} + +void * +dynmem_end(void) +{ + return &dynmem_pool[sizeof(dynmem_pool)]; +} + +void +irq_disable(void) +{ +} + +void +irq_enable(void) +{ +} + +irqstatus_t +irq_save(void) +{ + return 0; +} + +void +irq_restore(irqstatus_t flag) +{ +} + +void +irq_wait(void) +{ + irq_poll(); +} + +void +irq_poll(void) +{ + if(timer_interrupt_pending()) { + timer_clear_interrupt(); + uint32_t next = timer_dispatch_many(); + timer_set(next); + } + if(r_uart_fifo_rcv()) + sched_wake_task(&console_wake); +} + +/**************************************************************** +* Console IO +****************************************************************/ + +// Process any incoming commands +void +console_task(void) +{ + if (!sched_check_wake(&console_wake)) + return; + + int ret = 0; + for(int i=0; i MESSAGE_MAX ? MESSAGE_MAX : len; + ret = command_find_and_dispatch(receive_buf, msglen, &pop_count); + if (ret) { + len -= pop_count; + if (len) { + memcpy(receive_buf, &receive_buf[pop_count], len); + sched_wake_task(&console_wake); + } + } + receive_pos = len; +} +DECL_TASK(console_task); + +// Encode and transmit a "response" message +void +console_sendf(const struct command_encoder *ce, va_list args) +{ + uint8_t buf[MESSAGE_MAX]; + uint_fast8_t msglen = command_encode_and_frame(buf, ce, args); + + for(int i=0; i +// +// This file may be distributed under the terms of the GNU GPLv3 license. + + +#include "serial.h" +#include "util.h" +#include "internal.h" +#include "gpio.h" + +void r_uart_init(void){ + // Setup Pins PL2, PL3 as UART IO + gpio_mux_setup(2, PIO_ALT1); + gpio_mux_setup(3, PIO_ALT1); + + // Enable clock and assert reset + clear_bit(APB0_CLK_GATING_REG, 4); + set_bit(APB0_SOFT_RST_REG, 4); + set_bit(APB0_CLK_GATING_REG, 4); + + // Setup baud rate + set_bit(R_UART_LCR, 7); // Enable setting DLH, DLL + write_reg(R_UART_DLH, 0x0); + write_reg(R_UART_DLL, 0xD); // 1 500 000 + write_reg(R_UART_LCR, 0x3); // 8 bit data length + + write_reg(R_UART_FCR, 0<<0); // Disable fifo + r_uart_getc(); // flush input + write_reg(R_UART_FCR, 1<<0); // Enable fifo +} + +char r_uart_getc(void){ + char c = (char) read_reg(R_UART_RBR); + return c; +} + +uint32_t r_uart_fifo_rcv(void){ + return read_reg(R_UART_RFL); +} + +void r_uart_putc(char c){ + while(!(read_reg(R_UART_LSR) & 1<<5)) + ; + write_reg(R_UART_THR, c); +} + +void r_uart_puts(char *s){ + while(*s){ + r_uart_putc(*s++); + } +} diff --git a/src/ar100/serial.h b/src/ar100/serial.h new file mode 100644 index 00000000..89eca29e --- /dev/null +++ b/src/ar100/serial.h @@ -0,0 +1,50 @@ +#include + +#define R_UART_BASE 0x01F02800 +#define R_UART_RBR R_UART_BASE + 0x00 // UART Receive Buffer Register +#define R_UART_THR R_UART_BASE + 0x00 // UART Transmit Holding Register +#define R_UART_DLL R_UART_BASE + 0x00 // UART Divisor Latch Low Register +#define R_UART_DLH R_UART_BASE + 0x04 // UART Divisor Latch High Register +#define R_UART_IER R_UART_BASE + 0x04 // UART Interrupt Enable Register +#define R_UART_IIR R_UART_BASE + 0x08 // UART Interrupt Identity Register +#define R_UART_FCR R_UART_BASE + 0x08 // UART FIFO Control Register +#define R_UART_LCR R_UART_BASE + 0x0C // UART Line Control Register +#define R_UART_MCR R_UART_BASE + 0x10 // UART Modem Control Register +#define R_UART_LSR R_UART_BASE + 0x14 // UART Line Status Register +#define R_UART_MSR R_UART_BASE + 0x18 // UART Modem Status Register +#define R_UART_SCH R_UART_BASE + 0x1C // UART Scratch Register +#define R_UART_USR R_UART_BASE + 0x7C // UART Status Register +#define R_UART_TFL R_UART_BASE + 0x80 // UART Transmit FIFO Level +#define R_UART_RFL R_UART_BASE + 0x84 // UART_RFL +#define R_UART_HLT R_UART_BASE + 0xA4 // UART Halt TX Register + +#define UART0_BASE 0x01C28000 +#define UART0_RBR UART0_BASE + 0x00 // UART Receive Buffer Register +#define UART0_THR UART0_BASE + 0x00 // UART Transmit Holding Register +#define UART0_DLL UART0_BASE + 0x00 // UART Divisor Latch Low Register +#define UART0_DLH UART0_BASE + 0x04 // UART Divisor Latch High Register +#define UART0_IER UART0_BASE + 0x04 // UART Interrupt Enable Register +#define UART0_IIR UART0_BASE + 0x08 // UART Interrupt Identity Register +#define UART0_FCR UART0_BASE + 0x08 // UART FIFO Control Register +#define UART0_LCR UART0_BASE + 0x0C // UART Line Control Register +#define UART0_MCR UART0_BASE + 0x10 // UART Modem Control Register +#define UART0_LSR UART0_BASE + 0x14 // UART Line Status Register +#define UART0_MSR UART0_BASE + 0x18 // UART Modem Status Register +#define UART0_SCH UART0_BASE + 0x1C // UART Scratch Register +#define UART0_USR UART0_BASE + 0x7C // UART Status Register +#define UART0_TFL UART0_BASE + 0x80 // UART Transmit FIFO Level +#define UART0_RFL UART0_BASE + 0x84 // UART_RFL +#define UART0_HLT UART0_BASE + 0xA4 // UART Halt TX Register + + +#define R_PRCM_BASE 0x01F01400 +#define APB0_CLK_GATING_REG R_PRCM_BASE + 0x0028 // APB0 Clock Gating Reg +#define APB0_SOFT_RST_REG R_PRCM_BASE + 0x00B0 // APB0 SW Reset Reg + +void r_uart_init(void); +void r_uart_putc(char c); +char r_uart_getc(void); +uint32_t r_uart_fifo_rcv(void); +void uart_putc(char c); +void uart_puts(char *s); +void uart_puti(uint32_t u); diff --git a/src/ar100/timer.c b/src/ar100/timer.c new file mode 100644 index 00000000..140d9ed0 --- /dev/null +++ b/src/ar100/timer.c @@ -0,0 +1,52 @@ +// Timer functions for ar100 +// +// Copyright (C) 2020-2021 Elias Bakken +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include "timer.h" +#include "board/timer_irq.h" +#include "board/misc.h" + +volatile static uint32_t timer_compare; +static uint8_t interrupt_seen; + +uint8_t timer_interrupt_pending(void){ + if(interrupt_seen){ + return 0; + } + if(timer_is_before(mfspr(SPR_TICK_TTCR_ADDR), timer_compare)){ + return 0; + } + + return 1; +} +void timer_clear_interrupt(void){ + interrupt_seen = 1; +} +// Set the next timer wake up time +void timer_set(uint32_t value){ + timer_compare = value; + interrupt_seen = 0; +} + +// Return the current time (in absolute clock ticks). +uint32_t timer_read_time(void){ + return mfspr(SPR_TICK_TTCR_ADDR); +} + +void timer_reset(void){ + mtspr(SPR_TICK_TTCR_ADDR, 0); +} + +// Activate timer dispatch as soon as possible +void timer_kick(void){ + timer_set(timer_read_time() + 50); +} + +void timer_init(void){ + interrupt_seen = 1; + mtspr(SPR_TICK_TTMR_ADDR, 3<<30); // continous + timer_kick(); +} +DECL_INIT(timer_init); diff --git a/src/ar100/timer.h b/src/ar100/timer.h new file mode 100644 index 00000000..12e89752 --- /dev/null +++ b/src/ar100/timer.h @@ -0,0 +1,12 @@ +#include +#include "asm/spr.h" +#include "sched.h" +#include "internal.h" + +uint8_t timer_interrupt_pending(void); +void timer_set(uint32_t value); +uint32_t timer_read_time(void); +void timer_reset(void); +void timer_clear_interrupt(void); +void timer_kick(void); +void timer_init(void); diff --git a/src/ar100/util.c b/src/ar100/util.c new file mode 100644 index 00000000..7f2f9cf7 --- /dev/null +++ b/src/ar100/util.c @@ -0,0 +1,34 @@ +// Helper functions for ar100 +// +// Copyright (C) 2020-2021 Elias Bakken +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include "util.h" + +void *memcpy(void *restrict dest, const void *restrict src, size_t n){ + // Typecast src and dest addresses to (char *) + char *csrc = (char *)src; + char *cdest = (char *)dest; + + // Copy contents of src[] to dest[] + for (int i=0; i +#include + +void *memcpy(void *restrict dest, const void *restrict src, size_t n); +void *memset(void *restrict dest, int c, size_t n); + +inline void write_reg(uint32_t addr, uint32_t val){ + *((volatile unsigned long *)(addr)) = val; +} + +inline uint32_t read_reg(uint32_t addr){ + return *((volatile unsigned long *)(addr)); +} + +void set_bit(uint32_t addr, uint8_t bit); + +void clear_bit(uint32_t addr, uint8_t bit); -- cgit v1.2.3-70-g09d2