mirror of
https://github.com/QIDITECH/klipper.git
synced 2026-01-30 23:48:43 +03:00
plus4的klipper版本
This commit is contained in:
82
src/Kconfig
82
src/Kconfig
@@ -4,7 +4,6 @@ mainmenu "Klipper Firmware Configuration"
|
||||
|
||||
config LOW_LEVEL_OPTIONS
|
||||
bool "Enable extra low-level configuration options"
|
||||
default n
|
||||
help
|
||||
Enable low-level configuration options that (if modified) may
|
||||
result in a build that does not function correctly.
|
||||
@@ -16,15 +15,19 @@ choice
|
||||
config MACH_ATSAM
|
||||
bool "SAM3/SAM4/SAM E70 (Due and Duet)"
|
||||
config MACH_ATSAMD
|
||||
bool "SAMD21/SAMD51"
|
||||
bool "SAMC21/SAMD21/SAMD51/SAME5x"
|
||||
config MACH_LPC176X
|
||||
bool "LPC176x (Smoothieboard)"
|
||||
config MACH_STM32
|
||||
bool "STMicroelectronics STM32"
|
||||
config MACH_HC32F460
|
||||
bool "Huada Semiconductor HC32F460"
|
||||
config MACH_RP2040
|
||||
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
|
||||
@@ -36,8 +39,10 @@ source "src/atsam/Kconfig"
|
||||
source "src/atsamd/Kconfig"
|
||||
source "src/lpc176x/Kconfig"
|
||||
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"
|
||||
|
||||
@@ -57,18 +62,21 @@ config USBSERIAL
|
||||
bool
|
||||
config USBCANBUS
|
||||
bool
|
||||
config USB
|
||||
bool
|
||||
default y if USBSERIAL || USBCANBUS
|
||||
config USB_VENDOR_ID
|
||||
default 0x1d50
|
||||
config USB_DEVICE_ID
|
||||
default 0x614e
|
||||
config USB_SERIAL_NUMBER_CHIPID
|
||||
depends on HAVE_CHIPID && (USBSERIAL || USBCANBUS)
|
||||
depends on USB && HAVE_CHIPID
|
||||
default y
|
||||
config USB_SERIAL_NUMBER
|
||||
default "12345"
|
||||
|
||||
menu "USB ids"
|
||||
depends on (USBSERIAL || USBCANBUS) && LOW_LEVEL_OPTIONS
|
||||
depends on USB && LOW_LEVEL_OPTIONS
|
||||
config USB_VENDOR_ID
|
||||
hex "USB vendor ID" if USBSERIAL
|
||||
config USB_DEVICE_ID
|
||||
@@ -79,6 +87,53 @@ config USB_SERIAL_NUMBER
|
||||
string "USB serial number" if !USB_SERIAL_NUMBER_CHIPID
|
||||
endmenu
|
||||
|
||||
# Optional features that can be disabled (for devices with small flash sizes)
|
||||
config WANT_GPIO_BITBANGING
|
||||
bool
|
||||
depends on HAVE_GPIO
|
||||
default y
|
||||
config WANT_DISPLAYS
|
||||
bool
|
||||
depends on HAVE_GPIO
|
||||
default y
|
||||
config WANT_SENSORS
|
||||
bool
|
||||
depends on HAVE_GPIO_I2C || HAVE_GPIO_SPI
|
||||
default y
|
||||
config WANT_LIS2DW
|
||||
bool
|
||||
depends on HAVE_GPIO_SPI
|
||||
default y
|
||||
config WANT_SOFTWARE_I2C
|
||||
bool
|
||||
depends on HAVE_GPIO && HAVE_GPIO_I2C
|
||||
default y
|
||||
config WANT_SOFTWARE_SPI
|
||||
bool
|
||||
depends on HAVE_GPIO && HAVE_GPIO_SPI
|
||||
default y
|
||||
menu "Optional features (to reduce code size)"
|
||||
depends on HAVE_LIMITED_CODE_SIZE
|
||||
config WANT_GPIO_BITBANGING
|
||||
bool "Support GPIO \"bit-banging\" devices"
|
||||
depends on HAVE_GPIO
|
||||
config WANT_DISPLAYS
|
||||
bool "Support LCD devices"
|
||||
depends on HAVE_GPIO
|
||||
config WANT_SENSORS
|
||||
bool "Support external sensor devices"
|
||||
depends on HAVE_GPIO_I2C || HAVE_GPIO_SPI
|
||||
config WANT_LIS2DW
|
||||
bool "Support lis2dw 3-axis accelerometer"
|
||||
depends on HAVE_GPIO_SPI
|
||||
config WANT_SOFTWARE_I2C
|
||||
bool "Support software based I2C \"bit-banging\""
|
||||
depends on HAVE_GPIO && HAVE_GPIO_I2C
|
||||
config WANT_SOFTWARE_SPI
|
||||
bool "Support software based SPI \"bit-banging\""
|
||||
depends on HAVE_GPIO && HAVE_GPIO_SPI
|
||||
endmenu
|
||||
|
||||
# Generic configuration options for CANbus
|
||||
config CANSERIAL
|
||||
bool
|
||||
@@ -87,7 +142,7 @@ config CANBUS
|
||||
default y if CANSERIAL || USBCANBUS
|
||||
config CANBUS_FREQUENCY
|
||||
int "CAN bus speed" if LOW_LEVEL_OPTIONS && CANBUS
|
||||
default 500000
|
||||
default 1000000
|
||||
config CANBUS_FILTER
|
||||
bool
|
||||
default y if CANSERIAL
|
||||
@@ -106,31 +161,26 @@ config INITIAL_PINS
|
||||
# if the hardware does not support the feature.
|
||||
config HAVE_GPIO
|
||||
bool
|
||||
default n
|
||||
config HAVE_GPIO_ADC
|
||||
bool
|
||||
default n
|
||||
config HAVE_GPIO_SPI
|
||||
bool
|
||||
default n
|
||||
config HAVE_GPIO_SDIO
|
||||
bool
|
||||
config HAVE_GPIO_I2C
|
||||
bool
|
||||
default n
|
||||
config HAVE_GPIO_HARD_PWM
|
||||
bool
|
||||
default n
|
||||
config HAVE_GPIO_BITBANGING
|
||||
bool
|
||||
default n
|
||||
config HAVE_STRICT_TIMING
|
||||
bool
|
||||
default n
|
||||
config HAVE_CHIPID
|
||||
bool
|
||||
default n
|
||||
config HAVE_STEPPER_BOTH_EDGE
|
||||
bool
|
||||
default n
|
||||
config HAVE_BOOTLOADER_REQUEST
|
||||
bool
|
||||
config HAVE_LIMITED_CODE_SIZE
|
||||
bool
|
||||
|
||||
config INLINE_STEPPER_HACK
|
||||
# Enables gcc to inline stepper_event() into the main timer irq handler
|
||||
|
||||
18
src/Makefile
18
src/Makefile
@@ -4,10 +4,18 @@ src-y += sched.c command.c basecmd.c debugcmds.c
|
||||
src-$(CONFIG_HAVE_GPIO) += initial_pins.c gpiocmds.c stepper.c endstop.c \
|
||||
trsync.c
|
||||
src-$(CONFIG_HAVE_GPIO_ADC) += adccmds.c
|
||||
src-$(CONFIG_HAVE_GPIO_SPI) += spicmds.c thermocouple.c
|
||||
src-$(CONFIG_HAVE_GPIO_SPI) += spicmds.c
|
||||
src-$(CONFIG_HAVE_GPIO_SDIO) += sdiocmds.c
|
||||
src-$(CONFIG_HAVE_GPIO_I2C) += i2ccmds.c
|
||||
src-$(CONFIG_HAVE_GPIO_HARD_PWM) += pwmcmds.c
|
||||
bb-src-$(CONFIG_HAVE_GPIO_SPI) := spi_software.c sensor_adxl345.c sensor_angle.c
|
||||
bb-src-$(CONFIG_HAVE_GPIO_I2C) += sensor_mpu9250.c
|
||||
src-$(CONFIG_HAVE_GPIO_BITBANGING) += $(bb-src-y) lcd_st7920.c lcd_hd44780.c \
|
||||
buttons.c tmcuart.c neopixel.c pulse_counter.c
|
||||
|
||||
src-$(CONFIG_WANT_GPIO_BITBANGING) += buttons.c tmcuart.c neopixel.c \
|
||||
pulse_counter.c
|
||||
src-$(CONFIG_WANT_DISPLAYS) += lcd_st7920.c lcd_hd44780.c
|
||||
src-$(CONFIG_WANT_SOFTWARE_SPI) += spi_software.c
|
||||
src-$(CONFIG_WANT_SOFTWARE_I2C) += i2c_software.c
|
||||
sensors-src-$(CONFIG_HAVE_GPIO_SPI) := thermocouple.c sensor_adxl345.c \
|
||||
sensor_angle.c
|
||||
src-$(CONFIG_WANT_LIS2DW) += sensor_lis2dw.c
|
||||
sensors-src-$(CONFIG_HAVE_GPIO_I2C) += sensor_mpu9250.c
|
||||
src-$(CONFIG_WANT_SENSORS) += $(sensors-src-y)
|
||||
|
||||
21
src/ar100/Kconfig
Normal file
21
src/ar100/Kconfig
Normal file
@@ -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_STEPPER_BOTH_EDGE
|
||||
select HAVE_LIMITED_CODE_SIZE
|
||||
|
||||
config BOARD_DIRECTORY
|
||||
string
|
||||
default "ar100"
|
||||
|
||||
config CLOCK_FREQ
|
||||
int
|
||||
default 300000000
|
||||
|
||||
endif
|
||||
39
src/ar100/Makefile
Normal file
39
src/ar100/Makefile
Normal file
@@ -0,0 +1,39 @@
|
||||
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
|
||||
|
||||
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 $@
|
||||
58
src/ar100/ar100.ld
Normal file
58
src/ar100/ar100.ld
Normal file
@@ -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 )
|
||||
}
|
||||
}
|
||||
127
src/ar100/gpio.c
Normal file
127
src/ar100/gpio.c
Normal file
@@ -0,0 +1,127 @@
|
||||
// GPIO functions on ar100
|
||||
//
|
||||
// Copyright (C) 2020-2021 Elias Bakken <elias@iagent.no>
|
||||
//
|
||||
// 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<<cfg_off);
|
||||
write_reg(cfg_reg, curr_val | func<<cfg_off);
|
||||
|
||||
struct gpio_mux ret = {
|
||||
.pin = p,
|
||||
.reg = data_reg,
|
||||
.bank = bank
|
||||
};
|
||||
return ret;
|
||||
}
|
||||
|
||||
struct gpio_out gpio_out_setup(uint8_t pin, uint8_t val){
|
||||
|
||||
struct gpio_mux mux = gpio_mux_setup(pin, PIO_OUTPUT);
|
||||
struct gpio_out ret = {
|
||||
.pin = mux.pin,
|
||||
.reg = mux.reg,
|
||||
.bank = mux.bank,
|
||||
};
|
||||
data_regs[ret.bank] = read_reg(ret.reg);
|
||||
gpio_out_write(ret, val);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void gpio_out_write(struct gpio_out pin, uint8_t val){
|
||||
data_regs[pin.bank] &= ~(1<<pin.pin);
|
||||
data_regs[pin.bank] |= ((!!val)<<pin.pin);
|
||||
write_reg(pin.reg, data_regs[pin.bank]);
|
||||
}
|
||||
|
||||
void gpio_out_reset(struct gpio_out pin, uint8_t val){
|
||||
uint8_t p = pin.bank * 32 + pin.pin;
|
||||
gpio_out_setup(p, val);
|
||||
}
|
||||
|
||||
uint8_t gpio_in_read(struct gpio_in pin){
|
||||
data_regs[pin.bank] = read_reg(pin.reg);
|
||||
return !!(data_regs[pin.bank] & (1<<pin.pin));
|
||||
}
|
||||
|
||||
struct gpio_in gpio_in_setup(uint8_t pin, int8_t pull_up){
|
||||
struct gpio_mux mux = gpio_mux_setup(pin, PIO_INPUT);
|
||||
|
||||
uint32_t pullup_reg = PIO_BASE + mux.bank*0x24 + PULLUP_REG(mux.pin);
|
||||
uint8_t pullup_off = PULLUP_OFF(mux.pin);
|
||||
|
||||
if(mux.bank == 0) { // Handle R_PIO
|
||||
pullup_reg = R_PIO_BASE + PULLUP_REG(mux.pin);
|
||||
}
|
||||
|
||||
write_reg(pullup_reg, pull_up<<pullup_off);
|
||||
|
||||
struct gpio_in in = {
|
||||
.pin = mux.pin,
|
||||
.reg = mux.reg,
|
||||
.bank = mux.bank
|
||||
};
|
||||
data_regs[mux.bank] = read_reg(mux.reg);
|
||||
return in;
|
||||
}
|
||||
|
||||
void gpio_in_reset(struct gpio_in pin, int8_t pull_up){
|
||||
uint8_t p = pin.bank * 32 + pin.pin;
|
||||
gpio_in_setup(p, pull_up);
|
||||
}
|
||||
|
||||
void gpio_out_toggle_noirq(struct gpio_out pin){
|
||||
data_regs[pin.bank] ^= (1<<pin.pin);
|
||||
*((volatile uint32_t *)(pin.reg)) = data_regs[pin.bank];
|
||||
}
|
||||
|
||||
void gpio_out_toggle(struct gpio_out pin){
|
||||
gpio_out_toggle_noirq(pin);
|
||||
}
|
||||
|
||||
struct spi_config spi_setup(uint32_t bus, uint8_t mode, uint32_t rate){
|
||||
return (struct spi_config){ };
|
||||
}
|
||||
|
||||
void spi_prepare(struct spi_config config){
|
||||
}
|
||||
|
||||
void spi_transfer(struct spi_config config, uint8_t receive_data
|
||||
, uint8_t len, uint8_t *data){
|
||||
}
|
||||
43
src/ar100/gpio.h
Normal file
43
src/ar100/gpio.h
Normal file
@@ -0,0 +1,43 @@
|
||||
#ifndef __AR100_GPIO_H
|
||||
#define __AR100_GPIO_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
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
|
||||
34
src/ar100/internal.h
Normal file
34
src/ar100/internal.h
Normal file
@@ -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
|
||||
157
src/ar100/main.c
Normal file
157
src/ar100/main.c
Normal file
@@ -0,0 +1,157 @@
|
||||
// Main entry point for ar100
|
||||
//
|
||||
// Copyright (C) 2020-2021 Elias Bakken <elias@iagent.no>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <stdint.h> // uint32_t
|
||||
#include <string.h>
|
||||
#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<r_uart_fifo_rcv(); i++) {
|
||||
receive_buf[receive_pos + ret++] = r_uart_getc();
|
||||
}
|
||||
if(!ret)
|
||||
return;
|
||||
|
||||
int len = receive_pos + ret;
|
||||
uint_fast8_t pop_count, msglen = len > 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<msglen; i++) {
|
||||
r_uart_putc(buf[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void restore_data(void)
|
||||
{
|
||||
extern char __data_start, __data_end, __copy_start;
|
||||
memcpy (&__data_start, &__copy_start, &__data_end - &__data_start);
|
||||
}
|
||||
|
||||
void
|
||||
command_reset(uint32_t *args)
|
||||
{
|
||||
timer_reset();
|
||||
restore_data();
|
||||
void *reset = (void *)RESET_VECTOR;
|
||||
goto *reset;
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_reset, HF_IN_SHUTDOWN, "reset");
|
||||
|
||||
void
|
||||
save_data(void)
|
||||
{
|
||||
extern char __data_start, __data_end, __copy_start;
|
||||
memcpy (&__copy_start, &__data_start, &__data_end - &__data_start);
|
||||
}
|
||||
|
||||
__noreturn void
|
||||
main(uint32_t exception);
|
||||
__noreturn void
|
||||
main(uint32_t exception)
|
||||
{
|
||||
save_data();
|
||||
r_uart_init();
|
||||
sched_main();
|
||||
while(1) {} // Stop complaining about noreturn
|
||||
}
|
||||
53
src/ar100/serial.c
Normal file
53
src/ar100/serial.c
Normal file
@@ -0,0 +1,53 @@
|
||||
// Uart and r_uart functions for ar100
|
||||
//
|
||||
// Copyright (C) 2020-2021 Elias Bakken <elias@iagent.no>
|
||||
//
|
||||
// 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++);
|
||||
}
|
||||
}
|
||||
50
src/ar100/serial.h
Normal file
50
src/ar100/serial.h
Normal file
@@ -0,0 +1,50 @@
|
||||
#include <stdint.h>
|
||||
|
||||
#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);
|
||||
52
src/ar100/timer.c
Normal file
52
src/ar100/timer.c
Normal file
@@ -0,0 +1,52 @@
|
||||
// Timer functions for ar100
|
||||
//
|
||||
// Copyright (C) 2020-2021 Elias Bakken <elias@iagent.no>
|
||||
//
|
||||
// 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);
|
||||
12
src/ar100/timer.h
Normal file
12
src/ar100/timer.h
Normal file
@@ -0,0 +1,12 @@
|
||||
#include <stdint.h>
|
||||
#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);
|
||||
34
src/ar100/util.c
Normal file
34
src/ar100/util.c
Normal file
@@ -0,0 +1,34 @@
|
||||
// Helper functions for ar100
|
||||
//
|
||||
// Copyright (C) 2020-2021 Elias Bakken <elias@iagent.no>
|
||||
//
|
||||
// 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<n; i++)
|
||||
cdest[i] = csrc[i];
|
||||
return dest;
|
||||
}
|
||||
|
||||
void *memset(void *dest, int c, size_t n){
|
||||
unsigned char *s = dest;
|
||||
for(; n; n--){
|
||||
*s++ = c;
|
||||
}
|
||||
return dest;
|
||||
}
|
||||
|
||||
void set_bit(uint32_t addr, uint8_t bit){
|
||||
write_reg(addr, read_reg(addr) | (1<<bit));
|
||||
}
|
||||
|
||||
void clear_bit(uint32_t addr, uint8_t bit){
|
||||
write_reg(addr, read_reg(addr) & ~(1<<bit));
|
||||
}
|
||||
17
src/ar100/util.h
Normal file
17
src/ar100/util.h
Normal file
@@ -0,0 +1,17 @@
|
||||
#include <stdint.h>
|
||||
#include <stddef.h>
|
||||
|
||||
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);
|
||||
@@ -10,10 +10,10 @@ config ATSAM_SELECT
|
||||
select HAVE_GPIO_I2C
|
||||
select HAVE_GPIO_SPI
|
||||
select HAVE_GPIO_HARD_PWM if !MACH_SAME70
|
||||
select HAVE_GPIO_BITBANGING
|
||||
select HAVE_STRICT_TIMING
|
||||
select HAVE_CHIPID
|
||||
select HAVE_STEPPER_BOTH_EDGE
|
||||
select HAVE_BOOTLOADER_REQUEST
|
||||
|
||||
config BOARD_DIRECTORY
|
||||
string
|
||||
@@ -50,6 +50,9 @@ config MACH_SAM4E
|
||||
select MACH_SAM4
|
||||
config MACH_SAME70
|
||||
bool
|
||||
config HAVE_SAM_CANBUS
|
||||
bool
|
||||
default y if MACH_SAME70
|
||||
|
||||
config MCU
|
||||
string
|
||||
@@ -65,15 +68,14 @@ config CLOCK_FREQ
|
||||
default 120000000 if MACH_SAM4
|
||||
default 300000000 if MACH_SAME70
|
||||
|
||||
config FLASH_START
|
||||
hex
|
||||
default 0x400000 if MACH_SAM4 || MACH_SAME70
|
||||
default 0x80000
|
||||
|
||||
config FLASH_SIZE
|
||||
hex
|
||||
default 0x80000
|
||||
|
||||
config FLASH_BOOT_ADDRESS
|
||||
hex
|
||||
default 0x0
|
||||
|
||||
config RAM_START
|
||||
hex
|
||||
default 0x20400000 if MACH_SAME70
|
||||
@@ -89,6 +91,11 @@ config STACK_SIZE
|
||||
int
|
||||
default 512
|
||||
|
||||
config FLASH_APPLICATION_ADDRESS
|
||||
hex
|
||||
default 0x400000 if MACH_SAM4 || MACH_SAME70
|
||||
default 0x80000
|
||||
|
||||
choice
|
||||
prompt "Communication interface"
|
||||
config ATSAM_USB
|
||||
@@ -97,6 +104,32 @@ choice
|
||||
config ATSAM_SERIAL
|
||||
bool "Serial"
|
||||
select SERIAL
|
||||
config ATSAM_MMENU_CANBUS_PC12_PD12
|
||||
bool "CAN bus (on PC12/PD12)"
|
||||
depends on HAVE_SAM_CANBUS
|
||||
select CANSERIAL
|
||||
config ATSAM_MMENU_CANBUS_PB3_PB2
|
||||
bool "CAN bus (on PB3/PB2)"
|
||||
depends on HAVE_SAM_CANBUS
|
||||
select CANSERIAL
|
||||
config ATSAM_USBCANBUS
|
||||
bool "USB to CAN bus bridge"
|
||||
depends on HAVE_SAM_CANBUS
|
||||
select USBCANBUS
|
||||
endchoice
|
||||
choice
|
||||
prompt "CAN bus interface" if USBCANBUS
|
||||
config ATSAM_CMENU_CANBUS_PC12_PD12
|
||||
bool "CAN bus (on PC12/PD12)"
|
||||
config ATSAM_CMENU_CANBUS_PB3_PB2
|
||||
bool "CAN bus (on PB3/PB2)"
|
||||
endchoice
|
||||
|
||||
config ATSAM_CANBUS_PC12_PD12
|
||||
bool
|
||||
default y if ATSAM_MMENU_CANBUS_PC12_PD12 || ATSAM_CMENU_CANBUS_PC12_PD12
|
||||
config ATSAM_CANBUS_PB3_PB2
|
||||
bool
|
||||
default y if ATSAM_MMENU_CANBUS_PB3_PB2 || ATSAM_CMENU_CANBUS_PB3_PB2
|
||||
|
||||
endif
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
# Setup the toolchain
|
||||
CROSS_PREFIX=arm-none-eabi-
|
||||
|
||||
dirs-y += src/atsam src/generic
|
||||
dirs-y += src/atsam src/generic lib/fast-hash
|
||||
dirs-$(CONFIG_MACH_SAM3X) += lib/sam3x/gcc
|
||||
dirs-$(CONFIG_MACH_SAM4S) += lib/sam4s/gcc
|
||||
dirs-$(CONFIG_MACH_SAM4E) += lib/sam4e/gcc
|
||||
@@ -18,7 +18,7 @@ CFLAGS-$(CONFIG_MACH_SAM3X) += -Ilib/sam3x/include
|
||||
CFLAGS-$(CONFIG_MACH_SAM4S) += -Ilib/sam4s/include
|
||||
CFLAGS-$(CONFIG_MACH_SAM4E) += -Ilib/sam4e/include
|
||||
CFLAGS-$(CONFIG_MACH_SAME70) += -Ilib/same70b/include
|
||||
CFLAGS += $(CFLAGS-y) -D__$(MCU)__ -mthumb -Ilib/cmsis-core
|
||||
CFLAGS += $(CFLAGS-y) -D__$(MCU)__ -mthumb -Ilib/cmsis-core -Ilib/fast-hash
|
||||
|
||||
CFLAGS_klipper.elf += --specs=nano.specs --specs=nosys.specs
|
||||
CFLAGS_klipper.elf += -T $(OUT)src/generic/armcm_link.ld
|
||||
@@ -33,6 +33,10 @@ usb-src-$(CONFIG_MACH_SAM4) := atsam/sam4_usb.c
|
||||
usb-src-$(CONFIG_MACH_SAME70) := atsam/sam3_usb.c
|
||||
src-$(CONFIG_USBSERIAL) += $(usb-src-y) atsam/chipid.c generic/usb_cdc.c
|
||||
src-$(CONFIG_SERIAL) += atsam/serial.c generic/serial_irq.c
|
||||
canbus-src-y := generic/canserial.c ../lib/fast-hash/fasthash.c
|
||||
canbus-src-y += atsam/fdcan.c atsam/chipid.c
|
||||
src-$(CONFIG_USBCANBUS) += $(canbus-src-y) $(usb-src-y) generic/usb_canbus.c
|
||||
src-$(CONFIG_CANSERIAL) += $(canbus-src-y) generic/canbus.c
|
||||
src-$(CONFIG_MACH_SAM3X) += atsam/adc.c atsam/hard_pwm.c
|
||||
src-$(CONFIG_MACH_SAM4) += atsam/hard_pwm.c
|
||||
src-$(CONFIG_MACH_SAM4S) += atsam/adc.c
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "generic/irq.h" // irq_disable
|
||||
#include "generic/canserial.h" // canserial_set_uuid
|
||||
#include "generic/usb_cdc.h" // usb_fill_serial
|
||||
#include "generic/usbstd.h" // usb_string_descriptor
|
||||
#include "internal.h" // EFC0
|
||||
@@ -61,7 +62,7 @@ read_chip_id(uint32_t *id)
|
||||
void
|
||||
chipid_init(void)
|
||||
{
|
||||
if (!CONFIG_USB_SERIAL_NUMBER_CHIPID)
|
||||
if (!CONFIG_USB_SERIAL_NUMBER_CHIPID && !CONFIG_CANBUS)
|
||||
return;
|
||||
|
||||
uint32_t id[4];
|
||||
@@ -69,6 +70,10 @@ chipid_init(void)
|
||||
read_chip_id(id);
|
||||
irq_enable();
|
||||
|
||||
usb_fill_serial(&cdc_chipid.desc, ARRAY_SIZE(cdc_chipid.data), id);
|
||||
if (CONFIG_USB_SERIAL_NUMBER_CHIPID)
|
||||
usb_fill_serial(&cdc_chipid.desc, ARRAY_SIZE(cdc_chipid.data), id);
|
||||
|
||||
if (CONFIG_CANBUS)
|
||||
canserial_set_uuid((void*)id, CHIP_UID_LEN);
|
||||
}
|
||||
DECL_INIT(chipid_init);
|
||||
|
||||
307
src/atsam/fdcan.c
Normal file
307
src/atsam/fdcan.c
Normal file
@@ -0,0 +1,307 @@
|
||||
// CANbus support on atsame70 chips
|
||||
//
|
||||
// Copyright (C) 2021-2022 Kevin O'Connor <kevin@koconnor.net>
|
||||
// Copyright (C) 2019 Eug Krashtan <eug.krashtan@gmail.com>
|
||||
// Copyright (C) 2020 Pontus Borg <glpontus@gmail.com>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "command.h" // DECL_CONSTANT_STR
|
||||
#include "generic/armcm_boot.h" // armcm_enable_irq
|
||||
#include "generic/canbus.h" // canbus_notify_tx
|
||||
#include "generic/canserial.h" // CANBUS_ID_ADMIN
|
||||
#include "internal.h" // enable_pclock
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Pin configuration
|
||||
****************************************************************/
|
||||
|
||||
#if CONFIG_ATSAM_CANBUS_PB3_PB2
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_CAN", "PB3,PB2");
|
||||
#define GPIO_Rx GPIO('B', 3)
|
||||
#define GPIO_Tx GPIO('B', 2)
|
||||
#define CANx_GCLK_ID MCAN0_CLOCK_ID
|
||||
#elif CONFIG_ATSAM_CANBUS_PC12_PD12
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_CAN", "PC12,PD12");
|
||||
#define GPIO_Rx GPIO('C', 12)
|
||||
#define GPIO_Tx GPIO('D', 12)
|
||||
#define CANx_GCLK_ID MCAN1_CLOCK_ID
|
||||
#endif
|
||||
|
||||
#if CANx_GCLK_ID == MCAN0_CLOCK_ID
|
||||
#define CAN_FUNCTION_Rx 'A'
|
||||
#define CAN_FUNCTION_Tx 'A'
|
||||
#define CANx MCAN0
|
||||
#define CANx_IRQn MCAN0_INT0_IRQn
|
||||
#define CCFG_CANxDMABA MATRIX->CCFG_CAN0
|
||||
#define CCFG_CANxDMABA_Msk CCFG_CAN0_CAN0DMABA_Msk
|
||||
#define CCFG_CANxDMABA_Pos CCFG_CAN0_CAN0DMABA_Pos
|
||||
#else
|
||||
#define CAN_FUNCTION_Rx 'C'
|
||||
#define CAN_FUNCTION_Tx 'B'
|
||||
#define CANx MCAN1
|
||||
#define CANx_IRQn MCAN1_INT0_IRQn
|
||||
#define CCFG_CANxDMABA MATRIX->CCFG_SYSIO
|
||||
#define CCFG_CANxDMABA_Msk CCFG_SYSIO_CAN1DMABA_Msk
|
||||
#define CCFG_CANxDMABA_Pos CCFG_SYSIO_CAN1DMABA_Pos
|
||||
#endif
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Message ram layout
|
||||
****************************************************************/
|
||||
|
||||
struct fdcan_fifo {
|
||||
uint32_t id_section;
|
||||
uint32_t dlc_section;
|
||||
uint32_t data[64 / 4];
|
||||
};
|
||||
|
||||
#define FDCAN_XTD (1<<30)
|
||||
#define FDCAN_RTR (1<<29)
|
||||
|
||||
struct fdcan_msg_ram {
|
||||
uint32_t FLS[28]; // Filter list standard
|
||||
uint32_t FLE[16]; // Filter list extended
|
||||
struct fdcan_fifo RXF0[3];
|
||||
struct fdcan_fifo RXF1[3];
|
||||
uint32_t TEF[6]; // Tx event FIFO
|
||||
struct fdcan_fifo TXFIFO[3];
|
||||
};
|
||||
|
||||
// Message ram is in regular memory
|
||||
static struct fdcan_msg_ram MSG_RAM;
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* CANbus code
|
||||
****************************************************************/
|
||||
|
||||
#define FDCAN_IE_TC (MCAN_IE_TCE | MCAN_IE_TCFE | MCAN_IE_TFEE)
|
||||
|
||||
// Transmit a packet
|
||||
int
|
||||
canhw_send(struct canbus_msg *msg)
|
||||
{
|
||||
uint32_t txfqs = CANx->MCAN_TXFQS;
|
||||
if (txfqs & MCAN_TXFQS_TFQF)
|
||||
// No space in transmit fifo - wait for irq
|
||||
return -1;
|
||||
|
||||
uint32_t w_index = ((txfqs & MCAN_TXFQS_TFQPI_Msk) >> MCAN_TXFQS_TFQPI_Pos);
|
||||
struct fdcan_fifo *txfifo = &MSG_RAM.TXFIFO[w_index];
|
||||
uint32_t ids;
|
||||
if (msg->id & CANMSG_ID_EFF)
|
||||
ids = (msg->id & 0x1fffffff) | FDCAN_XTD;
|
||||
else
|
||||
ids = (msg->id & 0x7ff) << 18;
|
||||
ids |= msg->id & CANMSG_ID_RTR ? FDCAN_RTR : 0;
|
||||
txfifo->id_section = ids;
|
||||
txfifo->dlc_section = (msg->dlc & 0x0f) << 16;
|
||||
txfifo->data[0] = msg->data32[0];
|
||||
txfifo->data[1] = msg->data32[1];
|
||||
__DMB();
|
||||
CANx->MCAN_TXBAR;
|
||||
CANx->MCAN_TXBAR = ((uint32_t)1 << w_index);
|
||||
return CANMSG_DATA_LEN(msg);
|
||||
}
|
||||
|
||||
static void
|
||||
can_filter(uint32_t index, uint32_t id)
|
||||
{
|
||||
MSG_RAM.FLS[index] = ((0x2 << 30) // Classic filter
|
||||
| (0x1 << 27) // Store in Rx FIFO 0 if filter matches
|
||||
| (id << 16)
|
||||
| 0x7FF); // mask all enabled
|
||||
}
|
||||
|
||||
// Setup the receive packet filter
|
||||
void
|
||||
canhw_set_filter(uint32_t id)
|
||||
{
|
||||
if (!CONFIG_CANBUS_FILTER)
|
||||
return;
|
||||
/* Request initialisation */
|
||||
CANx->MCAN_CCCR |= MCAN_CCCR_INIT;
|
||||
/* Wait the acknowledge */
|
||||
while (!(CANx->MCAN_CCCR & MCAN_CCCR_INIT))
|
||||
;
|
||||
/* Enable configuration change */
|
||||
CANx->MCAN_CCCR |= MCAN_CCCR_CCE;
|
||||
|
||||
// Load filter
|
||||
can_filter(0, CANBUS_ID_ADMIN);
|
||||
can_filter(1, id);
|
||||
can_filter(2, id + 1);
|
||||
|
||||
uint32_t flssa = (uint32_t)MSG_RAM.FLS
|
||||
- (CCFG_CANxDMABA_Msk & CCFG_CANxDMABA);
|
||||
CANx->MCAN_SIDFC = flssa | ((id ? 3 : 1) << MCAN_SIDFC_LSS_Pos);
|
||||
CANx->MCAN_GFC = 0x02 << MCAN_GFC_ANFS_Pos;
|
||||
|
||||
/* Leave the initialisation mode for the filter */
|
||||
barrier();
|
||||
CANx->MCAN_CCCR &= ~MCAN_CCCR_CCE;
|
||||
CANx->MCAN_CCCR &= ~MCAN_CCCR_INIT;
|
||||
}
|
||||
|
||||
// This function handles CAN global interrupts
|
||||
void
|
||||
CAN_IRQHandler(void)
|
||||
{
|
||||
uint32_t ir = CANx->MCAN_IR;
|
||||
|
||||
if (ir & MCAN_IE_RF0NE) {
|
||||
CANx->MCAN_IR = MCAN_IE_RF0NE;
|
||||
|
||||
uint32_t rxf0s = CANx->MCAN_RXF0S;
|
||||
if (rxf0s & MCAN_RXF0S_F0FL_Msk) {
|
||||
// Read and ack data packet
|
||||
uint32_t idx = (rxf0s & MCAN_RXF0S_F0GI_Msk) >> MCAN_RXF0S_F0GI_Pos;
|
||||
struct fdcan_fifo *rxf0 = &MSG_RAM.RXF0[idx];
|
||||
uint32_t ids = rxf0->id_section;
|
||||
struct canbus_msg msg;
|
||||
if (ids & FDCAN_XTD)
|
||||
msg.id = (ids & 0x1fffffff) | CANMSG_ID_EFF;
|
||||
else
|
||||
msg.id = (ids >> 18) & 0x7ff;
|
||||
msg.id |= ids & FDCAN_RTR ? CANMSG_ID_RTR : 0;
|
||||
msg.dlc = (rxf0->dlc_section >> 16) & 0x0f;
|
||||
msg.data32[0] = rxf0->data[0];
|
||||
msg.data32[1] = rxf0->data[1];
|
||||
barrier();
|
||||
CANx->MCAN_RXF0A = idx;
|
||||
|
||||
// Process packet
|
||||
canbus_process_data(&msg);
|
||||
}
|
||||
}
|
||||
if (ir & FDCAN_IE_TC) {
|
||||
// Tx
|
||||
CANx->MCAN_IR = FDCAN_IE_TC;
|
||||
canbus_notify_tx();
|
||||
}
|
||||
}
|
||||
|
||||
static inline const uint32_t
|
||||
make_btr(uint32_t sjw, // Sync jump width, ... hmm
|
||||
uint32_t time_seg1, // time segment before sample point, 1 .. 16
|
||||
uint32_t time_seg2, // time segment after sample point, 1 .. 8
|
||||
uint32_t brp) // Baud rate prescaler, 1 .. 1024
|
||||
{
|
||||
return (((uint32_t)(sjw-1)) << MCAN_NBTP_NSJW_Pos
|
||||
| ((uint32_t)(time_seg1-1)) << MCAN_NBTP_NTSEG1_Pos
|
||||
| ((uint32_t)(time_seg2-1)) << MCAN_NBTP_NTSEG2_Pos
|
||||
| ((uint32_t)(brp - 1)) << MCAN_NBTP_NBRP_Pos);
|
||||
}
|
||||
|
||||
static inline const uint32_t
|
||||
compute_btr(uint32_t pclock, uint32_t bitrate)
|
||||
{
|
||||
/*
|
||||
Some equations:
|
||||
Tpclock = 1 / pclock
|
||||
Tq = brp * Tpclock
|
||||
Tbs1 = Tq * TS1
|
||||
Tbs2 = Tq * TS2
|
||||
NominalBitTime = Tq + Tbs1 + Tbs2
|
||||
BaudRate = 1/NominalBitTime
|
||||
Bit value sample point is after Tq+Tbs1. Ideal sample point
|
||||
is at 87.5% of NominalBitTime
|
||||
Use the lowest brp where ts1 and ts2 are in valid range
|
||||
*/
|
||||
|
||||
uint32_t bit_clocks = pclock / bitrate; // clock ticks per bit
|
||||
|
||||
uint32_t sjw = 2;
|
||||
uint32_t qs;
|
||||
// Find number of time quantas that gives us the exact wanted bit time
|
||||
for (qs = 18; qs > 9; qs--) {
|
||||
// check that bit_clocks / quantas is an integer
|
||||
uint32_t brp_rem = bit_clocks % qs;
|
||||
if (brp_rem == 0)
|
||||
break;
|
||||
}
|
||||
uint32_t brp = bit_clocks / qs;
|
||||
uint32_t time_seg2 = qs / 8; // sample at ~87.5%
|
||||
uint32_t time_seg1 = qs - (1 + time_seg2);
|
||||
|
||||
return make_btr(sjw, time_seg1, time_seg2, brp);
|
||||
}
|
||||
|
||||
void
|
||||
can_init(void)
|
||||
{
|
||||
if (!CONFIG_USBCANBUS) {
|
||||
// Configure UPLL for USB and CAN
|
||||
PMC->CKGR_UCKR = CKGR_UCKR_UPLLCOUNT(3) | CKGR_UCKR_UPLLEN;
|
||||
while (!(PMC->PMC_SR & PMC_SR_LOCKU))
|
||||
;
|
||||
}
|
||||
|
||||
// Configure PCK5 for CAN use
|
||||
PMC->PMC_PCK[5] = PMC_PCK_CSS_UPLL_CLK | PMC_PCK_PRES(5);
|
||||
while (!(PMC->PMC_SR & PMC_SR_PCKRDY5))
|
||||
;
|
||||
PMC->PMC_SCER |= PMC_SCER_PCK5;
|
||||
|
||||
enable_pclock(CANx_GCLK_ID);
|
||||
|
||||
gpio_peripheral(GPIO_Rx, CAN_FUNCTION_Rx, 1);
|
||||
gpio_peripheral(GPIO_Tx, CAN_FUNCTION_Tx, 0);
|
||||
|
||||
uint32_t pclock = get_pclock_frequency(CANx_GCLK_ID);
|
||||
|
||||
uint32_t btr = compute_btr(pclock, CONFIG_CANBUS_FREQUENCY);
|
||||
|
||||
/*##-1- Configure the CAN #######################################*/
|
||||
|
||||
/* Exit from sleep mode */
|
||||
CANx->MCAN_CCCR &= ~MCAN_CCCR_CSR;
|
||||
/* Wait the acknowledge */
|
||||
while (CANx->MCAN_CCCR & MCAN_CCCR_CSA)
|
||||
;
|
||||
/* Request initialization */
|
||||
CANx->MCAN_CCCR |= MCAN_CCCR_INIT;
|
||||
/* Wait the acknowledge */
|
||||
while (!(CANx->MCAN_CCCR & MCAN_CCCR_INIT))
|
||||
;
|
||||
/* Enable configuration change */
|
||||
CANx->MCAN_CCCR |= MCAN_CCCR_CCE;
|
||||
|
||||
/* Disable protocol exception handling */
|
||||
CANx->MCAN_CCCR |= MCAN_CCCR_PXHD;
|
||||
|
||||
CANx->MCAN_NBTP = btr;
|
||||
|
||||
/* Setup message RAM addresses */
|
||||
uint32_t ccfg = (CCFG_CANxDMABA & ~CCFG_CANxDMABA_Msk);
|
||||
CCFG_CANxDMABA = (ccfg | (((uint32_t)&MSG_RAM)
|
||||
& CCFG_CANxDMABA_Msk));
|
||||
uint32_t f0sa = (uint32_t)MSG_RAM.RXF0
|
||||
- (CCFG_CANxDMABA_Msk & CCFG_CANxDMABA);
|
||||
CANx->MCAN_RXF0C = f0sa
|
||||
| (ARRAY_SIZE(MSG_RAM.RXF0) << MCAN_RXF0C_F0S_Pos);
|
||||
CANx->MCAN_RXESC = (7 << MCAN_RXESC_F1DS_Pos)
|
||||
| (7 << MCAN_RXESC_F0DS_Pos);
|
||||
uint32_t tbsa = (uint32_t)MSG_RAM.TXFIFO
|
||||
- (CCFG_CANxDMABA_Msk & CCFG_CANxDMABA);
|
||||
CANx->MCAN_TXBC = tbsa
|
||||
| (ARRAY_SIZE(MSG_RAM.TXFIFO) << MCAN_TXBC_TFQS_Pos);
|
||||
CANx->MCAN_TXESC = 7 << MCAN_TXESC_TBDS_Pos;
|
||||
|
||||
/* Leave the initialisation mode */
|
||||
CANx->MCAN_CCCR &= ~MCAN_CCCR_CCE;
|
||||
CANx->MCAN_CCCR &= ~MCAN_CCCR_INIT;
|
||||
|
||||
/*##-2- Configure the CAN Filter #######################################*/
|
||||
canhw_set_filter(0);
|
||||
|
||||
/*##-3- Configure Interrupts #################################*/
|
||||
armcm_enable_irq(CAN_IRQHandler, CANx_IRQn, 1);
|
||||
CANx->MCAN_ILE = MCAN_ILE_EINT0;
|
||||
CANx->MCAN_IE = MCAN_IE_RF0NE | FDCAN_IE_TC;
|
||||
}
|
||||
DECL_INIT(can_init);
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "board/armcm_boot.h" // armcm_main
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "board/usb_cdc.h" // usb_request_bootloader
|
||||
#include "board/misc.h" // bootloader_request
|
||||
#include "command.h" // DECL_COMMAND_FLAGS
|
||||
#include "internal.h" // WDT
|
||||
#include "sched.h" // sched_main
|
||||
@@ -14,6 +14,8 @@
|
||||
#define FREQ_PERIPH_DIV (CONFIG_MACH_SAME70 ? 2 : 1)
|
||||
#define FREQ_PERIPH (CONFIG_CLOCK_FREQ / FREQ_PERIPH_DIV)
|
||||
|
||||
#define FREQ_SAME70_CAN 80000000
|
||||
|
||||
/****************************************************************
|
||||
* watchdog handler
|
||||
****************************************************************/
|
||||
@@ -62,6 +64,10 @@ enable_pclock(uint32_t id)
|
||||
uint32_t
|
||||
get_pclock_frequency(uint32_t id)
|
||||
{
|
||||
#if CONFIG_MACH_SAME70
|
||||
if (id == MCAN0_CLOCK_ID || id == MCAN1_CLOCK_ID)
|
||||
return FREQ_SAME70_CAN;
|
||||
#endif
|
||||
return FREQ_PERIPH;
|
||||
}
|
||||
|
||||
@@ -94,7 +100,7 @@ DECL_COMMAND_FLAGS(command_reset, HF_IN_SHUTDOWN, "reset");
|
||||
#endif
|
||||
|
||||
void noinline __aligned(16) // align for predictable flash code access
|
||||
usb_request_bootloader(void)
|
||||
bootloader_request(void)
|
||||
{
|
||||
irq_disable();
|
||||
// Request boot from ROM (instead of boot from flash)
|
||||
|
||||
@@ -70,5 +70,8 @@ void SystemInit( void )
|
||||
|
||||
// Configure PCK6 for TC use
|
||||
PMC->PMC_PCK[6] = PMC_PCK_CSS_MCK | PMC_PCK_PRES(2);
|
||||
PMC->PMC_SCER = PMC_SCER_PCK6;
|
||||
while ( !(PMC->PMC_SR & PMC_SR_PCKRDY6) )
|
||||
{
|
||||
}
|
||||
PMC->PMC_SCER |= PMC_SCER_PCK6;
|
||||
}
|
||||
|
||||
@@ -1,10 +0,0 @@
|
||||
#ifndef __SAM3_USB_CDC_EP_H
|
||||
#define __SAM3_USB_CDC_EP_H
|
||||
|
||||
enum {
|
||||
USB_CDC_EP_ACM = 3,
|
||||
USB_CDC_EP_BULK_OUT = 1,
|
||||
USB_CDC_EP_BULK_IN = 2,
|
||||
};
|
||||
|
||||
#endif // usb_cdc_ep.h
|
||||
@@ -9,11 +9,11 @@ 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_BITBANGING
|
||||
select HAVE_GPIO_HARD_PWM if MACH_SAMX2
|
||||
select HAVE_STRICT_TIMING
|
||||
select HAVE_CHIPID
|
||||
select HAVE_STEPPER_BOTH_EDGE
|
||||
select HAVE_BOOTLOADER_REQUEST
|
||||
|
||||
config HAVE_SERCOM
|
||||
depends on HAVE_GPIO_I2C || HAVE_GPIO_SPI
|
||||
@@ -26,12 +26,18 @@ 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
|
||||
config MACH_SAMD21E18
|
||||
bool "SAMD21E18 (Adafruit Trinket M0)"
|
||||
select MACH_SAMD21
|
||||
config MACH_SAMD21J18
|
||||
bool "SAMD21J18 (ReprapWorld Minitronics v2)"
|
||||
select MACH_SAMD21
|
||||
config MACH_SAMD21E15
|
||||
bool "SAMD21E15"
|
||||
select MACH_SAMD21
|
||||
@@ -47,29 +53,65 @@ choice
|
||||
config MACH_SAMD51P20
|
||||
bool "SAMD51P20 (Adafruit Grand Central)"
|
||||
select MACH_SAMD51
|
||||
config MACH_SAME51J19
|
||||
bool "SAME51J19"
|
||||
select MACH_SAME51
|
||||
config MACH_SAME54P20
|
||||
bool "SAME54P20"
|
||||
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
|
||||
bool
|
||||
select MACH_SAMX5
|
||||
config MACH_SAME51
|
||||
bool
|
||||
select MACH_SAMX5
|
||||
config MACH_SAME54
|
||||
bool
|
||||
select MACH_SAMX5
|
||||
config HAVE_SAMD_CANBUS
|
||||
bool
|
||||
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 "samd21j18a" if MACH_SAMD21J18
|
||||
default "samd21e15a" if MACH_SAMD21E15
|
||||
default "samd51g19a" if MACH_SAMD51G19
|
||||
default "samd51j19a" if MACH_SAMD51J19
|
||||
default "samd51n19a" if MACH_SAMD51N19
|
||||
default "samd51p20a" if MACH_SAMD51P20
|
||||
default "same51j19a" if MACH_SAME51J19
|
||||
default "same54p20a" if MACH_SAME54P20
|
||||
|
||||
config FLASH_SIZE
|
||||
hex
|
||||
default 0x8000 if MACH_SAMD21E15
|
||||
default 0x40000 if MACH_SAMD21G18 || MACH_SAMD21E18
|
||||
default 0x80000 if MACH_SAMD51G19 || MACH_SAMD51J19 || MACH_SAMD51N19
|
||||
default 0x100000 if MACH_SAMD51P20
|
||||
default 0x40000 if MACH_SAMC21G18 || MACH_SAMD21G18 || MACH_SAMD21E18 || MACH_SAMD21J18
|
||||
default 0x80000 if MACH_SAMD51G19 || MACH_SAMD51J19 || MACH_SAMD51N19 || MACH_SAME51J19
|
||||
default 0x100000 if MACH_SAMD51P20 || MACH_SAME54P20
|
||||
|
||||
config FLASH_BOOT_ADDRESS
|
||||
hex
|
||||
default 0x0
|
||||
|
||||
config RAM_START
|
||||
hex
|
||||
@@ -78,26 +120,54 @@ config RAM_START
|
||||
config RAM_SIZE
|
||||
hex
|
||||
default 0x1000 if MACH_SAMD21E15
|
||||
default 0x8000 if MACH_SAMD21G18 || MACH_SAMD21E18
|
||||
default 0x30000 if MACH_SAMD51G19 || MACH_SAMD51J19 || MACH_SAMD51N19
|
||||
default 0x40000 if MACH_SAMD51P20
|
||||
default 0x8000 if MACH_SAMC21G18 || MACH_SAMD21G18 || MACH_SAMD21E18 || MACH_SAMD21J18
|
||||
default 0x30000 if MACH_SAMD51G19 || MACH_SAMD51J19 || MACH_SAMD51N19 || MACH_SAME51J19
|
||||
default 0x40000 if MACH_SAMD51P20 || MACH_SAME54P20
|
||||
|
||||
config STACK_SIZE
|
||||
int
|
||||
default 512
|
||||
|
||||
|
||||
######################################################################
|
||||
# Bootloader
|
||||
######################################################################
|
||||
|
||||
choice
|
||||
prompt "Bootloader offset"
|
||||
config SAMD_FLASH_START_2000
|
||||
depends on MACH_SAMD21
|
||||
bool "8KiB bootloader (Arduino Zero)"
|
||||
config SAMD_FLASH_START_4000
|
||||
bool "16KiB bootloader (Arduino M0, Duet 3 Bootloader)"
|
||||
config SAMD_FLASH_START_0000
|
||||
bool "No bootloader"
|
||||
endchoice
|
||||
config FLASH_APPLICATION_ADDRESS
|
||||
hex
|
||||
default 0x4000 if SAMD_FLASH_START_4000
|
||||
default 0x2000 if SAMD_FLASH_START_2000
|
||||
default 0x0000
|
||||
|
||||
|
||||
######################################################################
|
||||
# Clock
|
||||
######################################################################
|
||||
|
||||
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_SAMD51
|
||||
bool "25Mhz crystal" if MACH_SAMC21 || MACH_SAMX5
|
||||
config CLOCK_REF_INTERNAL
|
||||
bool "Internal clock"
|
||||
bool "Internal clock" if !MACH_SAMC21
|
||||
endchoice
|
||||
|
||||
choice
|
||||
depends on MACH_SAMD51 && LOW_LEVEL_OPTIONS
|
||||
depends on MACH_SAMX5 && LOW_LEVEL_OPTIONS
|
||||
prompt "Processor speed"
|
||||
config SAMD51_FREQ_120
|
||||
bool "120 MHz (standard)"
|
||||
@@ -111,37 +181,76 @@ 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
|
||||
default 120000000 if MACH_SAMD51
|
||||
default 120000000 if MACH_SAMX5
|
||||
|
||||
choice
|
||||
prompt "Bootloader offset"
|
||||
config FLASH_START_2000
|
||||
depends on MACH_SAMD21
|
||||
bool "8KiB bootloader (Arduino Zero)"
|
||||
config FLASH_START_4000
|
||||
bool "16KiB bootloader (Arduino M0)"
|
||||
config FLASH_START_0000
|
||||
bool "No bootloader"
|
||||
endchoice
|
||||
|
||||
config FLASH_START
|
||||
hex
|
||||
default 0x4000 if FLASH_START_4000
|
||||
default 0x2000 if FLASH_START_2000
|
||||
default 0x0000
|
||||
######################################################################
|
||||
# Communication inteface
|
||||
######################################################################
|
||||
|
||||
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)"
|
||||
depends on HAVE_SAMD_CANBUS
|
||||
select CANSERIAL
|
||||
config ATSAMD_MMENU_CANBUS_PA25_PA24
|
||||
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 && !MACH_SAMC21
|
||||
select CANSERIAL
|
||||
config ATSAMD_MMENU_CANBUS_PB15_PB14
|
||||
bool "CAN bus (on PB15/PB14)"
|
||||
depends on HAVE_SAMD_CANBUS
|
||||
select CANSERIAL
|
||||
config ATSAMD_USBCANBUS
|
||||
bool "USB to CAN bus bridge"
|
||||
depends on HAVE_SAMD_CANBUS && HAVE_SAMD_USB
|
||||
select USBCANBUS
|
||||
endchoice
|
||||
choice
|
||||
prompt "CAN bus interface" if USBCANBUS
|
||||
config ATSAMD_CMENU_CANBUS_PA23_PA22
|
||||
bool "CAN bus (on PA23/PA22)"
|
||||
config ATSAMD_CMENU_CANBUS_PB13_PB12
|
||||
bool "CAN bus (on PB13/PB12)"
|
||||
config ATSAMD_CMENU_CANBUS_PB15_PB14
|
||||
bool "CAN bus (on PB15/PB14)"
|
||||
endchoice
|
||||
|
||||
config ATSAMD_CANBUS_PA23_PA22
|
||||
bool
|
||||
default y if ATSAMD_MMENU_CANBUS_PA23_PA22 || ATSAMD_CMENU_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
|
||||
config ATSAMD_CANBUS_PB15_PB14
|
||||
bool
|
||||
default y if ATSAMD_MMENU_CANBUS_PB15_PB14 || ATSAMD_CMENU_CANBUS_PB15_PB14
|
||||
|
||||
endif
|
||||
|
||||
@@ -3,15 +3,16 @@
|
||||
# Setup the toolchain
|
||||
CROSS_PREFIX=arm-none-eabi-
|
||||
|
||||
dirs-y += src/atsamd src/generic
|
||||
dirs-$(CONFIG_MACH_SAMD21) += lib/samd21/samd21a/gcc
|
||||
dirs-$(CONFIG_MACH_SAMD51) += lib/samd51/samd51a/gcc
|
||||
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) += -mcpu=cortex-m4 -Ilib/samd51/samd51a/include
|
||||
CFLAGS += $(CFLAGS-y) -D__$(MCU)__ -mthumb -Ilib/cmsis-core
|
||||
CFLAGS-$(CONFIG_MACH_SAMD51) += -Ilib/samd51/samd51a/include
|
||||
CFLAGS-$(CONFIG_MACH_SAME51) += -Ilib/same51/include
|
||||
CFLAGS-$(CONFIG_MACH_SAMX5) += -mcpu=cortex-m4 -Ilib/same54/include
|
||||
CFLAGS += $(CFLAGS-y) -D__$(MCU)__ -mthumb -Ilib/cmsis-core -Ilib/fast-hash
|
||||
|
||||
CFLAGS_klipper.elf += --specs=nano.specs --specs=nosys.specs
|
||||
CFLAGS_klipper.elf += -T $(OUT)src/generic/armcm_link.ld
|
||||
@@ -22,15 +23,21 @@ src-y += atsamd/main.c atsamd/gpio.c generic/crc16_ccitt.c
|
||||
src-y += generic/armcm_boot.c generic/armcm_irq.c generic/armcm_reset.c
|
||||
src-$(CONFIG_USBSERIAL) += atsamd/usbserial.c atsamd/chipid.c generic/usb_cdc.c
|
||||
src-$(CONFIG_SERIAL) += atsamd/serial.c generic/serial_irq.c
|
||||
canbus-src-y := generic/canserial.c ../lib/fast-hash/fasthash.c
|
||||
canbus-src-y += atsamd/fdcan.c atsamd/chipid.c
|
||||
src-$(CONFIG_USBCANBUS) += $(canbus-src-y) atsamd/usbserial.c generic/usb_canbus.c
|
||||
src-$(CONFIG_CANSERIAL) += $(canbus-src-y) generic/canbus.c
|
||||
src-$(CONFIG_HAVE_GPIO_ADC) += atsamd/adc.c
|
||||
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_SAMD51) += atsamd/samd51_watchdog.c
|
||||
src-$(CONFIG_MACH_SAMD51) += atsamd/samd51_clock.c generic/armcm_timer.c
|
||||
src-$(CONFIG_MACH_SAMX5) += atsamd/samd51_watchdog.c
|
||||
src-$(CONFIG_MACH_SAMX5) += atsamd/samd51_clock.c generic/armcm_timer.c
|
||||
|
||||
# Build the additional hex and bin output files
|
||||
target-y += $(OUT)klipper.bin $(OUT)klipper.elf.hex
|
||||
@@ -49,7 +56,7 @@ lib/bossac/bin/bossac:
|
||||
$(Q)make -C lib/bossac bin/bossac
|
||||
|
||||
BOSSAC_OFFSET-$(CONFIG_MACH_SAMD21) := 0x2000
|
||||
BOSSAC_OFFSET-$(CONFIG_MACH_SAMD51) := 0x4000
|
||||
BOSSAC_OFFSET-$(CONFIG_MACH_SAMX5) := 0x4000
|
||||
|
||||
flash: $(OUT)klipper.bin lib/bossac/bin/bossac
|
||||
@echo " Flashing $< to $(FLASH_DEVICE)"
|
||||
|
||||
@@ -12,7 +12,28 @@
|
||||
#define ADC_TEMPERATURE_PIN 0xfe
|
||||
DECL_ENUMERATION("pin", "ADC_TEMPERATURE", ADC_TEMPERATURE_PIN);
|
||||
|
||||
#if CONFIG_MACH_SAMD21
|
||||
#if CONFIG_MACH_SAMC21
|
||||
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_adc", "PA3");
|
||||
|
||||
#define ADC_INPUTCTRL_MUXNEG_GND ADC_INPUTCTRL_MUXNEG(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,7 +42,8 @@ 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_SAMD51
|
||||
|
||||
#elif CONFIG_MACH_SAMX5
|
||||
|
||||
#define SAMD51_ADC_SYNC(ADC, BIT) \
|
||||
while(ADC->SYNCBUSY.reg & ADC_SYNCBUSY_ ## BIT)
|
||||
@@ -53,7 +75,7 @@ static struct gpio_adc gpio_adc_pin_to_struct(uint8_t pin)
|
||||
}
|
||||
#if CONFIG_MACH_SAMD21
|
||||
Adc* reg = ADC;
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
#elif CONFIG_MACH_SAMC21 || CONFIG_MACH_SAMX5
|
||||
Adc* reg = (chan < 16 ? ADC0 : ADC1);
|
||||
chan %= 16;
|
||||
#endif
|
||||
@@ -69,7 +91,57 @@ 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);
|
||||
|
||||
// Set ADC-DAC VREFA pin to ADC mode
|
||||
gpio_peripheral(GPIO('A', 3), 'B', 0);
|
||||
|
||||
// Reset
|
||||
ADC0->CTRLA.reg = ADC_CTRLA_SWRST;
|
||||
while (ADC0->CTRLA.reg & ADC_CTRLA_SWRST)
|
||||
;
|
||||
ADC1->CTRLA.reg = ADC_CTRLA_SWRST;
|
||||
while (ADC1->CTRLA.reg & ADC_CTRLA_SWRST)
|
||||
;
|
||||
|
||||
// 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_AREFA | ADC_REFCTRL_REFCOMP;
|
||||
ADC0->CTRLB.reg = ADC_CTRLB_PRESCALER_DIV128;
|
||||
ADC0->SAMPCTRL.reg = ADC_SAMPCTRL_SAMPLEN(63);
|
||||
while (ADC0->SYNCBUSY.reg & ADC_SYNCBUSY_SAMPCTRL)
|
||||
;
|
||||
ADC0->CTRLA.reg = ADC_CTRLA_ENABLE;
|
||||
while (ADC0->SYNCBUSY.reg & ADC_SYNCBUSY_ENABLE)
|
||||
;
|
||||
|
||||
// ADC1
|
||||
ADC1->REFCTRL.reg = ADC_REFCTRL_REFSEL_AREFA | ADC_REFCTRL_REFCOMP;
|
||||
ADC1->CTRLB.reg = ADC_CTRLB_PRESCALER_DIV128;
|
||||
ADC1->SAMPCTRL.reg = ADC_SAMPCTRL_SAMPLEN(63);
|
||||
while (ADC1->SYNCBUSY.reg & ADC_SYNCBUSY_SAMPCTRL)
|
||||
;
|
||||
ADC1->CTRLA.reg = ADC_CTRLA_ENABLE;
|
||||
while (ADC1->SYNCBUSY.reg & ADC_SYNCBUSY_ENABLE)
|
||||
;
|
||||
|
||||
#elif CONFIG_MACH_SAMD21
|
||||
// Enable adc clock
|
||||
enable_pclock(ADC_GCLK_ID, ID_ADC);
|
||||
// Load calibraiton info
|
||||
@@ -85,7 +157,7 @@ adc_init(void)
|
||||
ADC->SAMPCTRL.reg = 63;
|
||||
ADC->CTRLA.reg = ADC_CTRLA_ENABLE;
|
||||
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
#elif CONFIG_MACH_SAMX5
|
||||
// Enable adc clock
|
||||
enable_pclock(ADC0_GCLK_ID, ID_ADC0);
|
||||
enable_pclock(ADC1_GCLK_ID, ID_ADC1);
|
||||
@@ -135,7 +207,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 };
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_USB_SERIAL_NUMBER_CHIPID
|
||||
#include "generic/canserial.h" // canserial_set_uuid
|
||||
#include "generic/usb_cdc.h" // usb_fill_serial
|
||||
#include "generic/usbstd.h" // usb_string_descriptor
|
||||
#include "sched.h" // DECL_INIT
|
||||
@@ -25,11 +26,11 @@ usbserial_get_serialid(void)
|
||||
void
|
||||
chipid_init(void)
|
||||
{
|
||||
if (!CONFIG_USB_SERIAL_NUMBER_CHIPID)
|
||||
if (!CONFIG_USB_SERIAL_NUMBER_CHIPID && !CONFIG_CANBUS)
|
||||
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;
|
||||
@@ -40,6 +41,11 @@ chipid_init(void)
|
||||
id[2] = *(uint32_t*)0x00806014;
|
||||
id[3] = *(uint32_t*)0x00806018;
|
||||
}
|
||||
usb_fill_serial(&cdc_chipid.desc, ARRAY_SIZE(cdc_chipid.data), id);
|
||||
|
||||
if (CONFIG_USB_SERIAL_NUMBER_CHIPID)
|
||||
usb_fill_serial(&cdc_chipid.desc, ARRAY_SIZE(cdc_chipid.data), id);
|
||||
|
||||
if (CONFIG_CANBUS)
|
||||
canserial_set_uuid((void*)id, CHIP_UID_LEN);
|
||||
}
|
||||
DECL_INIT(chipid_init);
|
||||
|
||||
@@ -35,11 +35,13 @@ route_pclock(uint32_t pclk_id, uint32_t clkgen_id)
|
||||
|
||||
// Enable a peripheral clock and power to that peripheral
|
||||
void
|
||||
enable_pclock(uint32_t pclk_id, uint32_t pm_id)
|
||||
enable_pclock(uint32_t pclk_id, int32_t pm_id)
|
||||
{
|
||||
route_pclock(pclk_id, CLKGEN_MAIN);
|
||||
uint32_t pm_port = pm_id / 32, pm_bit = 1 << (pm_id % 32);
|
||||
(&PM->APBAMASK.reg)[pm_port] |= pm_bit;
|
||||
if (pm_id >= 0) {
|
||||
uint32_t pm_port = pm_id / 32, pm_bit = 1 << (pm_id % 32);
|
||||
(&PM->APBAMASK.reg)[pm_port] |= pm_bit;
|
||||
}
|
||||
}
|
||||
|
||||
// Return the frequency of the given peripheral clock
|
||||
@@ -89,7 +91,7 @@ clock_init_internal(void)
|
||||
uint32_t fine = GET_FUSE(FUSES_DFLL48M_FINE_CAL);
|
||||
SYSCTRL->DFLLVAL.reg = (SYSCTRL_DFLLVAL_COARSE(coarse)
|
||||
| SYSCTRL_DFLLVAL_FINE(fine));
|
||||
if (CONFIG_USBSERIAL) {
|
||||
if (CONFIG_USB) {
|
||||
// Enable USB clock recovery mode
|
||||
uint32_t mul = DIV_ROUND_CLOSEST(FREQ_MAIN, 1000);
|
||||
SYSCTRL->DFLLMUL.reg = (SYSCTRL_DFLLMUL_FSTEP(10)
|
||||
|
||||
314
src/atsamd/fdcan.c
Normal file
314
src/atsamd/fdcan.c
Normal file
@@ -0,0 +1,314 @@
|
||||
// CANbus support on atsame51 chips
|
||||
//
|
||||
// Copyright (C) 2021-2022 Kevin O'Connor <kevin@koconnor.net>
|
||||
// Copyright (C) 2019 Eug Krashtan <eug.krashtan@gmail.com>
|
||||
// Copyright (C) 2020 Pontus Borg <glpontus@gmail.com>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "command.h" // DECL_CONSTANT_STR
|
||||
#include "generic/armcm_boot.h" // armcm_enable_irq
|
||||
#include "generic/canbus.h" // canbus_notify_tx
|
||||
#include "generic/canserial.h" // CANBUS_ID_ADMIN
|
||||
#include "internal.h" // enable_pclock
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Pin configuration
|
||||
****************************************************************/
|
||||
|
||||
#if CONFIG_ATSAMD_CANBUS_PA23_PA22
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_CAN", "PA23,PA22");
|
||||
#define GPIO_Rx GPIO('A', 23)
|
||||
#define GPIO_Tx GPIO('A', 22)
|
||||
#define CANx_GCLK_ID CAN0_GCLK_ID
|
||||
#elif CONFIG_ATSAMD_CANBUS_PA25_PA24
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_CAN", "PA25,PA24");
|
||||
#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)
|
||||
#define GPIO_Tx GPIO('B', 12)
|
||||
#define CANx_GCLK_ID CAN1_GCLK_ID
|
||||
#elif CONFIG_ATSAMD_CANBUS_PB15_PB14
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_CAN", "PB15,PB14");
|
||||
#define GPIO_Rx GPIO('B', 15)
|
||||
#define GPIO_Tx GPIO('B', 14)
|
||||
#define CANx_GCLK_ID CAN1_GCLK_ID
|
||||
#endif
|
||||
|
||||
#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
|
||||
#else
|
||||
#define CAN_FUNCTION 'H'
|
||||
#define CANx CAN1
|
||||
#define CANx_IRQn CAN1_IRQn
|
||||
#endif
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Message ram layout
|
||||
****************************************************************/
|
||||
|
||||
struct fdcan_fifo {
|
||||
uint32_t id_section;
|
||||
uint32_t dlc_section;
|
||||
uint32_t data[64 / 4];
|
||||
};
|
||||
|
||||
#define FDCAN_XTD (1<<30)
|
||||
#define FDCAN_RTR (1<<29)
|
||||
|
||||
struct fdcan_msg_ram {
|
||||
uint32_t FLS[28]; // Filter list standard
|
||||
uint32_t FLE[16]; // Filter list extended
|
||||
struct fdcan_fifo RXF0[3];
|
||||
struct fdcan_fifo RXF1[3];
|
||||
uint32_t TEF[6]; // Tx event FIFO
|
||||
struct fdcan_fifo TXFIFO[3];
|
||||
};
|
||||
|
||||
// Message ram is in regular memory
|
||||
static struct fdcan_msg_ram MSG_RAM;
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* CANbus code
|
||||
****************************************************************/
|
||||
|
||||
#define FDCAN_IE_TC (CAN_IE_TCE | CAN_IE_TCFE | CAN_IE_TFEE)
|
||||
|
||||
// Transmit a packet
|
||||
int
|
||||
canhw_send(struct canbus_msg *msg)
|
||||
{
|
||||
uint32_t txfqs = CANx->TXFQS.reg;
|
||||
if (txfqs & CAN_TXFQS_TFQF)
|
||||
// No space in transmit fifo - wait for irq
|
||||
return -1;
|
||||
|
||||
uint32_t w_index = ((txfqs & CAN_TXFQS_TFQPI_Msk) >> CAN_TXFQS_TFQPI_Pos);
|
||||
struct fdcan_fifo *txfifo = &MSG_RAM.TXFIFO[w_index];
|
||||
uint32_t ids;
|
||||
if (msg->id & CANMSG_ID_EFF)
|
||||
ids = (msg->id & 0x1fffffff) | FDCAN_XTD;
|
||||
else
|
||||
ids = (msg->id & 0x7ff) << 18;
|
||||
ids |= msg->id & CANMSG_ID_RTR ? FDCAN_RTR : 0;
|
||||
txfifo->id_section = ids;
|
||||
txfifo->dlc_section = (msg->dlc & 0x0f) << 16;
|
||||
txfifo->data[0] = msg->data32[0];
|
||||
txfifo->data[1] = msg->data32[1];
|
||||
__DMB();
|
||||
CANx->TXBAR.reg;
|
||||
CANx->TXBAR.reg = ((uint32_t)1 << w_index);
|
||||
return CANMSG_DATA_LEN(msg);
|
||||
}
|
||||
|
||||
static void
|
||||
can_filter(uint32_t index, uint32_t id)
|
||||
{
|
||||
MSG_RAM.FLS[index] = ((0x2 << 30) // Classic filter
|
||||
| (0x1 << 27) // Store in Rx FIFO 0 if filter matches
|
||||
| (id << 16)
|
||||
| 0x7FF); // mask all enabled
|
||||
}
|
||||
|
||||
// Setup the receive packet filter
|
||||
void
|
||||
canhw_set_filter(uint32_t id)
|
||||
{
|
||||
if (!CONFIG_CANBUS_FILTER)
|
||||
return;
|
||||
/* Request initialisation */
|
||||
CANx->CCCR.reg |= CAN_CCCR_INIT;
|
||||
/* Wait the acknowledge */
|
||||
while (!(CANx->CCCR.reg & CAN_CCCR_INIT))
|
||||
;
|
||||
/* Enable configuration change */
|
||||
CANx->CCCR.reg |= CAN_CCCR_CCE;
|
||||
|
||||
// Load filter
|
||||
can_filter(0, CANBUS_ID_ADMIN);
|
||||
can_filter(1, id);
|
||||
can_filter(2, id + 1);
|
||||
|
||||
uint32_t flssa = (uint32_t)MSG_RAM.FLS - CAN0_MSG_RAM_ADDR;
|
||||
CANx->SIDFC.reg = flssa | ((id ? 3 : 1) << CAN_SIDFC_LSS_Pos);
|
||||
CANx->GFC.reg = 0x02 << CAN_GFC_ANFS_Pos;
|
||||
|
||||
/* Leave the initialisation mode for the filter */
|
||||
barrier();
|
||||
CANx->CCCR.reg &= ~CAN_CCCR_CCE;
|
||||
CANx->CCCR.reg &= ~CAN_CCCR_INIT;
|
||||
}
|
||||
|
||||
// This function handles CAN global interrupts
|
||||
void
|
||||
CAN_IRQHandler(void)
|
||||
{
|
||||
uint32_t ir = CANx->IR.reg;
|
||||
|
||||
if (ir & CAN_IE_RF0NE) {
|
||||
CANx->IR.reg = CAN_IE_RF0NE;
|
||||
|
||||
uint32_t rxf0s = CANx->RXF0S.reg;
|
||||
if (rxf0s & CAN_RXF0S_F0FL_Msk) {
|
||||
// Read and ack data packet
|
||||
uint32_t idx = (rxf0s & CAN_RXF0S_F0GI_Msk) >> CAN_RXF0S_F0GI_Pos;
|
||||
struct fdcan_fifo *rxf0 = &MSG_RAM.RXF0[idx];
|
||||
uint32_t ids = rxf0->id_section;
|
||||
struct canbus_msg msg;
|
||||
if (ids & FDCAN_XTD)
|
||||
msg.id = (ids & 0x1fffffff) | CANMSG_ID_EFF;
|
||||
else
|
||||
msg.id = (ids >> 18) & 0x7ff;
|
||||
msg.id |= ids & FDCAN_RTR ? CANMSG_ID_RTR : 0;
|
||||
msg.dlc = (rxf0->dlc_section >> 16) & 0x0f;
|
||||
msg.data32[0] = rxf0->data[0];
|
||||
msg.data32[1] = rxf0->data[1];
|
||||
barrier();
|
||||
CANx->RXF0A.reg = idx;
|
||||
|
||||
// Process packet
|
||||
canbus_process_data(&msg);
|
||||
}
|
||||
}
|
||||
if (ir & FDCAN_IE_TC) {
|
||||
// Tx
|
||||
CANx->IR.reg = FDCAN_IE_TC;
|
||||
canbus_notify_tx();
|
||||
}
|
||||
}
|
||||
|
||||
static inline const uint32_t
|
||||
make_btr(uint32_t sjw, // Sync jump width, ... hmm
|
||||
uint32_t time_seg1, // time segment before sample point, 1 .. 16
|
||||
uint32_t time_seg2, // time segment after sample point, 1 .. 8
|
||||
uint32_t brp) // Baud rate prescaler, 1 .. 1024
|
||||
{
|
||||
return (((uint32_t)(sjw-1)) << CAN_NBTP_NSJW_Pos
|
||||
| ((uint32_t)(time_seg1-1)) << CAN_NBTP_NTSEG1_Pos
|
||||
| ((uint32_t)(time_seg2-1)) << CAN_NBTP_NTSEG2_Pos
|
||||
| ((uint32_t)(brp - 1)) << CAN_NBTP_NBRP_Pos);
|
||||
}
|
||||
|
||||
static inline const uint32_t
|
||||
compute_btr(uint32_t pclock, uint32_t bitrate)
|
||||
{
|
||||
/*
|
||||
Some equations:
|
||||
Tpclock = 1 / pclock
|
||||
Tq = brp * Tpclock
|
||||
Tbs1 = Tq * TS1
|
||||
Tbs2 = Tq * TS2
|
||||
NominalBitTime = Tq + Tbs1 + Tbs2
|
||||
BaudRate = 1/NominalBitTime
|
||||
Bit value sample point is after Tq+Tbs1. Ideal sample point
|
||||
is at 87.5% of NominalBitTime
|
||||
Use the lowest brp where ts1 and ts2 are in valid range
|
||||
*/
|
||||
|
||||
uint32_t bit_clocks = pclock / bitrate; // clock ticks per bit
|
||||
|
||||
uint32_t sjw = 2;
|
||||
uint32_t qs;
|
||||
// Find number of time quantas that gives us the exact wanted bit time
|
||||
for (qs = 18; qs > 9; qs--) {
|
||||
// check that bit_clocks / quantas is an integer
|
||||
uint32_t brp_rem = bit_clocks % qs;
|
||||
if (brp_rem == 0)
|
||||
break;
|
||||
}
|
||||
uint32_t brp = bit_clocks / qs;
|
||||
uint32_t time_seg2 = qs / 8; // sample at ~87.5%
|
||||
uint32_t time_seg1 = qs - (1 + time_seg2);
|
||||
|
||||
return make_btr(sjw, time_seg1, time_seg2, brp);
|
||||
}
|
||||
|
||||
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);
|
||||
gpio_peripheral(GPIO_Tx, CAN_FUNCTION, 0);
|
||||
|
||||
uint32_t pclock = get_pclock_frequency(CANx_GCLK_ID);
|
||||
|
||||
uint32_t btr = compute_btr(pclock, CONFIG_CANBUS_FREQUENCY);
|
||||
|
||||
/*##-1- Configure the CAN #######################################*/
|
||||
|
||||
/* Exit from sleep mode */
|
||||
CANx->CCCR.reg &= ~CAN_CCCR_CSR;
|
||||
/* Wait the acknowledge */
|
||||
while (CANx->CCCR.reg & CAN_CCCR_CSA)
|
||||
;
|
||||
/* Request initialisation */
|
||||
CANx->CCCR.reg |= CAN_CCCR_INIT;
|
||||
/* Wait the acknowledge */
|
||||
while (!(CANx->CCCR.reg & CAN_CCCR_INIT))
|
||||
;
|
||||
/* Enable configuration change */
|
||||
CANx->CCCR.reg |= CAN_CCCR_CCE;
|
||||
|
||||
/* Disable protocol exception handling */
|
||||
CANx->CCCR.reg |= CAN_CCCR_PXHD;
|
||||
|
||||
CANx->NBTP.reg = btr;
|
||||
|
||||
/* Setup message RAM addresses */
|
||||
uint32_t f0sa = (uint32_t)MSG_RAM.RXF0 - CAN0_MSG_RAM_ADDR;
|
||||
CANx->RXF0C.reg = f0sa | (ARRAY_SIZE(MSG_RAM.RXF0) << CAN_RXF0C_F0S_Pos);
|
||||
CANx->RXESC.reg = (7 << CAN_RXESC_F1DS_Pos) | (7 << CAN_RXESC_F0DS_Pos);
|
||||
uint32_t tbsa = (uint32_t)MSG_RAM.TXFIFO - CAN0_MSG_RAM_ADDR;
|
||||
CANx->TXBC.reg = tbsa | (ARRAY_SIZE(MSG_RAM.TXFIFO) << CAN_TXBC_TFQS_Pos);
|
||||
CANx->TXESC.reg = 7 << CAN_TXESC_TBDS_Pos;
|
||||
|
||||
/* Leave the initialisation mode */
|
||||
CANx->CCCR.reg &= ~CAN_CCCR_CCE;
|
||||
CANx->CCCR.reg &= ~CAN_CCCR_INIT;
|
||||
|
||||
/*##-2- Configure the CAN Filter #######################################*/
|
||||
canhw_set_filter(0);
|
||||
|
||||
/*##-3- Configure Interrupts #################################*/
|
||||
armcm_enable_irq(CAN_IRQHandler, CANx_IRQn, 1);
|
||||
CANx->ILE.reg = CAN_ILE_EINT0;
|
||||
CANx->IE.reg = CAN_IE_RF0NE | FDCAN_IE_TC;
|
||||
}
|
||||
DECL_INIT(can_init);
|
||||
@@ -42,11 +42,11 @@ 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);
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
#elif CONFIG_MACH_SAMX5
|
||||
#define NUM_PORT 4
|
||||
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
|
||||
|
||||
@@ -25,8 +25,6 @@ i2c_init(uint32_t bus, SercomI2cm *si)
|
||||
si->CTRLA.reg = 0;
|
||||
uint32_t areg = (SERCOM_I2CM_CTRLA_LOWTOUTEN
|
||||
| SERCOM_I2CM_CTRLA_INACTOUT(3)
|
||||
| SERCOM_I2CM_STATUS_SEXTTOUT
|
||||
| SERCOM_I2CM_STATUS_MEXTTOUT
|
||||
| SERCOM_I2CM_CTRLA_MODE(5));
|
||||
si->CTRLA.reg = areg;
|
||||
uint32_t freq = sercom_get_pclock_frequency(bus);
|
||||
|
||||
@@ -5,10 +5,16 @@
|
||||
#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"
|
||||
#elif CONFIG_MACH_SAME51
|
||||
#include "same51.h"
|
||||
#elif CONFIG_MACH_SAME54
|
||||
#include "same54.h"
|
||||
#endif
|
||||
|
||||
#define GPIO(PORT, NUM) (((PORT)-'A') * 32 + (NUM))
|
||||
@@ -18,7 +24,7 @@
|
||||
#define GET_FUSE(REG) \
|
||||
((*((uint32_t*)(REG##_ADDR)) & (REG##_Msk)) >> (REG##_Pos))
|
||||
|
||||
void enable_pclock(uint32_t pclk_id, uint32_t pm_id);
|
||||
void enable_pclock(uint32_t pclk_id, int32_t pm_id);
|
||||
uint32_t get_pclock_frequency(uint32_t pclk_id);
|
||||
void gpio_peripheral(uint32_t gpio, char ptype, int32_t pull_up);
|
||||
|
||||
|
||||
@@ -5,9 +5,27 @@
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "board/armcm_boot.h" // armcm_main
|
||||
#include "board/misc.h" // bootloader_request
|
||||
#include "board/io.h" // writel
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "internal.h" // SystemInit
|
||||
#include "sched.h" // sched_main
|
||||
|
||||
void
|
||||
bootloader_request(void)
|
||||
{
|
||||
if (!CONFIG_FLASH_APPLICATION_ADDRESS)
|
||||
return;
|
||||
// Bootloader hack
|
||||
irq_disable();
|
||||
#if CONFIG_MACH_SAMD21
|
||||
writel((void*)0x20007FFC, 0x07738135);
|
||||
#elif CONFIG_MACH_SAMX5
|
||||
writel((void*)(HSRAM_ADDR + HSRAM_SIZE - 4), 0xf01669ef);
|
||||
#endif
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
// Main entry point - called from armcm_boot.c:ResetHandler()
|
||||
void
|
||||
armcm_main(void)
|
||||
|
||||
148
src/atsamd/samc21_clock.c
Normal file
148
src/atsamd/samc21_clock.c
Normal file
@@ -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();
|
||||
}
|
||||
@@ -39,11 +39,13 @@ route_pclock(uint32_t pclk_id, uint32_t clkgen_id)
|
||||
|
||||
// Enable a peripheral clock and power to that peripheral
|
||||
void
|
||||
enable_pclock(uint32_t pclk_id, uint32_t pm_id)
|
||||
enable_pclock(uint32_t pclk_id, int32_t pm_id)
|
||||
{
|
||||
route_pclock(pclk_id, CLKGEN_48M);
|
||||
uint32_t pm_port = pm_id / 32, pm_bit = 1 << (pm_id % 32);
|
||||
(&MCLK->APBAMASK.reg)[pm_port] |= pm_bit;
|
||||
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
|
||||
@@ -157,7 +159,7 @@ static void
|
||||
clock_init_internal(void)
|
||||
{
|
||||
// Enable USB clock recovery mode if applicable
|
||||
if (CONFIG_USBSERIAL) {
|
||||
if (CONFIG_USB) {
|
||||
// Temporarily switch main clock to internal 32K clock
|
||||
gen_clock(CLKGEN_MAIN, GCLK_GENCTRL_SRC_OSCULP32K);
|
||||
|
||||
|
||||
@@ -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'},
|
||||
@@ -127,7 +127,7 @@ static const struct sercom_pad sercom_pads[] = {
|
||||
{ 5, GPIO('B', 3), 1, 'D'},
|
||||
{ 5, GPIO('B', 0), 2, 'D'},
|
||||
{ 5, GPIO('B', 1), 3, 'D'},
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
#elif CONFIG_MACH_SAMX5
|
||||
{ 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
|
||||
|
||||
@@ -61,7 +61,7 @@ serial_init(void)
|
||||
su->CTRLA.reg = areg | SERCOM_USART_CTRLA_ENABLE;
|
||||
#if CONFIG_MACH_SAMD21
|
||||
armcm_enable_irq(SERCOM0_Handler, SERCOM0_IRQn, 0);
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
#elif CONFIG_MACH_SAMX5
|
||||
armcm_enable_irq(SERCOM0_Handler, SERCOM0_0_IRQn, 0);
|
||||
armcm_enable_irq(SERCOM0_Handler, SERCOM0_1_IRQn, 0);
|
||||
armcm_enable_irq(SERCOM0_Handler, SERCOM0_2_IRQn, 0);
|
||||
|
||||
@@ -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();
|
||||
|
||||
@@ -5,10 +5,9 @@
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memcpy
|
||||
#include "autoconf.h" // CONFIG_FLASH_START
|
||||
#include "autoconf.h" // CONFIG_MACH_SAMD21
|
||||
#include "board/armcm_boot.h" // armcm_enable_irq
|
||||
#include "board/io.h" // readl
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "board/io.h" // writeb
|
||||
#include "board/usb_cdc.h" // usb_notify_ep0
|
||||
#include "board/usb_cdc_ep.h" // USB_CDC_EP_BULK_IN
|
||||
#include "command.h" // DECL_CONSTANT_STR
|
||||
@@ -171,21 +170,6 @@ usb_set_configure(void)
|
||||
USB_DEVICE_EPINTENSET_TRCPT0 | USB_DEVICE_EPINTENSET_TRCPT1);
|
||||
}
|
||||
|
||||
void
|
||||
usb_request_bootloader(void)
|
||||
{
|
||||
if (!CONFIG_FLASH_START)
|
||||
return;
|
||||
// Bootloader hack
|
||||
irq_disable();
|
||||
#if CONFIG_MACH_SAMD21
|
||||
writel((void*)0x20007FFC, 0x07738135);
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
writel((void*)(HSRAM_ADDR + HSRAM_SIZE - 4), 0xf01669ef);
|
||||
#endif
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Setup and interrupts
|
||||
@@ -252,7 +236,7 @@ usbserial_init(void)
|
||||
USB->DEVICE.INTENSET.reg = USB_DEVICE_INTENSET_EORST;
|
||||
#if CONFIG_MACH_SAMD21
|
||||
armcm_enable_irq(USB_Handler, USB_IRQn, 1);
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
#elif CONFIG_MACH_SAMX5
|
||||
armcm_enable_irq(USB_Handler, USB_0_IRQn, 1);
|
||||
armcm_enable_irq(USB_Handler, USB_1_IRQn, 1);
|
||||
armcm_enable_irq(USB_Handler, USB_2_IRQn, 1);
|
||||
|
||||
@@ -10,8 +10,8 @@ config AVR_SELECT
|
||||
select HAVE_GPIO_SPI
|
||||
select HAVE_GPIO_I2C
|
||||
select HAVE_GPIO_HARD_PWM
|
||||
select HAVE_GPIO_BITBANGING if !MACH_atmega168
|
||||
select HAVE_STRICT_TIMING
|
||||
select HAVE_LIMITED_CODE_SIZE if MACH_atmega168 || MACH_atmega328 || MACH_atmega328p
|
||||
|
||||
config BOARD_DIRECTORY
|
||||
string
|
||||
|
||||
@@ -27,31 +27,27 @@ static const uint8_t SCL = GPIO('D', 0), SDA = GPIO('D', 1);
|
||||
DECL_CONSTANT_STR("BUS_PINS_twi", "PD0,PD1");
|
||||
#endif
|
||||
|
||||
static void
|
||||
i2c_init(void)
|
||||
{
|
||||
if (TWCR & (1<<TWEN))
|
||||
// Already setup
|
||||
return;
|
||||
|
||||
// Setup output pins and enable pullups
|
||||
gpio_out_setup(SDA, 1);
|
||||
gpio_out_setup(SCL, 1);
|
||||
|
||||
// Set 100Khz frequency
|
||||
TWSR = 0;
|
||||
TWBR = ((CONFIG_CLOCK_FREQ / 100000) - 16) / 2;
|
||||
|
||||
// Enable interface
|
||||
TWCR = (1<<TWEN);
|
||||
}
|
||||
|
||||
struct i2c_config
|
||||
i2c_setup(uint32_t bus, uint32_t rate, uint8_t addr)
|
||||
{
|
||||
if (bus)
|
||||
shutdown("Unsupported i2c bus");
|
||||
i2c_init();
|
||||
|
||||
if (!(TWCR & (1<<TWEN))) {
|
||||
// Setup output pins and enable pullups
|
||||
gpio_out_setup(SDA, 1);
|
||||
gpio_out_setup(SCL, 1);
|
||||
|
||||
// Set frequency avoiding pulling in integer divide
|
||||
TWSR = 0;
|
||||
if (rate >= 400000)
|
||||
TWBR = ((CONFIG_CLOCK_FREQ / 400000) - 16) / 2;
|
||||
else
|
||||
TWBR = ((CONFIG_CLOCK_FREQ / 100000) - 16) / 2;
|
||||
|
||||
// Enable interface
|
||||
TWCR = (1<<TWEN);
|
||||
}
|
||||
return (struct i2c_config){ .addr=addr<<1 };
|
||||
}
|
||||
|
||||
|
||||
@@ -178,11 +178,6 @@ usb_set_configure(void)
|
||||
UEIENX = 1<<TXINE;
|
||||
}
|
||||
|
||||
void
|
||||
usb_request_bootloader(void)
|
||||
{
|
||||
}
|
||||
|
||||
#if CONFIG_MACH_at90usb1286
|
||||
#define UHWCON_Init ((1<<UIMOD) | (1<<UVREGE))
|
||||
#define PLLCSR_Init ((1<<PLLP2) | (1<<PLLP0) | (1<<PLLE))
|
||||
|
||||
@@ -4,14 +4,14 @@
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_FLASH_START
|
||||
#include "autoconf.h" // CONFIG_FLASH_APPLICATION_ADDRESS
|
||||
|
||||
OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
|
||||
OUTPUT_ARCH(arm)
|
||||
|
||||
MEMORY
|
||||
{
|
||||
rom (rx) : ORIGIN = CONFIG_FLASH_START , LENGTH = CONFIG_FLASH_SIZE
|
||||
rom (rx) : ORIGIN = CONFIG_FLASH_APPLICATION_ADDRESS , LENGTH = CONFIG_FLASH_SIZE
|
||||
ram (rwx) : ORIGIN = CONFIG_RAM_START , LENGTH = CONFIG_RAM_SIZE
|
||||
}
|
||||
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "armcm_reset.h" // try_request_canboot
|
||||
#include "autoconf.h" // CONFIG_FLASH_START
|
||||
#include "autoconf.h" // CONFIG_FLASH_APPLICATION_ADDRESS
|
||||
#include "board/internal.h" // NVIC_SystemReset
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "command.h" // DECL_COMMAND_FLAGS
|
||||
@@ -17,20 +17,22 @@
|
||||
static void
|
||||
canboot_reset(uint64_t req_signature)
|
||||
{
|
||||
if (!(CONFIG_FLASH_START & 0x00FFFFFF))
|
||||
if (CONFIG_FLASH_APPLICATION_ADDRESS == CONFIG_FLASH_BOOT_ADDRESS)
|
||||
// No bootloader
|
||||
return;
|
||||
uint32_t *bl_vectors = (uint32_t *)(CONFIG_FLASH_START & 0xFF000000);
|
||||
uint32_t *bl_vectors = (uint32_t *)CONFIG_FLASH_BOOT_ADDRESS;
|
||||
uint64_t *boot_sig = (uint64_t *)(bl_vectors[1] - 9);
|
||||
uint64_t *req_sig = (uint64_t *)bl_vectors[0];
|
||||
if (boot_sig == (void *)ALIGN((size_t)boot_sig, 8) &&
|
||||
*boot_sig == CANBOOT_SIGNATURE &&
|
||||
req_sig == (void *)ALIGN((size_t)req_sig, 8))
|
||||
{
|
||||
irq_disable();
|
||||
*req_sig = req_signature;
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
if (boot_sig != (void*)ALIGN((size_t)boot_sig, 8)
|
||||
|| *boot_sig != CANBOOT_SIGNATURE
|
||||
|| req_sig != (void*)ALIGN((size_t)req_sig, 8))
|
||||
return;
|
||||
irq_disable();
|
||||
*req_sig = req_signature;
|
||||
#if __CORTEX_M >= 7
|
||||
SCB_CleanDCache_by_Addr((void*)req_sig, sizeof(*req_sig));
|
||||
#endif
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
@@ -4,19 +4,23 @@
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "canbus.h" // canbus_send
|
||||
#include "canserial.h" // canserial_send
|
||||
#include "autoconf.h" // CONFIG_CANBUS_FREQUENCY
|
||||
#include "canbus.h" // canhw_send
|
||||
#include "canserial.h" // canserial_notify_tx
|
||||
#include "command.h" // DECL_CONSTANT
|
||||
|
||||
DECL_CONSTANT("CANBUS_FREQUENCY", CONFIG_CANBUS_FREQUENCY);
|
||||
|
||||
int
|
||||
canserial_send(struct canbus_msg *msg)
|
||||
canbus_send(struct canbus_msg *msg)
|
||||
{
|
||||
return canbus_send(msg);
|
||||
return canhw_send(msg);
|
||||
}
|
||||
|
||||
void
|
||||
canserial_set_filter(uint32_t id)
|
||||
canbus_set_filter(uint32_t id)
|
||||
{
|
||||
canbus_set_filter(id);
|
||||
canhw_set_filter(id);
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
@@ -18,10 +18,12 @@ struct canbus_msg {
|
||||
#define CANMSG_DATA_LEN(msg) ((msg)->dlc > 8 ? 8 : (msg)->dlc)
|
||||
|
||||
// callbacks provided by board specific code
|
||||
int canbus_send(struct canbus_msg *msg);
|
||||
void canbus_set_filter(uint32_t id);
|
||||
int canhw_send(struct canbus_msg *msg);
|
||||
void canhw_set_filter(uint32_t id);
|
||||
|
||||
// canbus.c
|
||||
int canbus_send(struct canbus_msg *msg);
|
||||
void canbus_set_filter(uint32_t id);
|
||||
void canbus_notify_tx(void);
|
||||
void canbus_process_data(struct canbus_msg *msg);
|
||||
|
||||
|
||||
@@ -7,11 +7,11 @@
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memcpy
|
||||
#include "board/armcm_reset.h" // try_request_canboot
|
||||
#include "autoconf.h" // CONFIG_HAVE_BOOTLOADER_REQUEST
|
||||
#include "board/io.h" // readb
|
||||
#include "board/irq.h" // irq_save
|
||||
#include "board/misc.h" // console_sendf
|
||||
#include "canbus.h" // canbus_set_uuid
|
||||
#include "canbus.h" // canbus_send
|
||||
#include "canserial.h" // canserial_notify_tx
|
||||
#include "command.h" // DECL_CONSTANT
|
||||
#include "fasthash.h" // fasthash64
|
||||
@@ -69,7 +69,7 @@ canserial_tx_task(void)
|
||||
break;
|
||||
msg.dlc = now;
|
||||
memcpy(msg.data, &CanData.transmit_buf[tpos], now);
|
||||
int ret = canserial_send(&msg);
|
||||
int ret = canbus_send(&msg);
|
||||
if (ret <= 0)
|
||||
break;
|
||||
tpos += now;
|
||||
@@ -153,7 +153,7 @@ can_process_query_unassigned(struct canbus_msg *msg)
|
||||
send.data[7] = CANBUS_CMD_SET_KLIPPER_NODEID;
|
||||
// Send with retry
|
||||
for (;;) {
|
||||
int ret = canserial_send(&send);
|
||||
int ret = canbus_send(&send);
|
||||
if (ret >= 0)
|
||||
return;
|
||||
}
|
||||
@@ -163,7 +163,7 @@ static void
|
||||
can_id_conflict(void)
|
||||
{
|
||||
CanData.assigned_id = 0;
|
||||
canserial_set_filter(CanData.assigned_id);
|
||||
canbus_set_filter(CanData.assigned_id);
|
||||
shutdown("Another CAN node assigned this ID");
|
||||
}
|
||||
|
||||
@@ -176,7 +176,7 @@ can_process_set_klipper_nodeid(struct canbus_msg *msg)
|
||||
if (can_check_uuid(msg)) {
|
||||
if (newid != CanData.assigned_id) {
|
||||
CanData.assigned_id = newid;
|
||||
canserial_set_filter(CanData.assigned_id);
|
||||
canbus_set_filter(CanData.assigned_id);
|
||||
}
|
||||
} else if (newid == CanData.assigned_id) {
|
||||
can_id_conflict();
|
||||
@@ -186,9 +186,9 @@ can_process_set_klipper_nodeid(struct canbus_msg *msg)
|
||||
static void
|
||||
can_process_request_bootloader(struct canbus_msg *msg)
|
||||
{
|
||||
if (!can_check_uuid(msg))
|
||||
if (!CONFIG_HAVE_BOOTLOADER_REQUEST || !can_check_uuid(msg))
|
||||
return;
|
||||
try_request_canboot();
|
||||
bootloader_request();
|
||||
}
|
||||
|
||||
// Handle an "admin" command
|
||||
@@ -224,7 +224,7 @@ canserial_notify_rx(void)
|
||||
DECL_CONSTANT("RECEIVE_WINDOW", ARRAY_SIZE(CanData.receive_buf));
|
||||
|
||||
// Handle incoming data (called from IRQ handler)
|
||||
int
|
||||
void
|
||||
canserial_process_data(struct canbus_msg *msg)
|
||||
{
|
||||
uint32_t id = msg->id;
|
||||
@@ -233,7 +233,7 @@ canserial_process_data(struct canbus_msg *msg)
|
||||
int rpos = CanData.receive_pos;
|
||||
uint32_t len = CANMSG_DATA_LEN(msg);
|
||||
if (len > sizeof(CanData.receive_buf) - rpos)
|
||||
return -1;
|
||||
return;
|
||||
memcpy(&CanData.receive_buf[rpos], msg->data, len);
|
||||
CanData.receive_pos = rpos + len;
|
||||
canserial_notify_rx();
|
||||
@@ -243,13 +243,12 @@ canserial_process_data(struct canbus_msg *msg)
|
||||
uint32_t pushp = CanData.admin_push_pos;
|
||||
if (pushp >= CanData.admin_pull_pos + ARRAY_SIZE(CanData.admin_queue))
|
||||
// No space - drop message
|
||||
return -1;
|
||||
return;
|
||||
uint32_t pos = pushp % ARRAY_SIZE(CanData.admin_queue);
|
||||
memcpy(&CanData.admin_queue[pos], msg, sizeof(*msg));
|
||||
CanData.admin_push_pos = pushp + 1;
|
||||
canserial_notify_rx();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Remove from the receive buffer the given number of bytes
|
||||
|
||||
@@ -6,14 +6,10 @@
|
||||
#define CANBUS_ID_ADMIN 0x3f0
|
||||
#define CANBUS_ID_ADMIN_RESP 0x3f1
|
||||
|
||||
// callbacks provided by board specific code
|
||||
struct canbus_msg;
|
||||
int canserial_send(struct canbus_msg *msg);
|
||||
void canserial_set_filter(uint32_t id);
|
||||
|
||||
// canserial.c
|
||||
void canserial_notify_tx(void);
|
||||
int canserial_process_data(struct canbus_msg *msg);
|
||||
struct canbus_msg;
|
||||
void canserial_process_data(struct canbus_msg *msg);
|
||||
void canserial_set_uuid(uint8_t *raw_uuid, uint32_t raw_uuid_len);
|
||||
|
||||
#endif // canbus.h
|
||||
#endif // canserial.h
|
||||
|
||||
@@ -18,4 +18,6 @@ void *dynmem_end(void);
|
||||
|
||||
uint16_t crc16_ccitt(uint8_t *buf, uint_fast8_t len);
|
||||
|
||||
void bootloader_request(void);
|
||||
|
||||
#endif // misc.h
|
||||
|
||||
@@ -79,6 +79,9 @@ console_task(void)
|
||||
if (ret > 0)
|
||||
command_dispatch(receive_buf, pop_count);
|
||||
if (ret) {
|
||||
if (CONFIG_HAVE_BOOTLOADER_REQUEST && ret < 0 && pop_count == 32
|
||||
&& !memcmp(receive_buf, " \x1c Request Serial Bootloader!! ~", 32))
|
||||
bootloader_request();
|
||||
console_pop_input(pop_count);
|
||||
if (ret > 0)
|
||||
command_send_ack();
|
||||
|
||||
@@ -13,6 +13,7 @@
|
||||
#include "board/pgm.h" // PROGMEM
|
||||
#include "board/usb_cdc_ep.h" // USB_CDC_EP_BULK_IN
|
||||
#include "byteorder.h" // cpu_to_le16
|
||||
#include "command.h" // DECL_CONSTANT
|
||||
#include "generic/usbstd.h" // struct usb_device_descriptor
|
||||
#include "sched.h" // sched_wake_task
|
||||
#include "usb_cdc.h" // usb_notify_ep0
|
||||
@@ -103,20 +104,18 @@ struct gs_host_frame {
|
||||
static struct usbcan_data {
|
||||
struct task_wake wake;
|
||||
|
||||
// Canbus data from host
|
||||
union {
|
||||
struct gs_host_frame host_frame;
|
||||
uint8_t rx_frame_pad[USB_CDC_EP_BULK_OUT_SIZE];
|
||||
};
|
||||
uint8_t host_status;
|
||||
|
||||
// Canbus data routed locally
|
||||
uint8_t notify_local;
|
||||
uint8_t notify_local, usb_send_busy;
|
||||
uint32_t assigned_id;
|
||||
|
||||
// Canbus data from host
|
||||
uint8_t host_status;
|
||||
uint32_t host_pull_pos, host_push_pos;
|
||||
struct gs_host_frame host_frames[16];
|
||||
|
||||
// Data from physical canbus interface
|
||||
uint32_t pull_pos, push_pos;
|
||||
struct canbus_msg queue[8];
|
||||
uint32_t canhw_pull_pos, canhw_push_pos;
|
||||
struct canbus_msg canhw_queue[32];
|
||||
} UsbCan;
|
||||
|
||||
enum {
|
||||
@@ -125,6 +124,8 @@ enum {
|
||||
HS_TX_LOCAL = 4,
|
||||
};
|
||||
|
||||
DECL_CONSTANT("CANBUS_BRIDGE", 1);
|
||||
|
||||
void
|
||||
canbus_notify_tx(void)
|
||||
{
|
||||
@@ -136,16 +137,16 @@ void
|
||||
canbus_process_data(struct canbus_msg *msg)
|
||||
{
|
||||
// Add to admin command queue
|
||||
uint32_t pushp = UsbCan.push_pos;
|
||||
if (pushp - UsbCan.pull_pos >= ARRAY_SIZE(UsbCan.queue))
|
||||
uint32_t pushp = UsbCan.canhw_push_pos;
|
||||
if (pushp - UsbCan.canhw_pull_pos >= ARRAY_SIZE(UsbCan.canhw_queue))
|
||||
// No space - drop message
|
||||
return;
|
||||
if (UsbCan.assigned_id && (msg->id & ~1) == UsbCan.assigned_id)
|
||||
// Id reserved for local
|
||||
return;
|
||||
uint32_t pos = pushp % ARRAY_SIZE(UsbCan.queue);
|
||||
memcpy(&UsbCan.queue[pos], msg, sizeof(*msg));
|
||||
UsbCan.push_pos = pushp + 1;
|
||||
uint32_t pos = pushp % ARRAY_SIZE(UsbCan.canhw_queue);
|
||||
memcpy(&UsbCan.canhw_queue[pos], msg, sizeof(*msg));
|
||||
UsbCan.canhw_push_pos = pushp + 1;
|
||||
usb_notify_bulk_out();
|
||||
}
|
||||
|
||||
@@ -163,21 +164,44 @@ send_frame(struct canbus_msg *msg)
|
||||
}
|
||||
|
||||
// Send any pending hw frames to host
|
||||
static int
|
||||
drain_hw_queue(void)
|
||||
static void
|
||||
drain_canhw_queue(void)
|
||||
{
|
||||
uint32_t pull_pos = UsbCan.canhw_pull_pos;
|
||||
for (;;) {
|
||||
uint32_t push_pos = readl(&UsbCan.push_pos);
|
||||
uint32_t pull_pos = UsbCan.pull_pos;
|
||||
if (push_pos != pull_pos) {
|
||||
uint32_t pos = pull_pos % ARRAY_SIZE(UsbCan.queue);
|
||||
int ret = send_frame(&UsbCan.queue[pos]);
|
||||
if (ret < 0)
|
||||
return -1;
|
||||
UsbCan.pull_pos = pull_pos + 1;
|
||||
continue;
|
||||
uint32_t push_pos = readl(&UsbCan.canhw_push_pos);
|
||||
if (push_pos == pull_pos) {
|
||||
// No more data to send
|
||||
UsbCan.usb_send_busy = 0;
|
||||
return;
|
||||
}
|
||||
return 0;
|
||||
uint32_t pos = pull_pos % ARRAY_SIZE(UsbCan.canhw_queue);
|
||||
int ret = send_frame(&UsbCan.canhw_queue[pos]);
|
||||
if (ret < 0) {
|
||||
// USB is busy - retry later
|
||||
UsbCan.usb_send_busy = 1;
|
||||
return;
|
||||
}
|
||||
UsbCan.canhw_pull_pos = pull_pos = pull_pos + 1;
|
||||
}
|
||||
}
|
||||
|
||||
// Fill local queue with any USB messages sent from host
|
||||
static void
|
||||
fill_usb_host_queue(void)
|
||||
{
|
||||
uint32_t pull_pos = UsbCan.host_pull_pos, push_pos = UsbCan.host_push_pos;
|
||||
for (;;) {
|
||||
if (push_pos - pull_pos >= ARRAY_SIZE(UsbCan.host_frames))
|
||||
// No more space in queue
|
||||
break;
|
||||
uint32_t pushp = push_pos % ARRAY_SIZE(UsbCan.host_frames);
|
||||
struct gs_host_frame *gs = &UsbCan.host_frames[pushp];
|
||||
int ret = usb_read_bulk_out(gs, sizeof(*gs));
|
||||
if (ret <= 0)
|
||||
// No more messages ready
|
||||
break;
|
||||
UsbCan.host_push_pos = push_pos = push_pos + 1;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -186,79 +210,79 @@ usbcan_task(void)
|
||||
{
|
||||
if (!sched_check_wake(&UsbCan.wake))
|
||||
return;
|
||||
for (;;) {
|
||||
// Send any pending hw frames to host
|
||||
int ret = drain_hw_queue();
|
||||
if (ret < 0)
|
||||
return;
|
||||
|
||||
// Send any pending hw frames to host
|
||||
drain_canhw_queue();
|
||||
|
||||
// Fill local queue with any USB messages arriving from host
|
||||
fill_usb_host_queue();
|
||||
|
||||
// Route messages received from host
|
||||
uint32_t pull_pos = UsbCan.host_pull_pos, push_pos = UsbCan.host_push_pos;
|
||||
uint32_t pullp = pull_pos % ARRAY_SIZE(UsbCan.host_frames);
|
||||
struct gs_host_frame *gs = &UsbCan.host_frames[pullp];
|
||||
for (;;) {
|
||||
// See if previous host frame needs to be transmitted
|
||||
uint_fast8_t host_status = UsbCan.host_status;
|
||||
if (host_status & (HS_TX_HW | HS_TX_LOCAL)) {
|
||||
struct gs_host_frame *gs = &UsbCan.host_frame;
|
||||
struct canbus_msg msg;
|
||||
msg.id = gs->can_id;
|
||||
msg.dlc = gs->can_dlc;
|
||||
msg.data32[0] = gs->data32[0];
|
||||
msg.data32[1] = gs->data32[1];
|
||||
if (host_status & HS_TX_LOCAL) {
|
||||
canserial_process_data(&msg);
|
||||
UsbCan.host_status = host_status = host_status & ~HS_TX_LOCAL;
|
||||
}
|
||||
if (host_status & HS_TX_HW) {
|
||||
ret = canbus_send(&msg);
|
||||
int ret = canhw_send(&msg);
|
||||
if (ret < 0)
|
||||
return;
|
||||
break;
|
||||
UsbCan.host_status = host_status = host_status & ~HS_TX_HW;
|
||||
}
|
||||
if (host_status & HS_TX_LOCAL) {
|
||||
ret = canserial_process_data(&msg);
|
||||
if (ret < 0) {
|
||||
usb_notify_bulk_out();
|
||||
return;
|
||||
}
|
||||
UsbCan.host_status = host_status & ~HS_TX_LOCAL;
|
||||
}
|
||||
continue;
|
||||
}
|
||||
|
||||
// Send any previous echo frames
|
||||
if (host_status) {
|
||||
ret = usb_send_bulk_in(&UsbCan.host_frame
|
||||
, sizeof(UsbCan.host_frame));
|
||||
if (UsbCan.notify_local || UsbCan.usb_send_busy)
|
||||
// Don't send echo frame until other traffic is sent
|
||||
break;
|
||||
int ret = usb_send_bulk_in(gs, sizeof(*gs));
|
||||
if (ret < 0)
|
||||
return;
|
||||
UsbCan.host_status = 0;
|
||||
continue;
|
||||
UsbCan.host_pull_pos = pull_pos = pull_pos + 1;
|
||||
}
|
||||
|
||||
// See if can read a new frame from host
|
||||
ret = usb_read_bulk_out(&UsbCan.host_frame, USB_CDC_EP_BULK_OUT_SIZE);
|
||||
if (ret > 0) {
|
||||
uint32_t id = UsbCan.host_frame.can_id;
|
||||
UsbCan.host_status = HS_TX_ECHO | HS_TX_HW;
|
||||
if (id == CANBUS_ID_ADMIN)
|
||||
UsbCan.host_status = HS_TX_ECHO | HS_TX_HW | HS_TX_LOCAL;
|
||||
else if (UsbCan.assigned_id && UsbCan.assigned_id == id)
|
||||
UsbCan.host_status = HS_TX_ECHO | HS_TX_LOCAL;
|
||||
continue;
|
||||
}
|
||||
|
||||
// No more work to be done
|
||||
if (UsbCan.notify_local) {
|
||||
UsbCan.notify_local = 0;
|
||||
canserial_notify_tx();
|
||||
}
|
||||
return;
|
||||
// Process next frame from host
|
||||
if (pull_pos == push_pos)
|
||||
// No frame available - no more work to be done
|
||||
break;
|
||||
gs = &UsbCan.host_frames[pull_pos % ARRAY_SIZE(UsbCan.host_frames)];
|
||||
uint32_t id = gs->can_id;
|
||||
UsbCan.host_status = HS_TX_ECHO | HS_TX_HW;
|
||||
if (id == CANBUS_ID_ADMIN)
|
||||
UsbCan.host_status = HS_TX_ECHO | HS_TX_HW | HS_TX_LOCAL;
|
||||
else if (UsbCan.assigned_id && UsbCan.assigned_id == id)
|
||||
UsbCan.host_status = HS_TX_ECHO | HS_TX_LOCAL;
|
||||
}
|
||||
|
||||
// Wake up local message response handling (if usb is not busy)
|
||||
if (UsbCan.notify_local && !UsbCan.usb_send_busy)
|
||||
canserial_notify_tx();
|
||||
}
|
||||
DECL_TASK(usbcan_task);
|
||||
|
||||
int
|
||||
canserial_send(struct canbus_msg *msg)
|
||||
canbus_send(struct canbus_msg *msg)
|
||||
{
|
||||
int ret = drain_hw_queue();
|
||||
if (ret < 0)
|
||||
goto retry_later;
|
||||
ret = send_frame(msg);
|
||||
if (UsbCan.usb_send_busy)
|
||||
goto retry_later;
|
||||
int ret = send_frame(msg);
|
||||
if (ret < 0)
|
||||
goto retry_later;
|
||||
if (UsbCan.notify_local && UsbCan.host_status)
|
||||
canbus_notify_tx();
|
||||
UsbCan.notify_local = 0;
|
||||
return msg->dlc;
|
||||
retry_later:
|
||||
@@ -267,7 +291,7 @@ retry_later:
|
||||
}
|
||||
|
||||
void
|
||||
canserial_set_filter(uint32_t id)
|
||||
canbus_set_filter(uint32_t id)
|
||||
{
|
||||
UsbCan.assigned_id = id;
|
||||
}
|
||||
|
||||
@@ -446,9 +446,11 @@ static uint8_t line_control_state;
|
||||
static void
|
||||
check_reboot(void)
|
||||
{
|
||||
if (!CONFIG_HAVE_BOOTLOADER_REQUEST)
|
||||
return;
|
||||
if (line_coding.dwDTERate == 1200 && !(line_control_state & 0x01))
|
||||
// A baud of 1200 is an Arduino style request to enter the bootloader
|
||||
usb_request_bootloader();
|
||||
bootloader_request();
|
||||
}
|
||||
|
||||
static void
|
||||
|
||||
@@ -21,7 +21,6 @@ int_fast8_t usb_send_ep0_progmem(const void *data, uint_fast8_t len);
|
||||
void usb_stall_ep0(void);
|
||||
void usb_set_address(uint_fast8_t addr);
|
||||
void usb_set_configure(void);
|
||||
void usb_request_bootloader(void);
|
||||
struct usb_string_descriptor *usbserial_get_serialid(void);
|
||||
|
||||
// usb_cdc.c
|
||||
|
||||
102
src/hc32f460/Kconfig
Normal file
102
src/hc32f460/Kconfig
Normal file
@@ -0,0 +1,102 @@
|
||||
# Kconfig settings for Huada HC32F460 processor
|
||||
|
||||
if MACH_HC32F460
|
||||
|
||||
config HC32F460_SELECT
|
||||
bool
|
||||
default y
|
||||
select HAVE_GPIO
|
||||
select HAVE_GPIO_ADC
|
||||
select HAVE_STRICT_TIMING
|
||||
select HAVE_GPIO_HARD_PWM
|
||||
select HAVE_STEPPER_BOTH_EDGE
|
||||
|
||||
config BOARD_DIRECTORY
|
||||
string
|
||||
default "hc32f460"
|
||||
|
||||
|
||||
######################################################################
|
||||
# Communication interface
|
||||
######################################################################
|
||||
choice
|
||||
prompt "Communication interface"
|
||||
config HC32F460_SERIAL_PA7_PA8
|
||||
bool "Serial (PA7 & PA8)"
|
||||
select SERIAL
|
||||
config HC32F460_SERIAL_PA13_PA14
|
||||
bool "Serial (PA13 & PA14)"
|
||||
select SERIAL
|
||||
config HC32F460_SERIAL_PA3_PA2
|
||||
bool "Serial (PA3 & PA2)"
|
||||
select SERIAL
|
||||
config HC32F460_SERIAL_PH2_PB10
|
||||
bool "Serial (PH2 & PB10)"
|
||||
select SERIAL
|
||||
config HC32F460_SERIAL_PA15_PA9
|
||||
bool "Serial (PA15 & PA09)"
|
||||
select SERIAL
|
||||
config HC32F460_SERIAL_PC0_PC1
|
||||
bool "Serial (PC0 & PC1)"
|
||||
select SERIAL
|
||||
endchoice
|
||||
|
||||
######################################################################
|
||||
# Bootloader
|
||||
# bootloader moves code and then VTOR.RESET points here:
|
||||
######################################################################
|
||||
config FLASH_SIZE
|
||||
hex
|
||||
default 0x40000
|
||||
|
||||
choice "Application Address"
|
||||
prompt "Application Address"
|
||||
config HC32F460_FLASH_APPLICATION_ADDRESS_0x008000
|
||||
bool "0x008000"
|
||||
config HC32F460_FLASH_APPLICATION_ADDRESS_0x00C000
|
||||
bool "0x00C000"
|
||||
config HC32F460_FLASH_APPLICATION_ADDRESS_0x010000
|
||||
bool "0x010000"
|
||||
endchoice
|
||||
|
||||
config FLASH_APPLICATION_ADDRESS
|
||||
hex
|
||||
default 0x008000 if HC32F460_FLASH_APPLICATION_ADDRESS_0x008000
|
||||
default 0x00C000 if HC32F460_FLASH_APPLICATION_ADDRESS_0x00C000
|
||||
default 0x010000 if HC32F460_FLASH_APPLICATION_ADDRESS_0x010000
|
||||
|
||||
config FLASH_BOOT_ADDRESS
|
||||
hex
|
||||
default 0x0
|
||||
|
||||
config RAM_SIZE
|
||||
hex
|
||||
default 0x8000
|
||||
|
||||
# use the fast RAM in the HC32F460
|
||||
config RAM_START
|
||||
hex
|
||||
default 0x1fff8000
|
||||
|
||||
config STACK_SIZE
|
||||
int
|
||||
default 1024
|
||||
|
||||
choice "Clock Speed"
|
||||
prompt "Clock Speed"
|
||||
config HC32F460_CLOCK_SPEED_168M
|
||||
bool "168 MHz"
|
||||
config HC32F460_CLOCK_SPEED_200M
|
||||
bool "200 MHz"
|
||||
endchoice
|
||||
|
||||
config CLOCK_FREQ
|
||||
int
|
||||
default 200000000 if HC32F460_CLOCK_SPEED_200M
|
||||
default 168000000 if HC32F460_CLOCK_SPEED_168M
|
||||
|
||||
config MCU
|
||||
string
|
||||
default "HC32F460"
|
||||
|
||||
endif
|
||||
37
src/hc32f460/Makefile
Normal file
37
src/hc32f460/Makefile
Normal file
@@ -0,0 +1,37 @@
|
||||
# hc32f460 build rules
|
||||
|
||||
# Setup the toolchain
|
||||
CROSS_PREFIX=arm-none-eabi-
|
||||
|
||||
dirs-y += src/hc32f460 src/generic lib/hc32f460/driver/src lib/hc32f460/mcu/common
|
||||
|
||||
CFLAGS += -mthumb -mcpu=cortex-m4 -Isrc/hc32f460 -Ilib/hc32f460/driver/inc -Ilib/hc32f460/mcu/common -Ilib/cmsis-core -DHC32F460
|
||||
|
||||
CFLAGS_klipper.elf += --specs=nano.specs --specs=nosys.specs
|
||||
CFLAGS_klipper.elf += -T $(OUT)src/generic/armcm_link.ld
|
||||
$(OUT)klipper.elf: $(OUT)src/generic/armcm_link.ld
|
||||
|
||||
# Add source files
|
||||
src-y += hc32f460/main.c
|
||||
src-y += hc32f460/interrupts.c
|
||||
src-y += hc32f460/gpio.c
|
||||
src-y += ../lib/hc32f460/mcu/common/system_hc32f460.c
|
||||
src-y += ../lib/hc32f460/driver/src/hc32f460_clk.c
|
||||
src-y += ../lib/hc32f460/driver/src/hc32f460_efm.c
|
||||
src-y += ../lib/hc32f460/driver/src/hc32f460_sram.c
|
||||
src-y += ../lib/hc32f460/driver/src/hc32f460_utility.c
|
||||
src-y += ../lib/hc32f460/driver/src/hc32f460_gpio.c
|
||||
src-y += ../lib/hc32f460/driver/src/hc32f460_pwc.c
|
||||
src-$(CONFIG_HAVE_GPIO_ADC) += hc32f460/adc.c ../lib/hc32f460/driver/src/hc32f460_adc.c
|
||||
src-$(CONFIG_SERIAL) += hc32f460/serial.c generic/serial_irq.c ../lib/hc32f460/driver/src/hc32f460_usart.c
|
||||
src-$(CONFIG_HAVE_GPIO_HARD_PWM) += hc32f460/hard_pwm.c ../lib/hc32f460/driver/src/hc32f460_timera.c
|
||||
src-y += generic/armcm_boot.c generic/armcm_irq.c generic/armcm_timer.c
|
||||
src-y += generic/armcm_reset.c generic/crc16_ccitt.c
|
||||
|
||||
|
||||
# Build the additional bin output file
|
||||
target-y += $(OUT)klipper.bin
|
||||
|
||||
$(OUT)klipper.bin: $(OUT)klipper.elf
|
||||
@echo " Creating bin file $@"
|
||||
$(Q)$(OBJCOPY) -O binary $< $@
|
||||
155
src/hc32f460/adc.c
Normal file
155
src/hc32f460/adc.c
Normal file
@@ -0,0 +1,155 @@
|
||||
// ADC functions on Huada HC32F460
|
||||
//
|
||||
// Copyright (C) 2022 Steven Gotthardt <gotthardt@gmail.com>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "generic/misc.h" // timer_from_us
|
||||
#include "command.h" // shutdown
|
||||
#include "board/gpio.h" // gpio_adc_setup
|
||||
#include "board/internal.h" // GPIO
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
// library
|
||||
#include "hc32f460_adc.h"
|
||||
#include "hc32f460_pwc.h"
|
||||
#include "hc32f460_gpio.h"
|
||||
|
||||
#define ADC_RESOLUTION_12BIT (12u)
|
||||
#define ADC_RESOLUTION_10BIT (10u)
|
||||
#define ADC_RESOLUTION_8BIT (8u)
|
||||
|
||||
#define ADC1_RESOLUTION (ADC_RESOLUTION_12BIT)
|
||||
#define ADC1_PRECISION (1ul << ADC1_RESOLUTION)
|
||||
|
||||
#if ADC1_RESOLUTION == ADC_RESOLUTION_12BIT
|
||||
#define AdcResolution AdcResolution_12Bit
|
||||
#elif ADC1_RESOLUTION == ADC_RESOLUTION_10BIT
|
||||
#define AdcResolution AdcResolution_10Bit
|
||||
#else
|
||||
#define AdcResolution AdcResolution_8Bit
|
||||
#endif
|
||||
|
||||
|
||||
/* Timeout value definitions. Found in example code */
|
||||
#define TIMEOUT_VAL (30u)
|
||||
|
||||
DECL_CONSTANT("ADC_MAX", ADC1_PRECISION-1);
|
||||
|
||||
// These pins can be used for ADC
|
||||
static const uint8_t adc_gpio[] = {
|
||||
GPIO('A', 0), // Chan 0
|
||||
GPIO('A', 1), // Chan 1
|
||||
GPIO('A', 2), // Chan 2
|
||||
GPIO('A', 3), // Chan 3
|
||||
GPIO('A', 4), // Chan 4
|
||||
GPIO('A', 5), // Chan 5
|
||||
GPIO('A', 6), // Chan 6
|
||||
GPIO('A', 7), // Chan 7
|
||||
GPIO('B', 0), // Chan 8
|
||||
GPIO('B', 1), // Chan 9
|
||||
GPIO('C', 0), // Chan 10 // TBed on TriGorilla
|
||||
GPIO('C', 1), // Chan 11 // THead on TriGorilla
|
||||
GPIO('C', 2), // Chan 12
|
||||
GPIO('C', 3), // Chan 13
|
||||
GPIO('C', 4), // Chan 14 // TBed on aquilla
|
||||
GPIO('C', 5), // Chan 15 // THead on aquilla
|
||||
};
|
||||
|
||||
|
||||
struct gpio_adc
|
||||
gpio_adc_setup(uint32_t gpio)
|
||||
{
|
||||
// validate pin in adc_pins table
|
||||
int chan;
|
||||
for (chan=0; ; chan++)
|
||||
{
|
||||
if (chan >= ARRAY_SIZE(adc_gpio))
|
||||
{
|
||||
shutdown("Not a valid ADC pin");
|
||||
}
|
||||
if (adc_gpio[chan] == gpio)
|
||||
{
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// set as analog
|
||||
gpio_peripheral(gpio, Pin_Mode_Ana, 0);
|
||||
|
||||
uint8_t sampleTime[ARRAY_SIZE(adc_gpio)] = { TIMEOUT_VAL }; // all chans
|
||||
stc_adc_ch_cfg_t stcAdcChan;
|
||||
stcAdcChan.u32Channel = 1 << chan;
|
||||
stcAdcChan.u8Sequence = ADC_SEQ_A; // all conversions are in SEQ A
|
||||
stcAdcChan.pu8SampTime = sampleTime;
|
||||
ADC_AddAdcChannel(M4_ADC1, &stcAdcChan);
|
||||
|
||||
return (struct gpio_adc){ .chan = 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)
|
||||
{
|
||||
// true if the sequence is finished
|
||||
if (ADC_GetEocFlag(M4_ADC1, ADC_SEQ_A))
|
||||
{
|
||||
// all conversions are done - clear the flag
|
||||
ADC_ClrEocFlag(M4_ADC1, ADC_SEQ_A);
|
||||
return 0;
|
||||
}
|
||||
else if (M4_ADC1->STR & 1)
|
||||
{
|
||||
// running but not done yet
|
||||
return timer_from_us(TIMEOUT_VAL/2);
|
||||
}
|
||||
else
|
||||
{
|
||||
// not running - so start
|
||||
ADC_StartConvert(M4_ADC1);
|
||||
}
|
||||
|
||||
return timer_from_us(TIMEOUT_VAL);
|
||||
}
|
||||
|
||||
|
||||
// Read a value; use only after gpio_adc_sample() returns zero
|
||||
uint16_t
|
||||
gpio_adc_read(struct gpio_adc g)
|
||||
{
|
||||
// return the one we want...
|
||||
return ADC_GetValue(M4_ADC1, g.chan);
|
||||
}
|
||||
|
||||
|
||||
// Cancel a sample that may have been started with gpio_adc_sample()
|
||||
void
|
||||
gpio_adc_cancel_sample(struct gpio_adc g)
|
||||
{
|
||||
ADC_StopConvert(M4_ADC1);
|
||||
}
|
||||
|
||||
|
||||
// The clocks are already set by the loader.
|
||||
// There is ADC1 and ADC2. Sequences do all channels at once.
|
||||
void
|
||||
adc_init(void)
|
||||
{
|
||||
// PCLK2 (ADC clock) is 'divide by 4', Max ADC clock is 60MHz
|
||||
stc_adc_init_t stcAdcInit = {0};
|
||||
stcAdcInit.enResolution = AdcResolution; // see define above
|
||||
stcAdcInit.enDataAlign = AdcDataAlign_Right;
|
||||
stcAdcInit.enAutoClear = AdcClren_Disable;
|
||||
stcAdcInit.enScanMode = AdcMode_SAOnce;
|
||||
|
||||
// power-on ADC
|
||||
PWC_Fcg3PeriphClockCmd(PWC_FCG3_PERIPH_ADC1, Enable);
|
||||
|
||||
// only using ADC1
|
||||
ADC_Init(M4_ADC1, &stcAdcInit);
|
||||
}
|
||||
|
||||
DECL_INIT(adc_init);
|
||||
153
src/hc32f460/gpio.c
Normal file
153
src/hc32f460/gpio.c
Normal file
@@ -0,0 +1,153 @@
|
||||
// GPIO functions on HC32F460
|
||||
//
|
||||
// Copyright (C) 2022 Steven Gotthardt <gotthardt@gmail.com>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // ffs
|
||||
#include "board/irq.h" // irq_save
|
||||
#include "command.h" // DECL_ENUMERATION_RANGE
|
||||
#include "board/gpio.h" // gpio_out_setup
|
||||
#include "internal.h"
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
#include "hc32f460_gpio.h"
|
||||
|
||||
|
||||
// 64pin package
|
||||
DECL_ENUMERATION_RANGE("pin", "PA0", GPIO('A', 0), 16);
|
||||
DECL_ENUMERATION_RANGE("pin", "PB0", GPIO('B', 0), 16);
|
||||
DECL_ENUMERATION_RANGE("pin", "PC0", GPIO('C', 0), 16);
|
||||
DECL_ENUMERATION_RANGE("pin", "PD2", GPIO('D', 2), 1);
|
||||
DECL_ENUMERATION_RANGE("pin", "PH2", PortH * 16 + 2, 1); // H: special case
|
||||
|
||||
|
||||
// HC32F460 ports are in one M4_PORT - offset by 0x10
|
||||
// eg toggle: M4_PORT->POTRA + 0x10 => M4_PORT->POTRB
|
||||
// 'gpio' is port (0-4) * 16 + pinPosition (0-15)
|
||||
#define POTR_OFFSET offsetof(M4_PORT_TypeDef, POTRA) // output flip
|
||||
#define PODR_OFFSET offsetof(M4_PORT_TypeDef, PODRA) // output data
|
||||
#define PIDR_OFFSET offsetof(M4_PORT_TypeDef, PIDRA) // input data
|
||||
#define POSR_OFFSET offsetof(M4_PORT_TypeDef, POSRA) // output set
|
||||
#define PORR_OFFSET offsetof(M4_PORT_TypeDef, PORRA) // output reset
|
||||
#define PORT_OFFSET offsetof(M4_PORT_TypeDef, PIDRB) // space between PORTS
|
||||
|
||||
|
||||
|
||||
void
|
||||
gpio_peripheral(uint32_t gpio, int func, int pull_up)
|
||||
{
|
||||
stc_port_init_t stcPortInit;
|
||||
|
||||
irqstatus_t flag = irq_save();
|
||||
|
||||
stcPortInit.enPinMode = func;
|
||||
stcPortInit.enLatch = Disable;
|
||||
stcPortInit.enExInt = Disable;
|
||||
stcPortInit.enInvert = Disable;
|
||||
stcPortInit.enPullUp = pull_up ? Enable : Disable;
|
||||
stcPortInit.enPinDrv = Pin_Drv_L;
|
||||
stcPortInit.enPinOType = Pin_OType_Cmos;
|
||||
stcPortInit.enPinSubFunc = Disable;
|
||||
|
||||
// make the port GPIO and disable the sub functionality
|
||||
PORT_SetFunc(GPIO2PORT(gpio), GPIO2BIT(gpio), Func_Gpio, Disable);
|
||||
PORT_Init(GPIO2PORT(gpio), GPIO2BIT(gpio), &stcPortInit);
|
||||
|
||||
irq_restore(flag);
|
||||
}
|
||||
|
||||
|
||||
struct gpio_out
|
||||
gpio_out_setup(uint32_t gpio, uint32_t val)
|
||||
{
|
||||
uint32_t port = (uint32_t)M4_PORT + GPIO2PORT(gpio) * PORT_OFFSET;
|
||||
struct gpio_out g =
|
||||
{ .gpio = gpio, .portAddress = port, .bitMask = GPIO2BIT(gpio) };
|
||||
gpio_out_reset(g, val);
|
||||
|
||||
return g;
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
gpio_out_reset(struct gpio_out g, uint32_t val)
|
||||
{
|
||||
irqstatus_t flag = irq_save();
|
||||
if (val)
|
||||
{
|
||||
uint16_t *POSRx = (uint16_t *)(g.portAddress + POSR_OFFSET);
|
||||
*POSRx = g.bitMask;
|
||||
}
|
||||
else
|
||||
{
|
||||
uint16_t *PORRx = (uint16_t *)(g.portAddress + PORR_OFFSET);
|
||||
*PORRx = g.bitMask;
|
||||
}
|
||||
|
||||
gpio_peripheral(g.gpio, Pin_Mode_Out, 0);
|
||||
irq_restore(flag);
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
gpio_out_toggle_noirq(struct gpio_out g)
|
||||
{
|
||||
uint16_t *POTRx = (uint16_t *)(g.portAddress + POTR_OFFSET);
|
||||
*POTRx = g.bitMask;
|
||||
}
|
||||
|
||||
|
||||
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, uint32_t val)
|
||||
{
|
||||
if (val)
|
||||
{
|
||||
uint16_t *POSRx = (uint16_t *)(g.portAddress + POSR_OFFSET);
|
||||
*POSRx = g.bitMask;
|
||||
}
|
||||
else
|
||||
{
|
||||
uint16_t *PORRx = (uint16_t *)(g.portAddress + PORR_OFFSET);
|
||||
*PORRx = g.bitMask;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
struct gpio_in
|
||||
gpio_in_setup(uint32_t gpio, int32_t pull_up)
|
||||
{
|
||||
uint32_t port = (uint32_t)M4_PORT + GPIO2PORT(gpio) * PORT_OFFSET;
|
||||
|
||||
struct gpio_in g =
|
||||
{ .gpio = gpio, .portAddress = port, .bitMask = GPIO2BIT(gpio) };
|
||||
gpio_in_reset(g, pull_up);
|
||||
|
||||
return g;
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
gpio_in_reset(struct gpio_in g, int32_t pull_up)
|
||||
{
|
||||
irqstatus_t flag = irq_save();
|
||||
gpio_peripheral(g.gpio, Pin_Mode_In, pull_up);
|
||||
irq_restore(flag);
|
||||
}
|
||||
|
||||
|
||||
uint8_t
|
||||
gpio_in_read(struct gpio_in g)
|
||||
{
|
||||
uint16_t *PIDRx = (uint16_t *)(g.portAddress + PIDR_OFFSET);
|
||||
return !!(*PIDRx & g.bitMask);
|
||||
}
|
||||
62
src/hc32f460/gpio.h
Normal file
62
src/hc32f460/gpio.h
Normal file
@@ -0,0 +1,62 @@
|
||||
#ifndef __HC32F460_GPIO_H
|
||||
#define __HC32F460_GPIO_H
|
||||
|
||||
#include <stdint.h> // uint32_t
|
||||
|
||||
|
||||
struct gpio_out {
|
||||
uint32_t portAddress; // M4_PORT or offset
|
||||
uint16_t gpio; // the mangled pin+port
|
||||
uint16_t bitMask; // the pin shifted to use in register
|
||||
};
|
||||
struct gpio_out gpio_out_setup(uint32_t gpio, uint32_t val);
|
||||
void gpio_out_reset(struct gpio_out g, uint32_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, uint32_t val);
|
||||
|
||||
struct gpio_in {
|
||||
uint32_t portAddress;
|
||||
uint16_t gpio;
|
||||
uint16_t bitMask;
|
||||
};
|
||||
struct gpio_in gpio_in_setup(uint32_t gpio, int32_t pull_up);
|
||||
void gpio_in_reset(struct gpio_in g, int32_t pull_up);
|
||||
uint8_t gpio_in_read(struct gpio_in g);
|
||||
|
||||
struct gpio_pwm {
|
||||
void *timer;
|
||||
uint32_t chan;
|
||||
};
|
||||
struct gpio_pwm gpio_pwm_setup(uint8_t gpio, uint32_t cycle_time, uint8_t val);
|
||||
void gpio_pwm_write(struct gpio_pwm g, uint32_t val);
|
||||
|
||||
// all ADC operations will be on ADC1
|
||||
struct gpio_adc {
|
||||
uint32_t chan;
|
||||
};
|
||||
struct gpio_adc gpio_adc_setup(uint32_t gpio);
|
||||
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 *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);
|
||||
|
||||
struct i2c_config {
|
||||
void *i2c;
|
||||
uint8_t addr;
|
||||
};
|
||||
|
||||
struct i2c_config i2c_setup(uint32_t bus, uint32_t rate, uint8_t addr);
|
||||
void i2c_write(struct i2c_config config, uint8_t write_len, uint8_t *write);
|
||||
void i2c_read(struct i2c_config config, uint8_t reg_len, uint8_t *reg
|
||||
, uint8_t read_len, uint8_t *read);
|
||||
|
||||
#endif // gpio.h
|
||||
164
src/hc32f460/hard_pwm.c
Normal file
164
src/hc32f460/hard_pwm.c
Normal file
@@ -0,0 +1,164 @@
|
||||
// Hardware PWM support on HC32F460
|
||||
//
|
||||
// Copyright (C) 2022 Steven Gotthardt <gotthardt@gmail.com>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h"
|
||||
#include "board/irq.h" // irq_save
|
||||
#include "command.h" // shutdown
|
||||
#include "board/gpio.h" // gpio_pwm_write
|
||||
#include "internal.h" // GPIO
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
// library
|
||||
#include "hc32f460_timera.h"
|
||||
#include "hc32f460_pwc.h"
|
||||
#include "hc32f460_gpio.h"
|
||||
|
||||
|
||||
#define MAX_PWM ((1 << 16) - 1)
|
||||
DECL_CONSTANT("PWM_MAX", MAX_PWM);
|
||||
|
||||
// timer A (general purpose) has 6 units and each has 8 PWM
|
||||
// M4_TMRA_TypeDef* timer;
|
||||
|
||||
struct gpio_pwm_info {
|
||||
uint8_t gpio;
|
||||
uint8_t unit; // 6 units in Timer A
|
||||
en_timera_channel_t chan;
|
||||
};
|
||||
|
||||
// Timer A (general purpose) is only timer used
|
||||
// These are for pin function 4 only
|
||||
// Some PWM come out on more than 1 pin
|
||||
// 64pin package
|
||||
static const struct gpio_pwm_info pwm_mapping[] = {
|
||||
{GPIO('A', 0), 2, TimeraCh1},
|
||||
{GPIO('A', 1), 2, TimeraCh2},
|
||||
{GPIO('A', 2), 2, TimeraCh3},
|
||||
{GPIO('A', 3), 2, TimeraCh4},
|
||||
{GPIO('A', 5), 2, TimeraCh1},
|
||||
{GPIO('A', 8), 1, TimeraCh1},
|
||||
{GPIO('A', 9), 1, TimeraCh2},
|
||||
{GPIO('A',10), 1, TimeraCh3},
|
||||
{GPIO('A',11), 1, TimeraCh4},
|
||||
{GPIO('A',13), 2, TimeraCh5},
|
||||
{GPIO('A',14), 2, TimeraCh6},
|
||||
{GPIO('A',15), 2, TimeraCh1},
|
||||
{GPIO('B', 0), 1, TimeraCh6},
|
||||
{GPIO('B', 1), 1, TimeraCh7},
|
||||
{GPIO('B', 2), 1, TimeraCh8},
|
||||
{GPIO('B', 3), 2, TimeraCh2},
|
||||
{GPIO('B', 4), 3, TimeraCh1},
|
||||
{GPIO('B', 5), 3, TimeraCh2},
|
||||
{GPIO('B', 6), 4, TimeraCh1},
|
||||
{GPIO('B', 7), 4, TimeraCh2},
|
||||
{GPIO('B', 8), 4, TimeraCh3},
|
||||
{GPIO('B', 9), 4, TimeraCh4},
|
||||
{GPIO('B',10), 2, TimeraCh3},
|
||||
{GPIO('B',12), 1, TimeraCh8},
|
||||
{GPIO('B',13), 1, TimeraCh5},
|
||||
{GPIO('B',14), 1, TimeraCh6},
|
||||
{GPIO('B',15), 1, TimeraCh7},
|
||||
{GPIO('C', 0), 2, TimeraCh5},
|
||||
{GPIO('C', 1), 2, TimeraCh6},
|
||||
{GPIO('C', 2), 2, TimeraCh7},
|
||||
{GPIO('C', 3), 2, TimeraCh8},
|
||||
{GPIO('C', 6), 3, TimeraCh1},
|
||||
{GPIO('C', 7), 3, TimeraCh2},
|
||||
{GPIO('C', 8), 3, TimeraCh3},
|
||||
{GPIO('C', 9), 3, TimeraCh4},
|
||||
{GPIO('C',10), 2, TimeraCh7},
|
||||
{GPIO('C',11), 2, TimeraCh8},
|
||||
{GPIO('C',13), 4, TimeraCh8},
|
||||
{GPIO('C',14), 4, TimeraCh5},
|
||||
{GPIO('C',15), 4, TimeraCh6},
|
||||
{GPIO('D', 2), 2, TimeraCh4},
|
||||
};
|
||||
|
||||
|
||||
struct gpio_pwm
|
||||
gpio_pwm_setup(uint8_t gpio, uint32_t cycle_time, uint8_t val)
|
||||
{
|
||||
// Find gpio pin in pwm_regs table
|
||||
const struct gpio_pwm_info* p = pwm_mapping;
|
||||
for (;; p++) {
|
||||
if (p >= &pwm_mapping[ARRAY_SIZE(pwm_mapping)])
|
||||
shutdown("Not a valid PWM pin");
|
||||
if (p->gpio == gpio)
|
||||
break;
|
||||
}
|
||||
|
||||
// select registers - could make it programmatic
|
||||
// All TimerA power control bits are in PWC_FCG2
|
||||
M4_TMRA_TypeDef *timerA;
|
||||
switch (p->unit)
|
||||
{
|
||||
default:
|
||||
case 1:
|
||||
timerA = M4_TMRA1;
|
||||
PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIMA1, Enable);
|
||||
break;
|
||||
case 2:
|
||||
timerA = M4_TMRA2;
|
||||
PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIMA2, Enable);
|
||||
break;
|
||||
case 3:
|
||||
timerA = M4_TMRA3;
|
||||
PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIMA3, Enable);
|
||||
break;
|
||||
case 4:
|
||||
timerA = M4_TMRA4;
|
||||
PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIMA4, Enable);
|
||||
break;
|
||||
case 5:
|
||||
timerA = M4_TMRA5;
|
||||
PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIMA5, Enable);
|
||||
break;
|
||||
case 6:
|
||||
timerA = M4_TMRA6;
|
||||
PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIMA6, Enable);
|
||||
break;
|
||||
}
|
||||
|
||||
// set the function - only using #4 (Func_Tima0)
|
||||
PORT_SetFunc(GPIO2PORT(gpio), GPIO2PIN(gpio), Func_Tima0, Disable);
|
||||
|
||||
/* Configuration timera unit 1 base structure */
|
||||
stc_timera_base_init_t stcTimeraInit;
|
||||
stcTimeraInit.enClkDiv = TimeraPclkDiv128; // 128 chosen - use below
|
||||
stcTimeraInit.enCntMode = TimeraCountModeTriangularWave;
|
||||
stcTimeraInit.enCntDir = TimeraCountDirUp;
|
||||
stcTimeraInit.enSyncStartupEn = Disable;
|
||||
stcTimeraInit.u16PeriodVal = cycle_time / 2U / 128U / 2;
|
||||
TIMERA_BaseInit(timerA, &stcTimeraInit);
|
||||
|
||||
/* Configuration timera unit 1 compare structure */
|
||||
stc_timera_compare_init_t stcTimerCompareInit;
|
||||
stcTimerCompareInit.u16CompareVal = stcTimeraInit.u16PeriodVal * 4u / 5u;
|
||||
stcTimerCompareInit.enStartCountOutput = TimeraCountStartOutputHigh;
|
||||
stcTimerCompareInit.enStopCountOutput = TimeraCountStopOutputHigh;
|
||||
stcTimerCompareInit.enCompareMatchOutput = TimeraCompareMatchOutputReverse;
|
||||
stcTimerCompareInit.enPeriodMatchOutput = TimeraPeriodMatchOutputKeep;
|
||||
stcTimerCompareInit.enSpecifyOutput = TimeraSpecifyOutputInvalid;
|
||||
stcTimerCompareInit.enCacheEn = Disable;
|
||||
stcTimerCompareInit.enTriangularTroughTransEn = Enable;
|
||||
stcTimerCompareInit.enTriangularCrestTransEn = Disable;
|
||||
stcTimerCompareInit.u16CompareCacheVal = stcTimerCompareInit.u16CompareVal;
|
||||
TIMERA_CompareInit(timerA, p->chan, &stcTimerCompareInit);
|
||||
TIMERA_CompareCmd(timerA, p->chan, Enable);
|
||||
|
||||
// default setup - all disabled
|
||||
stc_timera_hw_startup_config_t stcTimeraHwConfig = { 0 };
|
||||
TIMERA_HwStartupConfig(timerA, &stcTimeraHwConfig);
|
||||
|
||||
return (struct gpio_pwm){.timer = timerA, .chan = p->chan};
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
gpio_pwm_write(struct gpio_pwm g, uint32_t val)
|
||||
{
|
||||
TIMERA_SetCompareValue(g.timer, g.chan, (uint16_t)val);
|
||||
}
|
||||
29
src/hc32f460/internal.h
Normal file
29
src/hc32f460/internal.h
Normal file
@@ -0,0 +1,29 @@
|
||||
#ifndef __HC32F460_INTERNAL_H
|
||||
#define __HC32F460_INTERNAL_H
|
||||
|
||||
|
||||
// Local definitions for Huada HC32F460
|
||||
|
||||
#include "autoconf.h"
|
||||
#include "hc32f460.h"
|
||||
|
||||
// The HC32F460 library uses a port address and a shifted pin bit
|
||||
// eg en_result_t PORT_Toggle(en_port_t enPort, uint16_t u16Pin);
|
||||
// see hc32f460_gpio.h
|
||||
|
||||
|
||||
// encode and decode gpio ports and pins
|
||||
#define GPIO(PORT, NUM) (((PORT)-'A') * 16 + (NUM))
|
||||
#define GPIO2PORT(GPIO) ((GPIO) / 16)
|
||||
#define GPIO2BIT(GPIO) (1<<((GPIO) % 16))
|
||||
#define GPIO2PIN(GPIO) ((GPIO) % 16)
|
||||
|
||||
#define GPIO_INPUT 0
|
||||
#define GPIO_OUTPUT 1
|
||||
|
||||
void gpio_peripheral(uint32_t pin, int func, int pull_up);
|
||||
|
||||
// from local interrupts.c - helper
|
||||
void IrqRegistration(en_int_src_t irqSrc, IRQn_Type irqType);
|
||||
|
||||
#endif // internal.h
|
||||
29
src/hc32f460/interrupts.c
Normal file
29
src/hc32f460/interrupts.c
Normal file
@@ -0,0 +1,29 @@
|
||||
// Interrupt support for HC32F460
|
||||
// The library interrupt support is huge and redefines systick
|
||||
//
|
||||
// Copyright (C) 2022 Steven Gotthardt <gotthardt@gmail.com>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "hc32f460.h"
|
||||
|
||||
#define IRQ_PRIORITY_DEFAULT 15u
|
||||
|
||||
/* the interrupts on the hc32f460 can be 're-assigned'
|
||||
The author can choose the irqType (IRQ000_Handler, etc...)
|
||||
that the source (irqSrc) triggers
|
||||
*/
|
||||
|
||||
void IrqRegistration(en_int_src_t irqSrc, IRQn_Type irqType)
|
||||
{
|
||||
stc_intc_sel_field_t *stcIntSel = (stc_intc_sel_field_t *)
|
||||
((uint32_t)(&M4_INTC->SEL0) + (4u * irqType));
|
||||
|
||||
// what is the source of the selected interrupt? (USART, etc...)
|
||||
stcIntSel->INTSEL = irqSrc;
|
||||
|
||||
// set priority and enable
|
||||
NVIC_SetPriority(irqType, IRQ_PRIORITY_DEFAULT);
|
||||
NVIC_ClearPendingIRQ(irqType);
|
||||
NVIC_EnableIRQ(irqType);
|
||||
}
|
||||
34
src/hc32f460/main.c
Normal file
34
src/hc32f460/main.c
Normal file
@@ -0,0 +1,34 @@
|
||||
// Code to setup clocks on Huada HC32F460
|
||||
//
|
||||
// Copyright (C) 2022 Steven Gotthardt <gotthardt@gmail.com>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_MACH_AVR
|
||||
#include "sched.h"
|
||||
#include "system_hc32f460.h"
|
||||
#include "hc32f460_gpio.h"
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Startup
|
||||
****************************************************************/
|
||||
|
||||
// Main entry point - called from armcm_boot.c:ResetHandler()
|
||||
void __attribute__((noreturn))
|
||||
armcm_main(void)
|
||||
{
|
||||
// sets the system clock speed variable for library use
|
||||
SystemInit();
|
||||
|
||||
// disable JTAG/SWD on pins PA13, PA14, PA15, PB3, PB4
|
||||
// SWD still works until the relevant pins are reconfigured. Proprietary
|
||||
// flash program (XHSC ISP) must be used to reflash afterwards.
|
||||
PORT_DebugPortSetting(ALL_DBG_PIN, Disable);
|
||||
|
||||
// manage the system
|
||||
sched_main();
|
||||
|
||||
// never get here
|
||||
for (;;) ;
|
||||
}
|
||||
222
src/hc32f460/serial.c
Normal file
222
src/hc32f460/serial.c
Normal file
@@ -0,0 +1,222 @@
|
||||
// HC32F460 serial
|
||||
//
|
||||
// Copyright (C) 2022 Steven Gotthardt <gotthardt@gmail.com>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_SERIAL_BAUD
|
||||
|
||||
#include "command.h" // DECL_CONSTANT_STR
|
||||
#include "internal.h"
|
||||
#include "sched.h" // DECL_INIT
|
||||
#include "generic/serial_irq.h"
|
||||
#include "generic/armcm_boot.h"
|
||||
|
||||
#include "hc32f460_usart.h"
|
||||
#include "hc32f460_gpio.h"
|
||||
#include "hc32f460_pwc.h"
|
||||
|
||||
|
||||
#define USART_BAUDRATE (CONFIG_SERIAL_BAUD)
|
||||
|
||||
|
||||
// Aquila 1.0.3 pins for TX, RX to CH304 on PA15 and PA09
|
||||
// for the LCD connector: TX, RX on PC00 and PC01
|
||||
#if CONFIG_HC32F460_SERIAL_PA15_PA9
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PA15,PA9");
|
||||
#define USART_RX_PORT (PortA)
|
||||
#define USART_RX_PIN (Pin15)
|
||||
#define USART_TX_PORT (PortA)
|
||||
#define USART_TX_PIN (Pin09)
|
||||
#define USART_NUM 1
|
||||
|
||||
#elif CONFIG_HC32F460_SERIAL_PC0_PC1
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PC0,PC1");
|
||||
#define USART_RX_PORT (PortC)
|
||||
#define USART_RX_PIN (Pin00)
|
||||
#define USART_TX_PORT (PortC)
|
||||
#define USART_TX_PIN (Pin01)
|
||||
#define USART_NUM 1
|
||||
|
||||
#elif CONFIG_HC32F460_SERIAL_PA3_PA2
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PA3,PA2");
|
||||
#define USART_RX_PORT (PortA)
|
||||
#define USART_RX_PIN (Pin03)
|
||||
#define USART_TX_PORT (PortA)
|
||||
#define USART_TX_PIN (Pin02)
|
||||
#define USART_NUM 1
|
||||
|
||||
#elif CONFIG_HC32F460_SERIAL_PH2_PB10
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PH2,PB10");
|
||||
#define USART_RX_PORT (PortH)
|
||||
#define USART_RX_PIN (Pin02)
|
||||
#define USART_TX_PORT (PortB)
|
||||
#define USART_TX_PIN (Pin10)
|
||||
#define USART_NUM 3
|
||||
|
||||
#elif CONFIG_HC32F460_SERIAL_PA7_PA8
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PA7,PA8");
|
||||
#define USART_RX_PORT (PortA)
|
||||
#define USART_RX_PIN (Pin07)
|
||||
#define USART_TX_PORT (PortA)
|
||||
#define USART_TX_PIN (Pin08)
|
||||
#define USART_NUM 1
|
||||
|
||||
#elif CONFIG_HC32F460_SERIAL_PA13_PA14
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PA13,PA14");
|
||||
#define USART_RX_PORT (PortA)
|
||||
#define USART_RX_PIN (Pin13)
|
||||
#define USART_TX_PORT (PortA)
|
||||
#define USART_TX_PIN (Pin14)
|
||||
#define USART_NUM 1
|
||||
#endif
|
||||
|
||||
#if (USART_NUM == 1)
|
||||
// use USART 1 for serial connection
|
||||
#define USARTx M4_USART1
|
||||
|
||||
#define USART_RX_FUNC Func_Usart1_Rx
|
||||
#define USART_TX_FUNC Func_Usart1_Tx
|
||||
#define USART_RI_NUM INT_USART1_RI
|
||||
#define USART_TI_NUM INT_USART1_TI
|
||||
#define USART_EI_NUM INT_USART1_EI
|
||||
#define USART_TCI_NUM INT_USART1_TCI
|
||||
#elif (USART_NUM == 3)
|
||||
// use USART 3 for serial connection
|
||||
#define USARTx M4_USART3
|
||||
|
||||
#define USART_RX_FUNC Func_Usart3_Rx
|
||||
#define USART_TX_FUNC Func_Usart3_Tx
|
||||
#define USART_RI_NUM INT_USART3_RI
|
||||
#define USART_TI_NUM INT_USART3_TI
|
||||
#define USART_EI_NUM INT_USART3_EI
|
||||
#define USART_TCI_NUM INT_USART3_TCI
|
||||
#endif
|
||||
|
||||
#define USART_ENABLE (PWC_FCG1_PERIPH_USART1 | PWC_FCG1_PERIPH_USART2 | \
|
||||
PWC_FCG1_PERIPH_USART3 | PWC_FCG1_PERIPH_USART4)
|
||||
|
||||
|
||||
void
|
||||
serialError(void)
|
||||
{
|
||||
if (Set == USART_GetStatus(USARTx, UsartFrameErr))
|
||||
{
|
||||
USART_ClearStatus(USARTx, UsartFrameErr);
|
||||
|
||||
// use it anyway
|
||||
serial_rx_byte(USARTx->DR_f.RDR);
|
||||
}
|
||||
|
||||
if (Set == USART_GetStatus(USARTx, UsartOverrunErr))
|
||||
{
|
||||
USART_ClearStatus(USARTx, UsartOverrunErr);
|
||||
}
|
||||
}
|
||||
DECL_ARMCM_IRQ(serialError, Int001_IRQn);
|
||||
|
||||
|
||||
void
|
||||
serialTxComplete(void)
|
||||
{
|
||||
USART_FuncCmd(USARTx, UsartTx, Disable);
|
||||
USART_FuncCmd(USARTx, UsartTxCmpltInt, Disable);
|
||||
}
|
||||
DECL_ARMCM_IRQ(serialTxComplete, Int003_IRQn);
|
||||
|
||||
|
||||
void
|
||||
serialRx(void)
|
||||
{
|
||||
uint16_t data = USART_RecData(USARTx);
|
||||
|
||||
// call to klipper generic/serial_irq function
|
||||
serial_rx_byte(data);
|
||||
}
|
||||
DECL_ARMCM_IRQ(serialRx, Int000_IRQn);
|
||||
|
||||
|
||||
void
|
||||
serialTxEmpty(void)
|
||||
{
|
||||
uint8_t data2send;
|
||||
|
||||
// use helper from generic - zero means byte ready
|
||||
if (!serial_get_tx_byte(&data2send))
|
||||
{
|
||||
//USARTx->DR_f.TDR = data2send;
|
||||
USART_SendData(USARTx, data2send);
|
||||
}
|
||||
else
|
||||
{
|
||||
// no more data - stop the interrupt
|
||||
USART_FuncCmd(USARTx, UsartTxCmpltInt, Enable);
|
||||
USART_FuncCmd(USARTx, UsartTxEmptyInt, Disable);
|
||||
}
|
||||
}
|
||||
DECL_ARMCM_IRQ(serialTxEmpty, Int002_IRQn);
|
||||
|
||||
|
||||
// called by generic framework
|
||||
void
|
||||
serial_enable_tx_irq(void)
|
||||
{
|
||||
/* Enable TX && TX empty interrupt */
|
||||
USART_FuncCmd(USARTx, UsartTxAndTxEmptyInt, Enable);
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
serial_init(void)
|
||||
{
|
||||
const stc_usart_uart_init_t stcInitCfg = {
|
||||
UsartIntClkCkNoOutput,
|
||||
UsartClkDiv_1,
|
||||
UsartDataBits8,
|
||||
UsartDataLsbFirst,
|
||||
UsartOneStopBit,
|
||||
UsartParityNone,
|
||||
UsartSampleBit16,
|
||||
UsartStartBitFallEdge,
|
||||
UsartRtsEnable,
|
||||
};
|
||||
|
||||
// Function Clock Control - USART enable (sets bit to a 0)
|
||||
PWC_Fcg1PeriphClockCmd(USART_ENABLE, Enable);
|
||||
|
||||
/* Initialize port pins for USART IO - Disable = NO subfunction */
|
||||
PORT_SetFunc(USART_RX_PORT, USART_RX_PIN, USART_RX_FUNC, Disable);
|
||||
PORT_SetFunc(USART_TX_PORT, USART_TX_PIN, USART_TX_FUNC, Disable);
|
||||
|
||||
/* Initialize UART */
|
||||
USART_UART_Init(USARTx, &stcInitCfg);
|
||||
|
||||
/* Set baudrate */
|
||||
USART_SetBaudrate(USARTx, USART_BAUDRATE);
|
||||
|
||||
/* A word on interrupts in HC32F460
|
||||
In other vendors (STM) the irqs are assigned names in the vector list
|
||||
eg: USART1_IRQn but HC32F460 has numbered IRQs: IRQ000_IRQn IRQ143_IRQn
|
||||
Using INT_USART1_RI from hc32f460.h put in to IRQn->INTSEL
|
||||
if n = 5 then the USART1_RI iterrupt will be at IRQ005_IRQn
|
||||
For the specific case of each USART there are 5 separate irqs to map
|
||||
*/
|
||||
|
||||
/* Set USART RX IRQ */
|
||||
IrqRegistration(USART_RI_NUM, Int000_IRQn);
|
||||
|
||||
/* Set USART err */
|
||||
IrqRegistration(USART_EI_NUM, Int001_IRQn);
|
||||
|
||||
/* Set USART TX IRQ */
|
||||
IrqRegistration(USART_TI_NUM, Int002_IRQn);
|
||||
|
||||
/* Set USART TX complete IRQ */
|
||||
IrqRegistration(USART_TCI_NUM, Int003_IRQn);
|
||||
|
||||
/* Enable RX && RX interrupt function */
|
||||
USART_FuncCmd(USARTx, UsartRx, Enable);
|
||||
USART_FuncCmd(USARTx, UsartRxInt, Enable);
|
||||
}
|
||||
|
||||
DECL_INIT(serial_init);
|
||||
181
src/i2c_software.c
Normal file
181
src/i2c_software.c
Normal file
@@ -0,0 +1,181 @@
|
||||
// Software I2C emulation
|
||||
//
|
||||
// Copyright (C) 2023 Kevin O'Connor <kevin@koconnor.net>
|
||||
// Copyright (C) 2023 Alan.Ma <tech@biqu3d.com>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memcpy
|
||||
#include "board/gpio.h" // gpio_out_setup
|
||||
#include "board/internal.h" // gpio_peripheral
|
||||
#include "board/misc.h" // timer_read_time
|
||||
#include "basecmd.h" // oid_alloc
|
||||
#include "command.h" // DECL_COMMAND
|
||||
#include "sched.h" // sched_shutdown
|
||||
#include "i2ccmds.h" // i2cdev_set_software_bus
|
||||
|
||||
struct i2c_software {
|
||||
struct gpio_out scl_out, sda_out;
|
||||
struct gpio_in scl_in, sda_in;
|
||||
uint8_t addr;
|
||||
unsigned int ticks;
|
||||
};
|
||||
|
||||
void
|
||||
command_i2c_set_software_bus(uint32_t *args)
|
||||
{
|
||||
struct i2cdev_s *i2c = i2cdev_oid_lookup(args[0]);
|
||||
struct i2c_software *is = alloc_chunk(sizeof(*is));
|
||||
is->ticks = 1000000 / 100 / 2; // 100KHz
|
||||
is->addr = (args[4] & 0x7f) << 1; // address format shifted
|
||||
is->scl_in = gpio_in_setup(args[1], 1);
|
||||
is->scl_out = gpio_out_setup(args[1], 1);
|
||||
is->sda_in = gpio_in_setup(args[2], 1);
|
||||
is->sda_out = gpio_out_setup(args[2], 1);
|
||||
i2cdev_set_software_bus(i2c, is);
|
||||
}
|
||||
DECL_COMMAND(command_i2c_set_software_bus,
|
||||
"i2c_set_software_bus oid=%c scl_pin=%u sda_pin=%u"
|
||||
" rate=%u address=%u");
|
||||
|
||||
// The AVR micro-controllers require specialized timing
|
||||
#if CONFIG_MACH_AVR
|
||||
|
||||
#define i2c_delay(ticks) (void)(ticks)
|
||||
|
||||
#else
|
||||
|
||||
static unsigned int
|
||||
nsecs_to_ticks(uint32_t ns)
|
||||
{
|
||||
return timer_from_us(ns * 1000) / 1000000;
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_delay(unsigned int ticks) {
|
||||
unsigned int t = timer_read_time() + nsecs_to_ticks(ticks);
|
||||
while (t > timer_read_time());
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
static void
|
||||
i2c_software_send_ack(struct i2c_software *is, const uint8_t ack)
|
||||
{
|
||||
if (ack) {
|
||||
gpio_in_reset(is->sda_in, 1);
|
||||
} else {
|
||||
gpio_out_reset(is->sda_out, 0);
|
||||
}
|
||||
i2c_delay(is->ticks);
|
||||
gpio_in_reset(is->scl_in, 1);
|
||||
i2c_delay(is->ticks);
|
||||
gpio_out_reset(is->scl_out, 0);
|
||||
}
|
||||
|
||||
static uint8_t
|
||||
i2c_software_read_ack(struct i2c_software *is)
|
||||
{
|
||||
uint8_t nack = 0;
|
||||
gpio_in_reset(is->sda_in, 1);
|
||||
i2c_delay(is->ticks);
|
||||
gpio_in_reset(is->scl_in, 1);
|
||||
nack = gpio_in_read(is->sda_in);
|
||||
i2c_delay(is->ticks);
|
||||
gpio_out_reset(is->scl_out, 0);
|
||||
gpio_in_reset(is->sda_in, 1);
|
||||
return nack;
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_software_send_byte(struct i2c_software *is, uint8_t b)
|
||||
{
|
||||
for (uint_fast8_t i = 0; i < 8; i++) {
|
||||
if (b & 0x80) {
|
||||
gpio_in_reset(is->sda_in, 1);
|
||||
} else {
|
||||
gpio_out_reset(is->sda_out, 0);
|
||||
}
|
||||
b <<= 1;
|
||||
i2c_delay(is->ticks);
|
||||
gpio_in_reset(is->scl_in, 1);
|
||||
i2c_delay(is->ticks);
|
||||
gpio_out_reset(is->scl_out, 0);
|
||||
}
|
||||
|
||||
if (i2c_software_read_ack(is)) {
|
||||
shutdown("soft_i2c NACK");
|
||||
}
|
||||
}
|
||||
|
||||
static uint8_t
|
||||
i2c_software_read_byte(struct i2c_software *is, uint8_t remaining)
|
||||
{
|
||||
uint8_t b = 0;
|
||||
gpio_in_reset(is->sda_in, 1);
|
||||
for (uint_fast8_t i = 0; i < 8; i++) {
|
||||
i2c_delay(is->ticks);
|
||||
gpio_in_reset(is->scl_in, 1);
|
||||
i2c_delay(is->ticks);
|
||||
b <<= 1;
|
||||
b |= gpio_in_read(is->sda_in);
|
||||
gpio_out_reset(is->scl_out, 0);
|
||||
}
|
||||
gpio_in_reset(is->sda_in, 1);
|
||||
i2c_software_send_ack(is, remaining == 0);
|
||||
return b;
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_software_start(struct i2c_software *is, uint8_t addr)
|
||||
{
|
||||
i2c_delay(is->ticks);
|
||||
gpio_in_reset(is->sda_in, 1);
|
||||
gpio_in_reset(is->scl_in, 1);
|
||||
i2c_delay(is->ticks);
|
||||
gpio_out_reset(is->sda_out, 0);
|
||||
i2c_delay(is->ticks);
|
||||
gpio_out_reset(is->scl_out, 0);
|
||||
|
||||
i2c_software_send_byte(is, addr);
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_software_stop(struct i2c_software *is)
|
||||
{
|
||||
gpio_out_reset(is->sda_out, 0);
|
||||
i2c_delay(is->ticks);
|
||||
gpio_in_reset(is->scl_in, 1);
|
||||
i2c_delay(is->ticks);
|
||||
gpio_in_reset(is->sda_in, 1);
|
||||
}
|
||||
|
||||
void
|
||||
i2c_software_write(struct i2c_software *is, uint8_t write_len, uint8_t *write)
|
||||
{
|
||||
i2c_software_start(is, is->addr);
|
||||
while (write_len--)
|
||||
i2c_software_send_byte(is, *write++);
|
||||
i2c_software_stop(is);
|
||||
}
|
||||
|
||||
void
|
||||
i2c_software_read(struct i2c_software *is, uint8_t reg_len, uint8_t *reg
|
||||
, uint8_t read_len, uint8_t *read)
|
||||
{
|
||||
uint8_t addr = is->addr | 0x01;
|
||||
|
||||
if (reg_len) {
|
||||
// write the register
|
||||
i2c_software_start(is, is->addr);
|
||||
while(reg_len--)
|
||||
i2c_software_send_byte(is, *reg++);
|
||||
}
|
||||
// start/re-start and read data
|
||||
i2c_software_start(is, addr);
|
||||
while(read_len--) {
|
||||
*read = i2c_software_read_byte(is, read_len);
|
||||
read++;
|
||||
}
|
||||
i2c_software_stop(is);
|
||||
}
|
||||
13
src/i2c_software.h
Normal file
13
src/i2c_software.h
Normal file
@@ -0,0 +1,13 @@
|
||||
#ifndef __I2C_SOFTWARE_H
|
||||
#define __I2C_SOFTWARE_H
|
||||
|
||||
#include <stdint.h> // uint8_t
|
||||
|
||||
struct i2c_software *i2c_software_oid_lookup(uint8_t oid);
|
||||
void i2c_software_write(struct i2c_software *sw_i2c
|
||||
, uint8_t write_len, uint8_t *write);
|
||||
void i2c_software_read(struct i2c_software *sw_i2c
|
||||
, uint8_t reg_len, uint8_t *reg
|
||||
, uint8_t read_len, uint8_t *read);
|
||||
|
||||
#endif // i2c_software.h
|
||||
@@ -5,22 +5,25 @@
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memcpy
|
||||
#include "autoconf.h" // CONFIG_WANT_SOFTWARE_I2C
|
||||
#include "basecmd.h" //oid_alloc
|
||||
#include "command.h" //sendf
|
||||
#include "sched.h" //DECL_COMMAND
|
||||
#include "board/gpio.h" //i2c_write/read/setup
|
||||
#include "i2c_software.h" // i2c_software_setup
|
||||
#include "i2ccmds.h"
|
||||
|
||||
enum {
|
||||
IF_SOFTWARE = 1, IF_HARDWARE = 2
|
||||
};
|
||||
|
||||
void
|
||||
command_config_i2c(uint32_t *args)
|
||||
{
|
||||
uint8_t addr = args[3] & 0x7f;
|
||||
struct i2cdev_s *i2c = oid_alloc(args[0], command_config_i2c
|
||||
, sizeof(*i2c));
|
||||
i2c->i2c_config = i2c_setup(args[1], args[2], addr);
|
||||
}
|
||||
DECL_COMMAND(command_config_i2c,
|
||||
"config_i2c oid=%c i2c_bus=%u rate=%u address=%u");
|
||||
DECL_COMMAND(command_config_i2c, "config_i2c oid=%c");
|
||||
|
||||
struct i2cdev_s *
|
||||
i2cdev_oid_lookup(uint8_t oid)
|
||||
@@ -28,6 +31,24 @@ i2cdev_oid_lookup(uint8_t oid)
|
||||
return oid_lookup(oid, command_config_i2c);
|
||||
}
|
||||
|
||||
void
|
||||
command_i2c_set_bus(uint32_t *args)
|
||||
{
|
||||
uint8_t addr = args[3] & 0x7f;
|
||||
struct i2cdev_s *i2c = i2cdev_oid_lookup(args[0]);
|
||||
i2c->i2c_config = i2c_setup(args[1], args[2], addr);
|
||||
i2c->flags |= IF_HARDWARE;
|
||||
}
|
||||
DECL_COMMAND(command_i2c_set_bus,
|
||||
"i2c_set_bus oid=%c i2c_bus=%u rate=%u address=%u");
|
||||
|
||||
void
|
||||
i2cdev_set_software_bus(struct i2cdev_s *i2c, struct i2c_software *is)
|
||||
{
|
||||
i2c->i2c_software = is;
|
||||
i2c->flags |= IF_SOFTWARE;
|
||||
}
|
||||
|
||||
void
|
||||
command_i2c_write(uint32_t *args)
|
||||
{
|
||||
@@ -35,7 +56,11 @@ command_i2c_write(uint32_t *args)
|
||||
struct i2cdev_s *i2c = oid_lookup(oid, command_config_i2c);
|
||||
uint8_t data_len = args[1];
|
||||
uint8_t *data = command_decode_ptr(args[2]);
|
||||
i2c_write(i2c->i2c_config, data_len, data);
|
||||
uint_fast8_t flags = i2c->flags;
|
||||
if (CONFIG_WANT_SOFTWARE_I2C && flags & IF_SOFTWARE)
|
||||
i2c_software_write(i2c->i2c_software, data_len, data);
|
||||
else
|
||||
i2c_write(i2c->i2c_config, data_len, data);
|
||||
}
|
||||
DECL_COMMAND(command_i2c_write, "i2c_write oid=%c data=%*s");
|
||||
|
||||
@@ -48,7 +73,11 @@ command_i2c_read(uint32_t * args)
|
||||
uint8_t *reg = command_decode_ptr(args[2]);
|
||||
uint8_t data_len = args[3];
|
||||
uint8_t data[data_len];
|
||||
i2c_read(i2c->i2c_config, reg_len, reg, data_len, data);
|
||||
uint_fast8_t flags = i2c->flags;
|
||||
if (CONFIG_WANT_SOFTWARE_I2C && flags & IF_SOFTWARE)
|
||||
i2c_software_read(i2c->i2c_software, reg_len, reg, data_len, data);
|
||||
else
|
||||
i2c_read(i2c->i2c_config, reg_len, reg, data_len, data);
|
||||
sendf("i2c_read_response oid=%c response=%*s", oid, data_len, data);
|
||||
}
|
||||
DECL_COMMAND(command_i2c_read, "i2c_read oid=%c reg=%*s read_len=%u");
|
||||
@@ -66,13 +95,22 @@ command_i2c_modify_bits(uint32_t *args)
|
||||
uint8_t data_len = clear_set_len/2;
|
||||
uint8_t *clear_set = command_decode_ptr(args[4]);
|
||||
uint8_t receive_data[reg_len + data_len];
|
||||
uint_fast8_t flags = i2c->flags;
|
||||
memcpy(receive_data, reg, reg_len);
|
||||
i2c_read(i2c->i2c_config, reg_len, reg, data_len, receive_data + reg_len);
|
||||
if (CONFIG_WANT_SOFTWARE_I2C && flags & IF_SOFTWARE)
|
||||
i2c_software_read(
|
||||
i2c->i2c_software, reg_len, reg, data_len, receive_data + reg_len);
|
||||
else
|
||||
i2c_read(
|
||||
i2c->i2c_config, reg_len, reg, data_len, receive_data + reg_len);
|
||||
for (int i = 0; i < data_len; i++) {
|
||||
receive_data[reg_len + i] &= ~clear_set[i];
|
||||
receive_data[reg_len + i] |= clear_set[data_len + i];
|
||||
}
|
||||
i2c_write(i2c->i2c_config, reg_len + data_len, receive_data);
|
||||
if (CONFIG_WANT_SOFTWARE_I2C && flags & IF_SOFTWARE)
|
||||
i2c_software_write(i2c->i2c_software, reg_len + data_len, receive_data);
|
||||
else
|
||||
i2c_write(i2c->i2c_config, reg_len + data_len, receive_data);
|
||||
}
|
||||
DECL_COMMAND(command_i2c_modify_bits,
|
||||
"i2c_modify_bits oid=%c reg=%*s clear_set_bits=%*s");
|
||||
|
||||
@@ -6,8 +6,11 @@
|
||||
|
||||
struct i2cdev_s {
|
||||
struct i2c_config i2c_config;
|
||||
struct i2c_software *i2c_software;
|
||||
uint8_t flags;
|
||||
};
|
||||
|
||||
struct i2cdev_s *i2cdev_oid_lookup(uint8_t oid);
|
||||
void i2cdev_set_software_bus(struct i2cdev_s *i2c, struct i2c_software *is);
|
||||
|
||||
#endif
|
||||
|
||||
@@ -16,6 +16,8 @@ DECL_CTR("DECL_INITIAL_PINS " __stringify(CONFIG_INITIAL_PINS));
|
||||
void
|
||||
initial_pins_setup(void)
|
||||
{
|
||||
if (sizeof(CONFIG_INITIAL_PINS) <= 1)
|
||||
return;
|
||||
int i;
|
||||
for (i=0; i<initial_pins_size; i++) {
|
||||
const struct initial_pin_s *ip = &initial_pins[i];
|
||||
|
||||
@@ -6,12 +6,11 @@ if MACH_LINUX
|
||||
config LINUX_SELECT
|
||||
bool
|
||||
default y
|
||||
select HAVE_GPIO
|
||||
select HAVE_GPIO_ADC
|
||||
select HAVE_GPIO_SPI
|
||||
select HAVE_GPIO_HARD_PWM
|
||||
select HAVE_GPIO_I2C
|
||||
select HAVE_GPIO_BITBANGING
|
||||
select HAVE_GPIO
|
||||
select HAVE_GPIO_HARD_PWM
|
||||
|
||||
config BOARD_DIRECTORY
|
||||
string
|
||||
|
||||
@@ -11,4 +11,4 @@ CFLAGS_klipper.elf += -lutil -lrt -lpthread
|
||||
|
||||
flash: $(OUT)klipper.elf
|
||||
@echo " Flashing"
|
||||
$(Q)sudo ./scripts/flash-linux.sh
|
||||
$(Q)sudo ./scripts/flash-linux.sh $(OUT)
|
||||
|
||||
@@ -27,6 +27,7 @@ DECL_ENUMERATION_RANGE("pin", "gpiochip4/gpio0", GPIO(4, 0), MAX_GPIO_LINES);
|
||||
DECL_ENUMERATION_RANGE("pin", "gpiochip5/gpio0", GPIO(5, 0), MAX_GPIO_LINES);
|
||||
DECL_ENUMERATION_RANGE("pin", "gpiochip6/gpio0", GPIO(6, 0), MAX_GPIO_LINES);
|
||||
DECL_ENUMERATION_RANGE("pin", "gpiochip7/gpio0", GPIO(7, 0), MAX_GPIO_LINES);
|
||||
DECL_ENUMERATION_RANGE("pin", "gpiochip8/gpio0", GPIO(8, 0), MAX_GPIO_LINES);
|
||||
|
||||
struct gpio_line {
|
||||
int chipid;
|
||||
@@ -34,8 +35,8 @@ struct gpio_line {
|
||||
int fd;
|
||||
int state;
|
||||
};
|
||||
static struct gpio_line gpio_lines[8 * MAX_GPIO_LINES];
|
||||
static int gpio_chip_fd[8] = { -1, -1, -1, -1, -1, -1, -1, -1 };
|
||||
static struct gpio_line gpio_lines[9 * MAX_GPIO_LINES];
|
||||
static int gpio_chip_fd[9] = { -1, -1, -1, -1, -1, -1, -1, -1, -1 };
|
||||
|
||||
static int
|
||||
get_chip_fd(uint8_t chipId)
|
||||
@@ -147,11 +148,11 @@ gpio_in_reset(struct gpio_in g, int8_t pull_up)
|
||||
memset(&req, 0, sizeof(req));
|
||||
req.lines = 1;
|
||||
req.flags = GPIOHANDLE_REQUEST_INPUT;
|
||||
#if defined(GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_UP)
|
||||
#if defined(GPIOHANDLE_REQUEST_BIAS_PULL_UP)
|
||||
if (pull_up > 0) {
|
||||
req.flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_UP;
|
||||
req.flags |= GPIOHANDLE_REQUEST_BIAS_PULL_UP;
|
||||
} else if (pull_up < 0) {
|
||||
req.flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_DOWN;
|
||||
req.flags |= GPIOHANDLE_REQUEST_BIAS_PULL_DOWN;
|
||||
}
|
||||
#endif
|
||||
req.lineoffsets[0] = g.line->offset;
|
||||
|
||||
@@ -45,6 +45,7 @@ void gpio_pwm_write(struct gpio_pwm g, uint16_t val);
|
||||
|
||||
struct i2c_config {
|
||||
int fd;
|
||||
uint8_t addr;
|
||||
};
|
||||
|
||||
struct i2c_config i2c_setup(uint32_t bus, uint32_t rate, uint8_t addr);
|
||||
|
||||
@@ -4,7 +4,8 @@
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
#include <fcntl.h> // open
|
||||
#include <linux/i2c-dev.h> // I2C_SLAVE
|
||||
#include <linux/i2c-dev.h> // I2C_SLAVE i2c_msg
|
||||
#include <linux/i2c.h> // i2c_rdwr_ioctl_data I2C_M_RD I2C_FUNC_I2C
|
||||
#include <stdio.h> // snprintf
|
||||
#include <sys/ioctl.h> // ioctl
|
||||
#include <unistd.h> // write
|
||||
@@ -42,6 +43,13 @@ i2c_open(uint32_t bus, uint8_t addr)
|
||||
report_errno("open i2c", fd);
|
||||
goto fail;
|
||||
}
|
||||
// Test for I2C_RDWR support
|
||||
unsigned long i2c_funcs; // datatype from ioctl spec.
|
||||
ioctl(fd, I2C_FUNCS, &i2c_funcs);
|
||||
if ((i2c_funcs & I2C_FUNC_I2C) == 0) {
|
||||
report_errno("i2c does not support I2C_RDWR", fd);
|
||||
goto fail;
|
||||
}
|
||||
int ret = ioctl(fd, I2C_SLAVE, addr);
|
||||
if (ret < 0) {
|
||||
report_errno("ioctl i2c", fd);
|
||||
@@ -73,7 +81,7 @@ i2c_setup(uint32_t bus, uint32_t rate, uint8_t addr)
|
||||
// dtparam=i2c_baudrate=<rate>
|
||||
|
||||
int fd = i2c_open(bus, addr);
|
||||
return (struct i2c_config){.fd=fd};
|
||||
return (struct i2c_config){.fd=fd, .addr=addr};
|
||||
}
|
||||
|
||||
void
|
||||
@@ -91,12 +99,29 @@ void
|
||||
i2c_read(struct i2c_config config, uint8_t reg_len, uint8_t *reg
|
||||
, uint8_t read_len, uint8_t *data)
|
||||
{
|
||||
if(reg_len != 0)
|
||||
i2c_write(config, reg_len, reg);
|
||||
int ret = read(config.fd, data, read_len);
|
||||
if (ret != read_len) {
|
||||
if (ret < 0)
|
||||
report_errno("read value i2c", ret);
|
||||
struct i2c_rdwr_ioctl_data i2c_data;
|
||||
struct i2c_msg msgs[2];
|
||||
|
||||
if(reg_len != 0) {
|
||||
msgs[0].addr = config.addr;
|
||||
msgs[0].flags = 0x0;
|
||||
msgs[0].len = reg_len;
|
||||
msgs[0].buf = reg;
|
||||
i2c_data.nmsgs = 2;
|
||||
i2c_data.msgs = &msgs[0];
|
||||
} else {
|
||||
i2c_data.nmsgs = 1;
|
||||
i2c_data.msgs = &msgs[1];
|
||||
}
|
||||
|
||||
msgs[1].addr = config.addr;
|
||||
msgs[1].flags = I2C_M_RD;
|
||||
msgs[1].len = read_len;
|
||||
msgs[1].buf = data;
|
||||
|
||||
int ret = ioctl(config.fd, I2C_RDWR, &i2c_data);
|
||||
|
||||
if(ret < 0) {
|
||||
try_shutdown("Unable to read i2c device");
|
||||
}
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
#include <stdint.h> // uint32_t
|
||||
#include "autoconf.h" // CONFIG_CLOCK_FREQ
|
||||
|
||||
#define MAX_GPIO_LINES 256
|
||||
#define MAX_GPIO_LINES 288
|
||||
#define GPIO(PORT, NUM) ((PORT) * MAX_GPIO_LINES + (NUM))
|
||||
#define GPIO2PORT(PIN) ((PIN) / MAX_GPIO_LINES)
|
||||
#define GPIO2PIN(PIN) ((PIN) % MAX_GPIO_LINES)
|
||||
|
||||
@@ -4,10 +4,11 @@
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include </usr/include/sched.h> // sched_setscheduler
|
||||
#include </usr/include/sched.h> // sched_setscheduler sched_get_priority_max
|
||||
#include <stdio.h> // fprintf
|
||||
#include <string.h> // memset
|
||||
#include <unistd.h> // getopt
|
||||
#include <sys/mman.h> // mlockall MCL_CURRENT MCL_FUTURE
|
||||
#include "board/misc.h" // console_sendf
|
||||
#include "command.h" // DECL_CONSTANT
|
||||
#include "internal.h" // console_setup
|
||||
@@ -25,12 +26,18 @@ realtime_setup(void)
|
||||
{
|
||||
struct sched_param sp;
|
||||
memset(&sp, 0, sizeof(sp));
|
||||
sp.sched_priority = 1;
|
||||
sp.sched_priority = sched_get_priority_max(SCHED_FIFO) / 2;
|
||||
int ret = sched_setscheduler(0, SCHED_FIFO, &sp);
|
||||
if (ret < 0) {
|
||||
report_errno("sched_setscheduler", ret);
|
||||
return -1;
|
||||
}
|
||||
// Lock ourselves into memory
|
||||
ret = mlockall(MCL_CURRENT | MCL_FUTURE);
|
||||
if (ret) {
|
||||
report_errno("mlockall", ret);
|
||||
return -1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -62,7 +69,8 @@ main(int argc, char **argv)
|
||||
// Parse program args
|
||||
orig_argv = argv;
|
||||
int opt, watchdog = 0, realtime = 0;
|
||||
while ((opt = getopt(argc, argv, "wr")) != -1) {
|
||||
char *serial = "/tmp/klipper_host_mcu";
|
||||
while ((opt = getopt(argc, argv, "wrI:")) != -1) {
|
||||
switch (opt) {
|
||||
case 'w':
|
||||
watchdog = 1;
|
||||
@@ -70,8 +78,11 @@ main(int argc, char **argv)
|
||||
case 'r':
|
||||
realtime = 1;
|
||||
break;
|
||||
case 'I':
|
||||
serial = optarg;
|
||||
break;
|
||||
default:
|
||||
fprintf(stderr, "Usage: %s [-w] [-r]\n", argv[0]);
|
||||
fprintf(stderr, "Usage: %s [-w] [-r] [-I path]\n", argv[0]);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
@@ -82,7 +93,7 @@ main(int argc, char **argv)
|
||||
if (ret)
|
||||
return ret;
|
||||
}
|
||||
int ret = console_setup("/tmp/klipper_host_mcu");
|
||||
int ret = console_setup(serial);
|
||||
if (ret)
|
||||
return -1;
|
||||
if (watchdog) {
|
||||
|
||||
@@ -9,11 +9,11 @@ config LPC_SELECT
|
||||
select HAVE_GPIO_ADC
|
||||
select HAVE_GPIO_I2C
|
||||
select HAVE_GPIO_SPI
|
||||
select HAVE_GPIO_BITBANGING
|
||||
select HAVE_GPIO_HARD_PWM
|
||||
select HAVE_STRICT_TIMING
|
||||
select HAVE_CHIPID
|
||||
select HAVE_GPIO_HARD_PWM
|
||||
select HAVE_STEPPER_BOTH_EDGE
|
||||
select HAVE_BOOTLOADER_REQUEST
|
||||
|
||||
config BOARD_DIRECTORY
|
||||
string
|
||||
@@ -41,6 +41,10 @@ config FLASH_SIZE
|
||||
hex
|
||||
default 0x80000
|
||||
|
||||
config FLASH_BOOT_ADDRESS
|
||||
hex
|
||||
default 0x0
|
||||
|
||||
config RAM_START
|
||||
hex
|
||||
default 0x10000000
|
||||
@@ -53,15 +57,28 @@ config STACK_SIZE
|
||||
int
|
||||
default 512
|
||||
|
||||
config SMOOTHIEWARE_BOOTLOADER
|
||||
bool "Target board uses Smoothieware bootloader"
|
||||
default y
|
||||
|
||||
config FLASH_START
|
||||
######################################################################
|
||||
# Bootloader
|
||||
######################################################################
|
||||
|
||||
choice
|
||||
prompt "Bootloader offset"
|
||||
config LPC_FLASH_START_4000
|
||||
bool "16KiB bootloader (Smoothieware bootloader)"
|
||||
config LPC_FLASH_START_0000
|
||||
bool "No bootloader"
|
||||
endchoice
|
||||
config FLASH_APPLICATION_ADDRESS
|
||||
hex
|
||||
default 0x4000 if SMOOTHIEWARE_BOOTLOADER
|
||||
default 0x4000 if LPC_FLASH_START_4000
|
||||
default 0x0000
|
||||
|
||||
|
||||
######################################################################
|
||||
# Communication inteface
|
||||
######################################################################
|
||||
|
||||
choice
|
||||
prompt "Communication interface"
|
||||
config LPC_USB
|
||||
|
||||
@@ -23,5 +23,6 @@ int is_enabled_pclock(uint32_t pclk);
|
||||
void enable_pclock(uint32_t pclk);
|
||||
uint32_t get_pclock_frequency(uint32_t pclk);
|
||||
void gpio_peripheral(uint32_t gpio, int func, int pullup);
|
||||
void usb_disconnect(void);
|
||||
|
||||
#endif // internal.h
|
||||
|
||||
@@ -6,6 +6,9 @@
|
||||
|
||||
#include "autoconf.h" // CONFIG_CLOCK_FREQ
|
||||
#include "board/armcm_boot.h" // armcm_main
|
||||
#include "board/armcm_reset.h" // try_request_canboot
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "board/misc.h" // bootloader_request
|
||||
#include "internal.h" // enable_pclock
|
||||
#include "sched.h" // sched_main
|
||||
|
||||
@@ -37,6 +40,23 @@ DECL_INIT(watchdog_init);
|
||||
* misc functions
|
||||
****************************************************************/
|
||||
|
||||
// Try to reboot into bootloader
|
||||
void
|
||||
bootloader_request(void)
|
||||
{
|
||||
if (!CONFIG_FLASH_APPLICATION_ADDRESS)
|
||||
return;
|
||||
try_request_canboot();
|
||||
// Disable USB and pause for 5ms so host recognizes a disconnect
|
||||
irq_disable();
|
||||
if (CONFIG_USB)
|
||||
usb_disconnect();
|
||||
// The "LPC17xx-DFU-Bootloader" will enter the bootloader if the
|
||||
// watchdog timeout flag is set.
|
||||
LPC_WDT->WDMOD = 0x07;
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
// Check if a peripheral clock has been enabled
|
||||
int
|
||||
is_enabled_pclock(uint32_t pclk)
|
||||
|
||||
@@ -5,11 +5,8 @@
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memcpy
|
||||
#include "autoconf.h" // CONFIG_SMOOTHIEWARE_BOOTLOADER
|
||||
#include "board/armcm_boot.h" // armcm_enable_irq
|
||||
#include "board/armcm_timer.h" // udelay
|
||||
#include "board/armcm_reset.h" // try_request_canboot
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "board/misc.h" // timer_read_time
|
||||
#include "byteorder.h" // cpu_to_le32
|
||||
#include "command.h" // DECL_CONSTANT_STR
|
||||
@@ -246,20 +243,12 @@ usb_set_configure(void)
|
||||
usb_irq_enable();
|
||||
}
|
||||
|
||||
// Force a USB disconnect (used during reboot into bootloader)
|
||||
void
|
||||
usb_request_bootloader(void)
|
||||
usb_disconnect(void)
|
||||
{
|
||||
if (!CONFIG_SMOOTHIEWARE_BOOTLOADER)
|
||||
return;
|
||||
try_request_canboot();
|
||||
// Disable USB and pause for 5ms so host recognizes a disconnect
|
||||
irq_disable();
|
||||
sie_cmd_write(SIE_CMD_SET_DEVICE_STATUS, 0);
|
||||
udelay(5000);
|
||||
// The "LPC17xx-DFU-Bootloader" will enter the bootloader if the
|
||||
// watchdog timeout flag is set.
|
||||
LPC_WDT->WDMOD = 0x07;
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -8,6 +8,7 @@ config PRU_SELECT
|
||||
select HAVE_GPIO
|
||||
#select HAVE_GPIO_ADC
|
||||
select HAVE_STRICT_TIMING
|
||||
select HAVE_LIMITED_CODE_SIZE
|
||||
|
||||
config BOARD_DIRECTORY
|
||||
string
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
# Kconfig settings for STM32 processors
|
||||
# Kconfig settings for RP2040 processors
|
||||
|
||||
if MACH_RP2040
|
||||
|
||||
@@ -9,11 +9,11 @@ config RP2040_SELECT
|
||||
select HAVE_GPIO_ADC
|
||||
select HAVE_GPIO_SPI
|
||||
select HAVE_GPIO_I2C
|
||||
select HAVE_GPIO_BITBANGING
|
||||
select HAVE_STRICT_TIMING
|
||||
select HAVE_CHIPID
|
||||
select HAVE_GPIO_HARD_PWM
|
||||
select HAVE_STEPPER_BOTH_EDGE
|
||||
select HAVE_BOOTLOADER_REQUEST
|
||||
|
||||
config BOARD_DIRECTORY
|
||||
string
|
||||
@@ -31,6 +31,10 @@ config FLASH_SIZE
|
||||
hex
|
||||
default 0x200000
|
||||
|
||||
config FLASH_BOOT_ADDRESS
|
||||
hex
|
||||
default 0x10000100 # Stage2 binary starts at 0x10000000
|
||||
|
||||
config RAM_START
|
||||
hex
|
||||
default 0x20000000
|
||||
@@ -43,17 +47,32 @@ config STACK_SIZE
|
||||
int
|
||||
default 512
|
||||
|
||||
config FLASH_START
|
||||
hex
|
||||
default 0x10000000
|
||||
|
||||
|
||||
######################################################################
|
||||
# Bootloader options
|
||||
######################################################################
|
||||
|
||||
config RP2040_HAVE_STAGE2
|
||||
bool
|
||||
config RP2040_HAVE_BOOTLOADER
|
||||
bool
|
||||
default y if !RP2040_HAVE_STAGE2
|
||||
|
||||
choice
|
||||
prompt "Flash chip" if LOW_LEVEL_OPTIONS
|
||||
prompt "Bootloader offset"
|
||||
config RP2040_FLASH_START_0100
|
||||
bool "No bootloader"
|
||||
select RP2040_HAVE_STAGE2
|
||||
config RP2040_FLASH_START_4000
|
||||
bool "16KiB bootloader"
|
||||
endchoice
|
||||
config FLASH_APPLICATION_ADDRESS
|
||||
hex
|
||||
default 0x10004000 if RP2040_FLASH_START_4000
|
||||
default 0x10000100
|
||||
|
||||
choice
|
||||
prompt "Flash chip" if LOW_LEVEL_OPTIONS && RP2040_HAVE_STAGE2
|
||||
config RP2040_FLASH_W25Q080
|
||||
bool "W25Q080 with CLKDIV 2"
|
||||
config RP2040_FLASH_GENERIC_03
|
||||
|
||||
@@ -8,14 +8,11 @@ dirs-y += src/rp2040 src/generic lib/rp2040/elf2uf2 lib/fast-hash lib/can2040
|
||||
CFLAGS += -mcpu=cortex-m0plus -mthumb -Ilib/cmsis-core
|
||||
CFLAGS += -Ilib/rp2040 -Ilib/rp2040/cmsis_include -Ilib/fast-hash -Ilib/can2040
|
||||
|
||||
CFLAGS_klipper.elf += --specs=nano.specs --specs=nosys.specs
|
||||
CFLAGS_klipper.elf += -T $(OUT)src/rp2040/rp2040_link.ld
|
||||
$(OUT)klipper.elf: $(OUT)stage2.o $(OUT)src/rp2040/rp2040_link.ld
|
||||
|
||||
# Add source files
|
||||
src-y += rp2040/main.c rp2040/gpio.c rp2040/adc.c generic/crc16_ccitt.c
|
||||
src-y += rp2040/main.c rp2040/watchdog.c rp2040/gpio.c
|
||||
src-y += rp2040/adc.c rp2040/timer.c rp2040/bootrom.c
|
||||
src-y += generic/armcm_boot.c generic/armcm_irq.c generic/armcm_reset.c
|
||||
src-y += generic/timer_irq.c rp2040/timer.c rp2040/bootrom.c
|
||||
src-y += generic/timer_irq.c generic/crc16_ccitt.c
|
||||
src-$(CONFIG_USBSERIAL) += rp2040/usbserial.c generic/usb_cdc.c
|
||||
src-$(CONFIG_USBSERIAL) += rp2040/chipid.c
|
||||
src-$(CONFIG_SERIAL) += rp2040/serial.c generic/serial_irq.c
|
||||
@@ -38,11 +35,8 @@ $(OUT)stage2.o: lib/rp2040/boot_stage2/$(STAGE2_FILE) $(OUT)autoconf.h
|
||||
$(Q)$(OBJCOPY) -O binary $(OUT)stage2raw.o $(OUT)stage2raw.bin
|
||||
$(Q)lib/rp2040/boot_stage2/pad_checksum -s 0xffffffff $(OUT)stage2raw.bin $(OUT)stage2.S
|
||||
$(Q)$(CC) $(CFLAGS) -c $(OUT)stage2.S -o $(OUT)stage2.o
|
||||
OBJS_klipper.elf += $(OUT)stage2.o
|
||||
|
||||
# Binary output file rules
|
||||
target-y += $(OUT)klipper.uf2
|
||||
|
||||
# Binary output file rules when using stage2
|
||||
$(OUT)lib/rp2040/elf2uf2/elf2uf2: lib/rp2040/elf2uf2/main.cpp
|
||||
@echo " Building $@"
|
||||
$(Q)g++ -g -O -Ilib/rp2040 $< -o $@
|
||||
@@ -51,11 +45,29 @@ $(OUT)klipper.uf2: $(OUT)klipper.elf $(OUT)lib/rp2040/elf2uf2/elf2uf2
|
||||
@echo " Creating uf2 file $@"
|
||||
$(Q)$(OUT)lib/rp2040/elf2uf2/elf2uf2 $< $@
|
||||
|
||||
rptarget-$(CONFIG_RP2040_HAVE_STAGE2) := $(OUT)klipper.uf2
|
||||
rplink-$(CONFIG_RP2040_HAVE_STAGE2) := $(OUT)src/rp2040/rp2040_link.ld
|
||||
stage2-$(CONFIG_RP2040_HAVE_STAGE2) := $(OUT)stage2.o
|
||||
|
||||
# rp2040 building when using a bootloader
|
||||
$(OUT)klipper.bin: $(OUT)klipper.elf
|
||||
@echo " Creating bin file $@"
|
||||
$(Q)$(OBJCOPY) -O binary $< $@
|
||||
|
||||
rptarget-$(CONFIG_RP2040_HAVE_BOOTLOADER) := $(OUT)klipper.bin
|
||||
rplink-$(CONFIG_RP2040_HAVE_BOOTLOADER) := $(OUT)src/generic/armcm_link.ld
|
||||
|
||||
# Set klipper.elf linker rules
|
||||
target-y += $(rptarget-y)
|
||||
CFLAGS_klipper.elf += --specs=nano.specs --specs=nosys.specs -T $(rplink-y)
|
||||
OBJS_klipper.elf += $(stage2-y)
|
||||
$(OUT)klipper.elf: $(stage2-y) $(rplink-y)
|
||||
|
||||
# Flash rules
|
||||
lib/rp2040_flash/rp2040_flash:
|
||||
@echo " Building rp2040_flash"
|
||||
$(Q)make -C lib/rp2040_flash rp2040_flash
|
||||
|
||||
# Flash rules
|
||||
flash: $(OUT)klipper.uf2 lib/rp2040_flash/rp2040_flash
|
||||
flash: $(rptarget-y) lib/rp2040_flash/rp2040_flash
|
||||
@echo " Flashing $< to $(FLASH_DEVICE)"
|
||||
$(Q)$(PYTHON) ./scripts/flash_usb.py -t $(CONFIG_MCU) -d "$(FLASH_DEVICE)" $(if $(NOSUDO),--no-sudo) $(OUT)klipper.uf2
|
||||
$(Q)$(PYTHON) ./scripts/flash_usb.py -t $(CONFIG_MCU) -d "$(FLASH_DEVICE)" $(if $(NOSUDO),--no-sudo) $(rptarget-y)
|
||||
|
||||
@@ -15,13 +15,23 @@
|
||||
// to (especially for the flash functions) call while the XIP layer
|
||||
// is unavailable.
|
||||
|
||||
static __always_inline void *rom_hword_as_ptr(uint16_t rom_address) {
|
||||
#if defined(__GNUC__) && (__GNUC__ >= 12)
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Warray-bounds"
|
||||
return (void *)(uintptr_t)*(uint16_t *)(uintptr_t)rom_address;
|
||||
#pragma GCC diagnostic pop
|
||||
#else
|
||||
return (void *)(uintptr_t)*(uint16_t *)(uintptr_t)rom_address;
|
||||
#endif
|
||||
}
|
||||
|
||||
static void * _ramfunc
|
||||
rom_func_lookup(uint32_t code)
|
||||
{
|
||||
// Table and lookup function are provided by the BOOTROM
|
||||
void *(*fn)(uint16_t *, uint32_t) =
|
||||
(void *)(uintptr_t)(*(uint16_t *)0x18);
|
||||
uint16_t *table = (uint16_t *)(uintptr_t)(*(uint16_t *)0x14);
|
||||
void *(*fn)(uint16_t *, uint32_t) = rom_hword_as_ptr(0x18);
|
||||
uint16_t *table = rom_hword_as_ptr(0x14);
|
||||
return fn(table, code);
|
||||
}
|
||||
|
||||
|
||||
@@ -26,7 +26,7 @@ static struct can2040 cbus;
|
||||
|
||||
// Transmit a packet
|
||||
int
|
||||
canbus_send(struct canbus_msg *msg)
|
||||
canhw_send(struct canbus_msg *msg)
|
||||
{
|
||||
int ret = can2040_transmit(&cbus, (void*)msg);
|
||||
if (ret < 0)
|
||||
@@ -36,7 +36,7 @@ canbus_send(struct canbus_msg *msg)
|
||||
|
||||
// Setup the receive packet filter
|
||||
void
|
||||
canbus_set_filter(uint32_t id)
|
||||
canhw_set_filter(uint32_t id)
|
||||
{
|
||||
// Filter not implemented (and not necessary)
|
||||
}
|
||||
|
||||
@@ -48,7 +48,7 @@ mask_to_pin(uint32_t mask)
|
||||
struct gpio_out
|
||||
gpio_out_setup(uint8_t pin, uint8_t val)
|
||||
{
|
||||
if (pin > 30)
|
||||
if (pin >= 30)
|
||||
goto fail;
|
||||
struct gpio_out g = { .bit=1<<pin };
|
||||
gpio_out_reset(g, val);
|
||||
@@ -93,7 +93,7 @@ gpio_out_write(struct gpio_out g, uint8_t val)
|
||||
struct gpio_in
|
||||
gpio_in_setup(uint8_t pin, int8_t pull_up)
|
||||
{
|
||||
if (pin > 30)
|
||||
if (pin >= 30)
|
||||
goto fail;
|
||||
struct gpio_in g = { .bit=1<<pin };
|
||||
gpio_in_reset(g, pull_up);
|
||||
|
||||
@@ -75,8 +75,8 @@ i2c_setup(uint32_t bus, uint32_t rate, uint8_t addr)
|
||||
|
||||
const struct i2c_info *info = &i2c_bus[bus];
|
||||
|
||||
gpio_peripheral(info->sda_pin, 3, 0);
|
||||
gpio_peripheral(info->scl_pin, 3, 0);
|
||||
gpio_peripheral(info->sda_pin, 3, 1);
|
||||
gpio_peripheral(info->scl_pin, 3, 1);
|
||||
|
||||
if (!is_enabled_pclock(info->pclk)) {
|
||||
enable_pclock(info->pclk);
|
||||
|
||||
@@ -5,35 +5,29 @@
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <stdint.h> // uint32_t
|
||||
#include "board/misc.h" // bootloader_request
|
||||
#include "generic/armcm_reset.h" // try_request_canboot
|
||||
#include "hardware/structs/clocks.h" // clock_hw_t
|
||||
#include "hardware/structs/pll.h" // pll_hw_t
|
||||
#include "hardware/structs/resets.h" // sio_hw
|
||||
#include "hardware/structs/watchdog.h" // watchdog_hw
|
||||
#include "hardware/structs/xosc.h" // xosc_hw
|
||||
#include "internal.h" // enable_pclock
|
||||
#include "sched.h" // sched_main
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* watchdog handler
|
||||
* Bootloader
|
||||
****************************************************************/
|
||||
|
||||
void
|
||||
watchdog_reset(void)
|
||||
bootloader_request(void)
|
||||
{
|
||||
watchdog_hw->load = 0x800000; // ~350ms
|
||||
watchdog_hw->ctrl = 0;
|
||||
try_request_canboot();
|
||||
// Use the bootrom-provided code to reset into BOOTSEL mode
|
||||
reset_to_usb_boot(0, 0);
|
||||
}
|
||||
DECL_TASK(watchdog_reset);
|
||||
|
||||
void
|
||||
watchdog_init(void)
|
||||
{
|
||||
watchdog_reset();
|
||||
watchdog_hw->ctrl = (WATCHDOG_CTRL_PAUSE_DBG0_BITS
|
||||
| WATCHDOG_CTRL_PAUSE_DBG1_BITS
|
||||
| WATCHDOG_CTRL_PAUSE_JTAG_BITS
|
||||
| WATCHDOG_CTRL_ENABLE_BITS);
|
||||
}
|
||||
DECL_INIT(watchdog_init);
|
||||
|
||||
|
||||
/****************************************************************
|
||||
|
||||
@@ -4,14 +4,14 @@
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_FLASH_START
|
||||
#include "autoconf.h" // CONFIG_FLASH_SIZE
|
||||
|
||||
OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
|
||||
OUTPUT_ARCH(arm)
|
||||
|
||||
MEMORY
|
||||
{
|
||||
rom (rx) : ORIGIN = CONFIG_FLASH_START , LENGTH = CONFIG_FLASH_SIZE
|
||||
rom (rx) : ORIGIN = 0x10000000 , LENGTH = CONFIG_FLASH_SIZE
|
||||
ram (rwx) : ORIGIN = CONFIG_RAM_START , LENGTH = CONFIG_RAM_SIZE
|
||||
}
|
||||
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
// Hardware interface to USB on rp2040
|
||||
//
|
||||
// Copyright (C) 2021 Kevin O'Connor <kevin@koconnor.net>
|
||||
// Copyright (C) 2021-2023 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
@@ -26,52 +26,46 @@
|
||||
|
||||
#define DPBUF_SIZE 64
|
||||
|
||||
// Get the offset of a given endpoint's base buffer
|
||||
static uint32_t
|
||||
usb_buf_offset(uint32_t ep)
|
||||
{
|
||||
return 0x100 + ep * DPBUF_SIZE * 2;
|
||||
}
|
||||
|
||||
static int_fast8_t
|
||||
usb_write_packet(uint32_t ep, const void *data, uint_fast8_t len)
|
||||
// Obtain a pointer to an endpoint buffer
|
||||
static void*
|
||||
usb_buf_addr(uint32_t ep, int bufnum)
|
||||
{
|
||||
// Check if there is room for this packet
|
||||
uint32_t epb = usb_dpram->ep_buf_ctrl[ep].in;
|
||||
if (epb & (USB_BUF_CTRL_AVAIL|USB_BUF_CTRL_FULL))
|
||||
return -1;
|
||||
uint32_t pid = (epb ^ USB_BUF_CTRL_DATA1_PID) & USB_BUF_CTRL_DATA1_PID;
|
||||
uint32_t new_epb = USB_BUF_CTRL_FULL | USB_BUF_CTRL_LAST | pid | len;
|
||||
usb_dpram->ep_buf_ctrl[ep].in = new_epb;
|
||||
// Copy the packet to the hw buffer
|
||||
void *addr = (void*)usb_dpram + usb_buf_offset(ep);
|
||||
barrier();
|
||||
memcpy(addr, data, len);
|
||||
barrier();
|
||||
// Inform the USB hardware of the available packet
|
||||
usb_dpram->ep_buf_ctrl[ep].in = new_epb | USB_BUF_CTRL_AVAIL;
|
||||
return len;
|
||||
return (void*)usb_dpram + usb_buf_offset(ep) + bufnum * DPBUF_SIZE;
|
||||
}
|
||||
|
||||
static int_fast8_t
|
||||
usb_read_packet(uint32_t ep, void *data, uint_fast8_t max_len)
|
||||
// Return a pointer to the ep_buf_ctrl register for an endpoint
|
||||
static volatile uint16_t *
|
||||
lookup_epbufctrl(uint32_t ep, int is_rx, int bufnum)
|
||||
{
|
||||
volatile uint16_t *epbp;
|
||||
if (is_rx)
|
||||
epbp = (void*)&usb_dpram->ep_buf_ctrl[ep].out;
|
||||
else
|
||||
epbp = (void*)&usb_dpram->ep_buf_ctrl[ep].in;
|
||||
return &epbp[bufnum];
|
||||
}
|
||||
|
||||
// Determine the next transfer PID id from the last PID
|
||||
static uint32_t
|
||||
next_data_pid(uint32_t epb)
|
||||
{
|
||||
return (epb ^ USB_BUF_CTRL_DATA1_PID) & USB_BUF_CTRL_DATA1_PID;
|
||||
}
|
||||
|
||||
// Extract the number of bytes in an rx buffer
|
||||
static uint32_t
|
||||
get_rx_count(uint32_t epb, uint32_t max_len)
|
||||
{
|
||||
// Check if there is a packet ready
|
||||
uint32_t epb = usb_dpram->ep_buf_ctrl[ep].out;
|
||||
if ((epb & (USB_BUF_CTRL_AVAIL|USB_BUF_CTRL_FULL)) != USB_BUF_CTRL_FULL)
|
||||
return -1;
|
||||
// Copy the packet to the given buffer
|
||||
uint32_t pid = (epb ^ USB_BUF_CTRL_DATA1_PID) & USB_BUF_CTRL_DATA1_PID;
|
||||
uint32_t new_epb = USB_BUF_CTRL_LAST | pid | DPBUF_SIZE;
|
||||
usb_dpram->ep_buf_ctrl[ep].out = new_epb;
|
||||
uint32_t c = epb & USB_BUF_CTRL_LEN_MASK;
|
||||
if (c > max_len)
|
||||
c = max_len;
|
||||
void *addr = (void*)usb_dpram + usb_buf_offset(ep);
|
||||
barrier();
|
||||
memcpy(data, addr, c);
|
||||
barrier();
|
||||
// Notify the USB hardware that the space is now available
|
||||
usb_dpram->ep_buf_ctrl[ep].out = new_epb | USB_BUF_CTRL_AVAIL;
|
||||
return c;
|
||||
}
|
||||
|
||||
@@ -80,23 +74,65 @@ usb_read_packet(uint32_t ep, void *data, uint_fast8_t max_len)
|
||||
* Interface
|
||||
****************************************************************/
|
||||
|
||||
static uint32_t bulk_out_push_count;
|
||||
|
||||
int_fast8_t
|
||||
usb_read_bulk_out(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
return usb_read_packet(USB_CDC_EP_BULK_OUT, data, max_len);
|
||||
// Check if there is a packet ready
|
||||
uint32_t bopc = bulk_out_push_count, bufnum = bopc & 1;
|
||||
uint32_t ep = USB_CDC_EP_BULK_OUT;
|
||||
volatile uint16_t *epbp = lookup_epbufctrl(ep, 1, bufnum);
|
||||
uint32_t epb = *epbp;
|
||||
if ((epb & (USB_BUF_CTRL_AVAIL|USB_BUF_CTRL_FULL)) != USB_BUF_CTRL_FULL)
|
||||
return -1;
|
||||
// Determine the next packet header
|
||||
bulk_out_push_count = bopc + 1;
|
||||
uint32_t pid = bufnum ? USB_BUF_CTRL_DATA1_PID : 0;
|
||||
uint32_t new_epb = USB_BUF_CTRL_LAST | pid | DPBUF_SIZE;
|
||||
*epbp = new_epb;
|
||||
barrier();
|
||||
// Copy the packet to the given buffer
|
||||
uint32_t c = get_rx_count(epb, max_len);
|
||||
memcpy(data, usb_buf_addr(ep, bufnum), c);
|
||||
// Notify the USB hardware that the space is now available
|
||||
barrier();
|
||||
*epbp = new_epb | USB_BUF_CTRL_AVAIL;
|
||||
return c;
|
||||
}
|
||||
|
||||
static uint32_t bulk_in_pop_count;
|
||||
|
||||
int_fast8_t
|
||||
usb_send_bulk_in(void *data, uint_fast8_t len)
|
||||
{
|
||||
return usb_write_packet(USB_CDC_EP_BULK_IN, data, len);
|
||||
// Check if there is room for this packet
|
||||
uint32_t bipc = bulk_in_pop_count, bufnum = bipc & 1;
|
||||
uint32_t ep = USB_CDC_EP_BULK_IN;
|
||||
volatile uint16_t *epbp = lookup_epbufctrl(ep, 0, bufnum);
|
||||
uint32_t epb = *epbp;
|
||||
if (epb & (USB_BUF_CTRL_AVAIL|USB_BUF_CTRL_FULL))
|
||||
return -1;
|
||||
// Determine the next packet header
|
||||
bulk_in_pop_count = bipc + 1;
|
||||
uint32_t pid = bufnum ? USB_BUF_CTRL_DATA1_PID : 0;
|
||||
uint32_t new_epb = USB_BUF_CTRL_FULL | USB_BUF_CTRL_LAST | pid | len;
|
||||
*epbp = new_epb;
|
||||
barrier();
|
||||
// Copy the packet to the hw buffer
|
||||
memcpy(usb_buf_addr(ep, bufnum), data, len);
|
||||
// Inform the USB hardware of the available packet
|
||||
barrier();
|
||||
*epbp = new_epb | USB_BUF_CTRL_AVAIL;
|
||||
return len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_read_ep0_setup(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
if (!(usb_hw->intr & USB_INTR_SETUP_REQ_BITS)) {
|
||||
usb_hw->inte = USB_INTE_BUFF_STATUS_BITS | USB_INTE_SETUP_REQ_BITS;
|
||||
usb_hw->inte = (USB_INTE_BUFF_STATUS_BITS | USB_INTE_SETUP_REQ_BITS
|
||||
| USB_INTE_BUS_RESET_BITS);
|
||||
return -1;
|
||||
}
|
||||
usb_dpram->ep_buf_ctrl[0].in = 0;
|
||||
@@ -117,19 +153,51 @@ usb_read_ep0_setup(void *data, uint_fast8_t max_len)
|
||||
int_fast8_t
|
||||
usb_read_ep0(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
// Check if there is a packet ready
|
||||
uint32_t ep = 0;
|
||||
if (usb_hw->intr & USB_INTR_SETUP_REQ_BITS)
|
||||
// Early end of transmission
|
||||
return -2;
|
||||
return usb_read_packet(0, data, max_len);
|
||||
volatile uint16_t *epbp = lookup_epbufctrl(ep, 1, 0);
|
||||
uint32_t epb = *epbp;
|
||||
if ((epb & (USB_BUF_CTRL_AVAIL|USB_BUF_CTRL_FULL)) != USB_BUF_CTRL_FULL)
|
||||
return -1;
|
||||
// Determine the next packet header
|
||||
uint32_t new_epb = USB_BUF_CTRL_LAST | next_data_pid(epb) | DPBUF_SIZE;
|
||||
*epbp = new_epb;
|
||||
barrier();
|
||||
// Copy the packet to the given buffer
|
||||
uint32_t c = get_rx_count(epb, max_len);
|
||||
memcpy(data, usb_buf_addr(ep, 0), c);
|
||||
// Notify the USB hardware that the space is now available
|
||||
barrier();
|
||||
*epbp = new_epb | USB_BUF_CTRL_AVAIL;
|
||||
return c;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_send_ep0(const void *data, uint_fast8_t len)
|
||||
{
|
||||
// Check if there is room for this packet
|
||||
uint32_t ep = 0;
|
||||
if (usb_hw->intr & USB_INTR_SETUP_REQ_BITS || usb_hw->buf_status & 2)
|
||||
// Early end of transmission
|
||||
return -2;
|
||||
return usb_write_packet(0, data, len);
|
||||
volatile uint16_t *epbp = lookup_epbufctrl(ep, 0, 0);
|
||||
uint32_t epb = *epbp;
|
||||
if (epb & (USB_BUF_CTRL_AVAIL|USB_BUF_CTRL_FULL))
|
||||
return -1;
|
||||
// Determine the next packet header
|
||||
uint32_t pid = next_data_pid(epb);
|
||||
uint32_t new_epb = USB_BUF_CTRL_FULL | USB_BUF_CTRL_LAST | pid | len;
|
||||
*epbp = new_epb;
|
||||
barrier();
|
||||
// Copy the packet to the hw buffer
|
||||
memcpy(usb_buf_addr(ep, 0), data, len);
|
||||
// Inform the USB hardware of the available packet
|
||||
barrier();
|
||||
*epbp = new_epb | USB_BUF_CTRL_AVAIL;
|
||||
return len;
|
||||
}
|
||||
|
||||
void
|
||||
@@ -155,16 +223,13 @@ usb_set_address(uint_fast8_t addr)
|
||||
void
|
||||
usb_set_configure(void)
|
||||
{
|
||||
usb_dpram->ep_buf_ctrl[USB_CDC_EP_BULK_IN].in = USB_BUF_CTRL_DATA1_PID;
|
||||
usb_dpram->ep_buf_ctrl[USB_CDC_EP_BULK_OUT].out = (
|
||||
USB_BUF_CTRL_AVAIL | USB_BUF_CTRL_LAST | DPBUF_SIZE);
|
||||
}
|
||||
bulk_in_pop_count = 0;
|
||||
usb_dpram->ep_buf_ctrl[USB_CDC_EP_BULK_IN].in = 0;
|
||||
|
||||
void
|
||||
usb_request_bootloader(void)
|
||||
{
|
||||
// Use the bootrom-provided code to reset into BOOTSEL mode
|
||||
reset_to_usb_boot(0, 0);
|
||||
bulk_out_push_count = 0;
|
||||
uint32_t epb0 = USB_BUF_CTRL_AVAIL | USB_BUF_CTRL_LAST | DPBUF_SIZE;
|
||||
uint32_t epb1 = epb0 | USB_BUF_CTRL_DATA1_PID;
|
||||
usb_dpram->ep_buf_ctrl[USB_CDC_EP_BULK_OUT].out = epb0 | (epb1 << 16);
|
||||
}
|
||||
|
||||
|
||||
@@ -175,6 +240,7 @@ usb_request_bootloader(void)
|
||||
// The rp2040 USB has an errata causing it to sometimes not connect
|
||||
// after a reset. The following code has extracts from the PICO SDK.
|
||||
|
||||
static uint8_t need_errata;
|
||||
static struct task_wake usb_errata_wake;
|
||||
|
||||
// Workaround for rp2040-e5 errata
|
||||
@@ -260,7 +326,7 @@ USB_Handler(void)
|
||||
{
|
||||
uint32_t ints = usb_hw->ints;
|
||||
if (ints & USB_INTS_SETUP_REQ_BITS) {
|
||||
usb_hw->inte = USB_INTE_BUFF_STATUS_BITS;
|
||||
usb_hw->inte = USB_INTE_BUFF_STATUS_BITS | USB_INTE_BUS_RESET_BITS;
|
||||
usb_notify_ep0();
|
||||
}
|
||||
if (ints & USB_INTS_BUFF_STATUS_BITS) {
|
||||
@@ -279,8 +345,10 @@ USB_Handler(void)
|
||||
}
|
||||
}
|
||||
if (ints & USB_INTS_BUS_RESET_BITS) {
|
||||
usb_hw->dev_addr_ctrl = 0;
|
||||
usb_hw->sie_status = USB_SIE_STATUS_BUS_RESET_BITS;
|
||||
sched_wake_task(&usb_errata_wake);
|
||||
if (need_errata)
|
||||
sched_wake_task(&usb_errata_wake);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -293,10 +361,12 @@ endpoint_setup(void)
|
||||
usb_dpram->ep_ctrl[USB_CDC_EP_ACM-1].in = ep_acm;
|
||||
// BULK
|
||||
uint32_t ep_out = (EP_CTRL_ENABLE_BITS | usb_buf_offset(USB_CDC_EP_BULK_OUT)
|
||||
| EP_CTRL_DOUBLE_BUFFERED_BITS
|
||||
| EP_CTRL_INTERRUPT_PER_BUFFER
|
||||
| (USB_ENDPOINT_XFER_BULK << EP_CTRL_BUFFER_TYPE_LSB));
|
||||
usb_dpram->ep_ctrl[USB_CDC_EP_BULK_OUT-1].out = ep_out;
|
||||
uint32_t ep_in = (EP_CTRL_ENABLE_BITS | usb_buf_offset(USB_CDC_EP_BULK_IN)
|
||||
| EP_CTRL_DOUBLE_BUFFERED_BITS
|
||||
| EP_CTRL_INTERRUPT_PER_BUFFER
|
||||
| (USB_ENDPOINT_XFER_BULK << EP_CTRL_BUFFER_TYPE_LSB));
|
||||
usb_dpram->ep_ctrl[USB_CDC_EP_BULK_IN-1].in = ep_in;
|
||||
@@ -324,11 +394,12 @@ usbserial_init(void)
|
||||
uint32_t chip_id = *((io_ro_32*)(SYSINFO_BASE + SYSINFO_CHIP_ID_OFFSET));
|
||||
uint32_t version = ((chip_id & SYSINFO_CHIP_ID_REVISION_BITS)
|
||||
>> SYSINFO_CHIP_ID_REVISION_LSB);
|
||||
need_errata = (version == 1);
|
||||
|
||||
// Enable irqs
|
||||
usb_hw->sie_ctrl = USB_SIE_CTRL_EP0_INT_1BUF_BITS;
|
||||
usb_hw->inte = (USB_INTE_BUFF_STATUS_BITS | USB_INTE_SETUP_REQ_BITS
|
||||
| (version == 1 ? USB_INTE_BUS_RESET_BITS: 0));
|
||||
| USB_INTE_BUS_RESET_BITS);
|
||||
armcm_enable_irq(USB_Handler, USBCTRL_IRQ_IRQn, 1);
|
||||
|
||||
// Enable USB pullup
|
||||
|
||||
29
src/rp2040/watchdog.c
Normal file
29
src/rp2040/watchdog.c
Normal file
@@ -0,0 +1,29 @@
|
||||
// Watchdog code on rp2040
|
||||
//
|
||||
// Copyright (C) 2021-2022 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 "hardware/structs/psm.h" // psm_hw
|
||||
#include "hardware/structs/watchdog.h" // watchdog_hw
|
||||
#include "sched.h" // DECL_TASK
|
||||
|
||||
void
|
||||
watchdog_reset(void)
|
||||
{
|
||||
watchdog_hw->load = 0x800000; // ~350ms
|
||||
}
|
||||
DECL_TASK(watchdog_reset);
|
||||
|
||||
void
|
||||
watchdog_init(void)
|
||||
{
|
||||
psm_hw->wdsel = PSM_WDSEL_BITS & ~(PSM_WDSEL_ROSC_BITS|PSM_WDSEL_XOSC_BITS);
|
||||
watchdog_reset();
|
||||
watchdog_hw->ctrl = (WATCHDOG_CTRL_PAUSE_DBG0_BITS
|
||||
| WATCHDOG_CTRL_PAUSE_DBG1_BITS
|
||||
| WATCHDOG_CTRL_PAUSE_JTAG_BITS
|
||||
| WATCHDOG_CTRL_ENABLE_BITS);
|
||||
}
|
||||
DECL_INIT(watchdog_init);
|
||||
166
src/sdiocmds.c
Normal file
166
src/sdiocmds.c
Normal file
@@ -0,0 +1,166 @@
|
||||
// Commands for sending messages on an SDIO bus
|
||||
//
|
||||
// Copyright (C) 2022 H. Gregor Molter <gregor.molter@secretlab.de>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memcpy
|
||||
#include "board/gpio.h" // gpio_in_setup
|
||||
#include "board/sdio.h" // sdio_setup
|
||||
#include "basecmd.h" // oid_alloc
|
||||
#include "command.h" // DECL_COMMAND
|
||||
#include "sched.h" // DECL_SHUTDOWN
|
||||
|
||||
struct sdiodev_s {
|
||||
struct sdio_config sdio_config;
|
||||
uint32_t blocksize;
|
||||
uint32_t speed;
|
||||
uint8_t data_buffer[4096];
|
||||
};
|
||||
|
||||
#define TIMEOUT_MSEC 500
|
||||
|
||||
void
|
||||
command_config_sdio(uint32_t *args)
|
||||
{
|
||||
struct sdiodev_s *sdio = oid_alloc(args[0], command_config_sdio
|
||||
, sizeof(*sdio));
|
||||
sdio->blocksize = args[1];
|
||||
sdio->speed = 400000; // Initial speed set to ~400khz
|
||||
}
|
||||
DECL_COMMAND(command_config_sdio, "config_sdio oid=%c blocksize=%u");
|
||||
|
||||
struct sdiodev_s *
|
||||
sdiodev_oid_lookup(uint8_t oid)
|
||||
{
|
||||
return oid_lookup(oid, command_config_sdio);
|
||||
}
|
||||
|
||||
void
|
||||
command_sdio_set_bus(uint32_t *args)
|
||||
{
|
||||
struct sdiodev_s *sdio = sdiodev_oid_lookup(args[0]);
|
||||
sdio->sdio_config = sdio_setup(args[1]);
|
||||
}
|
||||
DECL_COMMAND(command_sdio_set_bus, "sdio_set_bus oid=%c sdio_bus=%u");
|
||||
|
||||
void
|
||||
command_sdio_set_speed(uint32_t *args)
|
||||
{
|
||||
struct sdiodev_s *sdio = sdiodev_oid_lookup(args[0]);
|
||||
sdio->speed = args[1];
|
||||
sdio_set_speed(sdio->sdio_config, sdio->speed);
|
||||
}
|
||||
DECL_COMMAND(command_sdio_set_speed, "sdio_set_speed oid=%c speed=%u");
|
||||
|
||||
void
|
||||
command_sdio_send_command(uint32_t *args)
|
||||
{
|
||||
uint8_t oid = args[0];
|
||||
uint8_t cmd = args[1];
|
||||
uint32_t argument = args[2];
|
||||
uint8_t wait = args[3];
|
||||
struct sdiodev_s *sdio = sdiodev_oid_lookup(oid);
|
||||
uint8_t response[16];
|
||||
uint8_t response_len = 0;
|
||||
uint8_t err = sdio_send_command(sdio->sdio_config, cmd, argument, wait
|
||||
, response, &response_len);
|
||||
sendf("sdio_send_command_response oid=%c error=%c response=%*s"
|
||||
, oid, err, response_len, response);
|
||||
}
|
||||
DECL_COMMAND(command_sdio_send_command
|
||||
, "sdio_send_command oid=%c cmd=%c argument=%u wait=%c");
|
||||
|
||||
void
|
||||
command_sdio_read_data(uint32_t *args)
|
||||
{
|
||||
uint8_t oid = args[0];
|
||||
uint8_t cmd = args[1];
|
||||
uint32_t argument = args[2];
|
||||
uint32_t data_len = 0;
|
||||
struct sdiodev_s *sdio = sdiodev_oid_lookup(oid);
|
||||
uint32_t timeout = TIMEOUT_MSEC*sdio->speed/1000;
|
||||
uint8_t err = sdio_prepare_data_transfer(sdio->sdio_config, 1, 1
|
||||
, sdio->blocksize, timeout);
|
||||
if (err == 0) {
|
||||
err = sdio_send_command(sdio->sdio_config, cmd, argument
|
||||
, 1, NULL, NULL);
|
||||
if (err == 0) {
|
||||
data_len = sdio->blocksize;
|
||||
if (data_len <= sizeof(sdio->data_buffer)) {
|
||||
err = sdio_read_data(sdio->sdio_config, sdio->data_buffer
|
||||
, 1, sdio->blocksize);
|
||||
} else {
|
||||
data_len = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
sendf("sdio_read_data_response oid=%c error=%c read=%u"
|
||||
, oid, err, data_len);
|
||||
}
|
||||
DECL_COMMAND(command_sdio_read_data
|
||||
, "sdio_read_data oid=%c cmd=%c argument=%u");
|
||||
|
||||
void
|
||||
command_sdio_write_data(uint32_t *args)
|
||||
{
|
||||
uint8_t oid = args[0];
|
||||
uint8_t cmd = args[1];
|
||||
uint32_t argument = args[2];
|
||||
uint32_t data_len = 0;
|
||||
struct sdiodev_s *sdio = sdiodev_oid_lookup(oid);
|
||||
uint32_t timeout = TIMEOUT_MSEC*sdio->speed/1000;
|
||||
uint8_t err = sdio_prepare_data_transfer(sdio->sdio_config, 0, 1
|
||||
, sdio->blocksize, timeout);
|
||||
if (err == 0) {
|
||||
err = sdio_send_command(sdio->sdio_config, cmd, argument
|
||||
, 1, NULL, NULL);
|
||||
if (err == 0) {
|
||||
data_len = sdio->blocksize;
|
||||
if (data_len <= sizeof(sdio->data_buffer)) {
|
||||
err = sdio_write_data(sdio->sdio_config, sdio->data_buffer
|
||||
, 1, sdio->blocksize);
|
||||
} else {
|
||||
data_len = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
sendf("sdio_write_data_response oid=%c error=%c write=%u"
|
||||
, oid, err, data_len);
|
||||
}
|
||||
DECL_COMMAND(command_sdio_write_data
|
||||
, "sdio_write_data oid=%c cmd=%c argument=%u");
|
||||
|
||||
void
|
||||
command_sdio_read_data_buffer(uint32_t *args)
|
||||
{
|
||||
uint8_t oid = args[0];
|
||||
uint32_t offset = args[1];
|
||||
uint8_t len = args[2];
|
||||
struct sdiodev_s *sdio = sdiodev_oid_lookup(oid);
|
||||
uint8_t *buf = &(sdio->data_buffer[offset]);
|
||||
|
||||
if (offset + len > sizeof(sdio->data_buffer)) {
|
||||
len = 0;
|
||||
}
|
||||
sendf("sdio_read_data_buffer_response oid=%c data=%*s", oid, len, buf);
|
||||
}
|
||||
DECL_COMMAND(command_sdio_read_data_buffer
|
||||
, "sdio_read_data_buffer oid=%c offset=%u len=%c");
|
||||
|
||||
void
|
||||
command_sdio_write_data_buffer(uint32_t *args)
|
||||
{
|
||||
uint8_t oid = args[0];
|
||||
uint32_t offset = args[1];
|
||||
uint8_t write_data_len = args[2];
|
||||
uint8_t *write_data = command_decode_ptr(args[3]);
|
||||
struct sdiodev_s *sdio = sdiodev_oid_lookup(oid);
|
||||
uint8_t *buf = &(sdio->data_buffer[offset]);
|
||||
|
||||
if (offset + write_data_len <= sizeof(sdio->data_buffer)) {
|
||||
memcpy(buf, write_data, write_data_len);
|
||||
}
|
||||
}
|
||||
DECL_COMMAND(command_sdio_write_data_buffer
|
||||
, "sdio_write_data_buffer oid=%c offset=%u data=%*s");
|
||||
8
src/sdiocmds.h
Normal file
8
src/sdiocmds.h
Normal file
@@ -0,0 +1,8 @@
|
||||
#ifndef __SDIOCMDS_H
|
||||
#define __SDIOCMDS_H
|
||||
|
||||
#include <stdint.h> // uint8_t
|
||||
|
||||
struct sdiodev_s *sdiodev_oid_lookup(uint8_t oid);
|
||||
|
||||
#endif // sdiocmds.h
|
||||
221
src/sensor_lis2dw.c
Normal file
221
src/sensor_lis2dw.c
Normal file
@@ -0,0 +1,221 @@
|
||||
// Support for gathering acceleration data from LIS2DW chip
|
||||
//
|
||||
// Copyright (C) 2023 Zhou.XianMing <zhouxm@biqu3d.com>
|
||||
// Copyright (C) 2020 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memcpy
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "board/misc.h" // timer_read_time
|
||||
#include "basecmd.h" // oid_alloc
|
||||
#include "command.h" // DECL_COMMAND
|
||||
#include "sched.h" // DECL_TASK
|
||||
#include "spicmds.h" // spidev_transfer
|
||||
|
||||
#define LIS_AR_DATAX0 0x28
|
||||
#define LIS_AM_READ 0x80
|
||||
#define LIS_FIFO_CTRL 0x2E
|
||||
#define LIS_FIFO_SAMPLES 0x2F
|
||||
|
||||
struct lis2dw {
|
||||
struct timer timer;
|
||||
uint32_t rest_ticks;
|
||||
struct spidev_s *spi;
|
||||
uint16_t sequence, limit_count;
|
||||
uint8_t flags, data_count, fifo_disable;
|
||||
uint8_t data[48];
|
||||
};
|
||||
|
||||
enum {
|
||||
LIS_HAVE_START = 1<<0, LIS_RUNNING = 1<<1, LIS_PENDING = 1<<2,
|
||||
};
|
||||
|
||||
static struct task_wake lis2dw_wake;
|
||||
|
||||
// Event handler that wakes lis2dw_task() periodically
|
||||
static uint_fast8_t
|
||||
lis2dw_event(struct timer *timer)
|
||||
{
|
||||
struct lis2dw *ax = container_of(timer, struct lis2dw, timer);
|
||||
ax->flags |= LIS_PENDING;
|
||||
sched_wake_task(&lis2dw_wake);
|
||||
return SF_DONE;
|
||||
}
|
||||
|
||||
void
|
||||
command_config_lis2dw(uint32_t *args)
|
||||
{
|
||||
struct lis2dw *ax = oid_alloc(args[0], command_config_lis2dw
|
||||
, sizeof(*ax));
|
||||
ax->timer.func = lis2dw_event;
|
||||
ax->spi = spidev_oid_lookup(args[1]);
|
||||
}
|
||||
DECL_COMMAND(command_config_lis2dw, "config_lis2dw oid=%c spi_oid=%c");
|
||||
|
||||
// Report local measurement buffer
|
||||
static void
|
||||
lis2dw_report(struct lis2dw *ax, uint8_t oid)
|
||||
{
|
||||
sendf("lis2dw_data oid=%c sequence=%hu data=%*s"
|
||||
, oid, ax->sequence, ax->data_count, ax->data);
|
||||
ax->data_count = 0;
|
||||
ax->sequence++;
|
||||
}
|
||||
|
||||
// Report buffer and fifo status
|
||||
static void
|
||||
lis2dw_status(struct lis2dw *ax, uint_fast8_t oid
|
||||
, uint32_t time1, uint32_t time2, uint_fast8_t fifo)
|
||||
{
|
||||
sendf("lis2dw_status oid=%c clock=%u query_ticks=%u next_sequence=%hu"
|
||||
" buffered=%c fifo=%c limit_count=%hu"
|
||||
, oid, time1, time2-time1, ax->sequence
|
||||
, ax->data_count, fifo, ax->limit_count);
|
||||
}
|
||||
|
||||
// Helper code to reschedule the lis2dw_event() timer
|
||||
static void
|
||||
lis2dw_reschedule_timer(struct lis2dw *ax)
|
||||
{
|
||||
irq_disable();
|
||||
ax->timer.waketime = timer_read_time() + ax->rest_ticks;
|
||||
sched_add_timer(&ax->timer);
|
||||
irq_enable();
|
||||
}
|
||||
|
||||
// Query accelerometer data
|
||||
static void
|
||||
lis2dw_query(struct lis2dw *ax, uint8_t oid)
|
||||
{
|
||||
uint8_t msg[7] = {0};
|
||||
uint8_t fifo[2] = {LIS_FIFO_SAMPLES| LIS_AM_READ , 0};
|
||||
uint8_t fifo_empty,fifo_ovrn = 0;
|
||||
|
||||
msg[0] = LIS_AR_DATAX0 | LIS_AM_READ ;
|
||||
uint8_t *d = &ax->data[ax->data_count];
|
||||
|
||||
spidev_transfer(ax->spi, 1, sizeof(msg), msg);
|
||||
|
||||
spidev_transfer(ax->spi, 1, sizeof(fifo), fifo);
|
||||
fifo_empty = fifo[1]&0x3F;
|
||||
fifo_ovrn = fifo[1]&0x40;
|
||||
|
||||
d[0] = msg[1]; // x low bits
|
||||
d[1] = msg[2]; // x high bits
|
||||
d[2] = msg[3]; // y low bits
|
||||
d[3] = msg[4]; // y high bits
|
||||
d[4] = msg[5]; // z low bits
|
||||
d[5] = msg[6]; // z high bits
|
||||
|
||||
ax->data_count += 6;
|
||||
if (ax->data_count + 6 > ARRAY_SIZE(ax->data))
|
||||
lis2dw_report(ax, oid);
|
||||
|
||||
// Check fifo status
|
||||
if (fifo_ovrn)
|
||||
ax->limit_count++;
|
||||
|
||||
// check if we need to run the task again (more packets in fifo?)
|
||||
if (!fifo_empty&&!(ax->fifo_disable)) {
|
||||
// More data in fifo - wake this task again
|
||||
sched_wake_task(&lis2dw_wake);
|
||||
} else if (ax->flags & LIS_RUNNING) {
|
||||
// Sleep until next check time
|
||||
sched_del_timer(&ax->timer);
|
||||
ax->flags &= ~LIS_PENDING;
|
||||
lis2dw_reschedule_timer(ax);
|
||||
}
|
||||
}
|
||||
|
||||
// Startup measurements
|
||||
static void
|
||||
lis2dw_start(struct lis2dw *ax, uint8_t oid)
|
||||
{
|
||||
sched_del_timer(&ax->timer);
|
||||
ax->flags = LIS_RUNNING;
|
||||
ax->fifo_disable = 0;
|
||||
uint8_t ctrl[2] = {LIS_FIFO_CTRL , 0xC0};
|
||||
spidev_transfer(ax->spi, 0, sizeof(ctrl), ctrl);
|
||||
lis2dw_reschedule_timer(ax);
|
||||
}
|
||||
|
||||
// End measurements
|
||||
static void
|
||||
lis2dw_stop(struct lis2dw *ax, uint8_t oid)
|
||||
{
|
||||
// Disable measurements
|
||||
sched_del_timer(&ax->timer);
|
||||
ax->flags = 0;
|
||||
// Drain any measurements still in fifo
|
||||
ax->fifo_disable = 1;
|
||||
lis2dw_query(ax, oid);
|
||||
|
||||
uint8_t ctrl[2] = {LIS_FIFO_CTRL , 0};
|
||||
uint32_t end1_time = timer_read_time();
|
||||
spidev_transfer(ax->spi, 0, sizeof(ctrl), ctrl);
|
||||
uint32_t end2_time = timer_read_time();
|
||||
|
||||
uint8_t msg[2] = { LIS_FIFO_SAMPLES | LIS_AM_READ , 0};
|
||||
spidev_transfer(ax->spi, 1, sizeof(msg), msg);
|
||||
uint8_t fifo_status = msg[1]&0x1f;
|
||||
|
||||
//Report final data
|
||||
if (ax->data_count)
|
||||
lis2dw_report(ax, oid);
|
||||
lis2dw_status(ax, oid, end1_time, end2_time, fifo_status);
|
||||
}
|
||||
|
||||
void
|
||||
command_query_lis2dw(uint32_t *args)
|
||||
{
|
||||
struct lis2dw *ax = oid_lookup(args[0], command_config_lis2dw);
|
||||
|
||||
if (!args[2]) {
|
||||
// End measurements
|
||||
lis2dw_stop(ax, args[0]);
|
||||
return;
|
||||
}
|
||||
// Start new measurements query
|
||||
sched_del_timer(&ax->timer);
|
||||
ax->timer.waketime = args[1];
|
||||
ax->rest_ticks = args[2];
|
||||
ax->flags = LIS_HAVE_START;
|
||||
ax->sequence = ax->limit_count = 0;
|
||||
ax->data_count = 0;
|
||||
ax->fifo_disable = 0;
|
||||
sched_add_timer(&ax->timer);
|
||||
}
|
||||
DECL_COMMAND(command_query_lis2dw,
|
||||
"query_lis2dw oid=%c clock=%u rest_ticks=%u");
|
||||
|
||||
void
|
||||
command_query_lis2dw_status(uint32_t *args)
|
||||
{
|
||||
struct lis2dw *ax = oid_lookup(args[0], command_config_lis2dw);
|
||||
uint8_t msg[2] = { LIS_FIFO_SAMPLES | LIS_AM_READ, 0x00 };
|
||||
uint32_t time1 = timer_read_time();
|
||||
spidev_transfer(ax->spi, 1, sizeof(msg), msg);
|
||||
uint32_t time2 = timer_read_time();
|
||||
lis2dw_status(ax, args[0], time1, time2, msg[1]&0x1f);
|
||||
}
|
||||
DECL_COMMAND(command_query_lis2dw_status, "query_lis2dw_status oid=%c");
|
||||
|
||||
void
|
||||
lis2dw_task(void)
|
||||
{
|
||||
if (!sched_check_wake(&lis2dw_wake))
|
||||
return;
|
||||
uint8_t oid;
|
||||
struct lis2dw *ax;
|
||||
foreach_oid(oid, ax, command_config_lis2dw) {
|
||||
uint_fast8_t flags = ax->flags;
|
||||
if (!(flags & LIS_PENDING))
|
||||
continue;
|
||||
if (flags & LIS_HAVE_START)
|
||||
lis2dw_start(ax, oid);
|
||||
else
|
||||
lis2dw_query(ax, oid);
|
||||
}
|
||||
}
|
||||
DECL_TASK(lis2dw_task);
|
||||
@@ -1,5 +1,6 @@
|
||||
// Support for gathering acceleration data from mpu9250 chip
|
||||
//
|
||||
// Copyright (C) 2023 Matthew Swabey <matthew@swabey.org>
|
||||
// Copyright (C) 2022 Harry Beyel <harry3b9@gmail.com>
|
||||
// Copyright (C) 2020-2021 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
@@ -24,6 +25,7 @@
|
||||
#define AR_USER_CTRL 0x6A
|
||||
#define AR_FIFO_COUNT_H 0x72
|
||||
#define AR_FIFO 0x74
|
||||
#define AR_INT_STATUS 0x3A
|
||||
|
||||
#define SET_ENABLE_FIFO 0x08
|
||||
#define SET_DISABLE_FIFO 0x00
|
||||
@@ -35,17 +37,20 @@
|
||||
#define SET_PWR_2_ACCEL 0x07 // only enable accelerometers
|
||||
#define SET_PWR_2_NONE 0x3F // disable all sensors
|
||||
|
||||
#define FIFO_OVERFLOW_INT 0x10
|
||||
|
||||
#define BYTES_PER_FIFO_ENTRY 6
|
||||
#define BYTES_PER_BLOCK 48
|
||||
|
||||
struct mpu9250 {
|
||||
struct timer timer;
|
||||
uint32_t rest_ticks;
|
||||
struct i2cdev_s *i2c;
|
||||
uint16_t sequence, limit_count;
|
||||
uint16_t sequence, limit_count, fifo_max, fifo_pkts_bytes;
|
||||
uint8_t flags, data_count;
|
||||
// data size must be <= 255 due to i2c api
|
||||
// msg size must be <= 255 due to Klipper api
|
||||
// = SAMPLES_PER_BLOCK (from mpu9250.py) * BYTES_PER_FIFO_ENTRY + 1
|
||||
uint8_t data[48];
|
||||
uint8_t data[BYTES_PER_BLOCK];
|
||||
};
|
||||
|
||||
enum {
|
||||
@@ -55,14 +60,16 @@ enum {
|
||||
static struct task_wake mpu9250_wake;
|
||||
|
||||
// Reads the fifo byte count from the device.
|
||||
uint16_t
|
||||
static uint16_t
|
||||
get_fifo_status (struct mpu9250 *mp)
|
||||
{
|
||||
uint8_t regs[] = {AR_FIFO_COUNT_H};
|
||||
uint8_t reg[] = {AR_FIFO_COUNT_H};
|
||||
uint8_t msg[2];
|
||||
i2c_read(mp->i2c->i2c_config, sizeof(regs), regs, 2, msg);
|
||||
msg[0] = 0x1F & msg[0]; // discard 3 MSB per datasheet
|
||||
return (((uint16_t)msg[0]) << 8 | msg[1]);
|
||||
i2c_read(mp->i2c->i2c_config, sizeof(reg), reg, sizeof(msg), msg);
|
||||
uint16_t fifo_bytes = ((msg[0] & 0x1f) << 8) | msg[1];
|
||||
if (fifo_bytes > mp->fifo_max)
|
||||
mp->fifo_max = fifo_bytes;
|
||||
return fifo_bytes;
|
||||
}
|
||||
|
||||
// Event handler that wakes mpu9250_task() periodically
|
||||
@@ -120,42 +127,25 @@ mp9250_reschedule_timer(struct mpu9250 *mp)
|
||||
static void
|
||||
mp9250_query(struct mpu9250 *mp, uint8_t oid)
|
||||
{
|
||||
// Check fifo status
|
||||
uint16_t fifo_bytes = get_fifo_status(mp);
|
||||
if (fifo_bytes >= AR_FIFO_SIZE - BYTES_PER_FIFO_ENTRY)
|
||||
mp->limit_count++;
|
||||
// If not enough bytes to fill report read MPU FIFO's fill
|
||||
if (mp->fifo_pkts_bytes < BYTES_PER_BLOCK)
|
||||
mp->fifo_pkts_bytes = get_fifo_status(mp);
|
||||
|
||||
// Read data
|
||||
// FIFO data are: [Xh, Xl, Yh, Yl, Zh, Zl]
|
||||
uint8_t reg = AR_FIFO;
|
||||
uint8_t bytes_to_read = fifo_bytes < sizeof(mp->data) - mp->data_count ?
|
||||
fifo_bytes & 0xFF :
|
||||
(sizeof(mp->data) - mp->data_count) & 0xFF;
|
||||
|
||||
// round down to nearest full packet of data
|
||||
bytes_to_read = bytes_to_read / BYTES_PER_FIFO_ENTRY * BYTES_PER_FIFO_ENTRY;
|
||||
|
||||
// Extract x, y, z measurements into data holder and report
|
||||
if (bytes_to_read > 0) {
|
||||
i2c_read(mp->i2c->i2c_config, sizeof(reg), ®,
|
||||
bytes_to_read, &mp->data[mp->data_count]);
|
||||
mp->data_count += bytes_to_read;
|
||||
|
||||
// report data when buffer is full
|
||||
if (mp->data_count + BYTES_PER_FIFO_ENTRY > sizeof(mp->data)) {
|
||||
mp9250_report(mp, oid);
|
||||
}
|
||||
// If we have enough bytes to fill the buffer do it and send report
|
||||
if (mp->fifo_pkts_bytes >= BYTES_PER_BLOCK) {
|
||||
uint8_t reg = AR_FIFO;
|
||||
i2c_read(mp->i2c->i2c_config, sizeof(reg), ®
|
||||
, BYTES_PER_BLOCK, &mp->data[0]);
|
||||
mp->data_count = BYTES_PER_BLOCK;
|
||||
mp->fifo_pkts_bytes -= BYTES_PER_BLOCK;
|
||||
mp9250_report(mp, oid);
|
||||
}
|
||||
|
||||
// check if we need to run the task again (more packets in fifo?)
|
||||
if ( bytes_to_read > 0 &&
|
||||
bytes_to_read / BYTES_PER_FIFO_ENTRY <
|
||||
fifo_bytes / BYTES_PER_FIFO_ENTRY) {
|
||||
// more data still ready in the fifo buffer
|
||||
// If we have enough bytes remaining to fill another report wake again
|
||||
// otherwise schedule timed wakeup
|
||||
if (mp->fifo_pkts_bytes >= BYTES_PER_BLOCK) {
|
||||
sched_wake_task(&mpu9250_wake);
|
||||
}
|
||||
else if (mp->flags & AX_RUNNING) {
|
||||
// No more fifo data, but actively running. Sleep until next check
|
||||
} else if (mp->flags & AX_RUNNING) {
|
||||
sched_del_timer(&mp->timer);
|
||||
mp->flags &= ~AX_PENDING;
|
||||
mp9250_reschedule_timer(mp);
|
||||
@@ -182,6 +172,9 @@ mp9250_start(struct mpu9250 *mp, uint8_t oid)
|
||||
msg[1] = SET_USER_FIFO_EN; // enable FIFO buffer access
|
||||
i2c_write(mp->i2c->i2c_config, sizeof(msg), msg);
|
||||
|
||||
uint8_t int_reg[] = {AR_INT_STATUS}; // clear FIFO overflow flag
|
||||
i2c_read(mp->i2c->i2c_config, sizeof(int_reg), int_reg, 1, msg);
|
||||
|
||||
msg[0] = AR_FIFO_EN;
|
||||
msg[1] = SET_ENABLE_FIFO; // enable accel output to FIFO
|
||||
i2c_write(mp->i2c->i2c_config, sizeof(msg), msg);
|
||||
@@ -203,18 +196,16 @@ mp9250_stop(struct mpu9250 *mp, uint8_t oid)
|
||||
i2c_write(mp->i2c->i2c_config, sizeof(msg), msg);
|
||||
uint32_t end2_time = timer_read_time();
|
||||
|
||||
// Drain any measurements still in fifo
|
||||
uint16_t fifo_bytes = get_fifo_status(mp);
|
||||
while (fifo_bytes >= BYTES_PER_FIFO_ENTRY) {
|
||||
mp9250_query(mp, oid);
|
||||
fifo_bytes = get_fifo_status(mp);
|
||||
}
|
||||
|
||||
// Report final data
|
||||
if (mp->data_count > 0)
|
||||
mp9250_report(mp, oid);
|
||||
uint16_t bytes_to_read = get_fifo_status(mp);
|
||||
mp9250_status(mp, oid, end1_time, end2_time,
|
||||
fifo_bytes / BYTES_PER_FIFO_ENTRY);
|
||||
bytes_to_read / BYTES_PER_FIFO_ENTRY);
|
||||
|
||||
// Uncomment and rebuilt to check for FIFO overruns when tuning
|
||||
//output("mpu9240 limit_count=%u fifo_max=%u",
|
||||
// mp->limit_count, mp->fifo_max);
|
||||
}
|
||||
|
||||
void
|
||||
@@ -232,8 +223,11 @@ command_query_mpu9250(uint32_t *args)
|
||||
mp->timer.waketime = args[1];
|
||||
mp->rest_ticks = args[2];
|
||||
mp->flags = AX_HAVE_START;
|
||||
mp->sequence = mp->limit_count = 0;
|
||||
mp->sequence = 0;
|
||||
mp->limit_count = 0;
|
||||
mp->data_count = 0;
|
||||
mp->fifo_max = 0;
|
||||
mp->fifo_pkts_bytes = 0;
|
||||
sched_add_timer(&mp->timer);
|
||||
}
|
||||
DECL_COMMAND(command_query_mpu9250,
|
||||
@@ -243,13 +237,24 @@ void
|
||||
command_query_mpu9250_status(uint32_t *args)
|
||||
{
|
||||
struct mpu9250 *mp = oid_lookup(args[0], command_config_mpu9250);
|
||||
|
||||
// Detect if a FIFO overrun occurred
|
||||
uint8_t int_reg[] = {AR_INT_STATUS};
|
||||
uint8_t int_msg;
|
||||
i2c_read(mp->i2c->i2c_config, sizeof(int_reg), int_reg, sizeof(int_msg),
|
||||
&int_msg);
|
||||
if (int_msg & FIFO_OVERFLOW_INT)
|
||||
mp->limit_count++;
|
||||
|
||||
// Read latest FIFO count (with precise timing)
|
||||
uint8_t reg[] = {AR_FIFO_COUNT_H};
|
||||
uint8_t msg[2];
|
||||
uint32_t time1 = timer_read_time();
|
||||
uint8_t regs[] = {AR_FIFO_COUNT_H};
|
||||
i2c_read(mp->i2c->i2c_config, 1, regs, 2, msg);
|
||||
i2c_read(mp->i2c->i2c_config, sizeof(reg), reg, sizeof(msg), msg);
|
||||
uint32_t time2 = timer_read_time();
|
||||
msg[0] = 0x1F & msg[0]; // discard 3 MSB
|
||||
uint16_t fifo_bytes = (((uint16_t)msg[0]) << 8) | msg[1];
|
||||
uint16_t fifo_bytes = ((msg[0] & 0x1f) << 8) | msg[1];
|
||||
|
||||
// Report status
|
||||
mp9250_status(mp, args[0], time1, time2, fifo_bytes / BYTES_PER_FIFO_ENTRY);
|
||||
}
|
||||
DECL_COMMAND(command_query_mpu9250_status, "query_mpu9250_status oid=%c");
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memcpy
|
||||
#include "autoconf.h" // CONFIG_HAVE_GPIO_BITBANGING
|
||||
#include "autoconf.h" // CONFIG_WANT_SOFTWARE_SPI
|
||||
#include "board/gpio.h" // gpio_out_write
|
||||
#include "basecmd.h" // oid_alloc
|
||||
#include "command.h" // DECL_COMMAND
|
||||
@@ -92,7 +92,7 @@ spidev_transfer(struct spidev_s *spi, uint8_t receive_data
|
||||
// Not yet initialized
|
||||
return;
|
||||
|
||||
if (CONFIG_HAVE_GPIO_BITBANGING && flags & SF_SOFTWARE)
|
||||
if (CONFIG_WANT_SOFTWARE_SPI && flags & SF_SOFTWARE)
|
||||
spi_software_prepare(spi->spi_software);
|
||||
else
|
||||
spi_prepare(spi->spi_config);
|
||||
@@ -100,7 +100,7 @@ spidev_transfer(struct spidev_s *spi, uint8_t receive_data
|
||||
if (flags & SF_HAVE_PIN)
|
||||
gpio_out_write(spi->pin, !!(flags & SF_CS_ACTIVE_HIGH));
|
||||
|
||||
if (CONFIG_HAVE_GPIO_BITBANGING && flags & SF_SOFTWARE)
|
||||
if (CONFIG_WANT_SOFTWARE_SPI && flags & SF_SOFTWARE)
|
||||
spi_software_transfer(spi->spi_software, receive_data, data_len, data);
|
||||
else
|
||||
spi_transfer(spi->spi_config, receive_data, data_len, data);
|
||||
|
||||
@@ -7,13 +7,15 @@ config STM32_SELECT
|
||||
default y
|
||||
select HAVE_GPIO
|
||||
select HAVE_GPIO_ADC
|
||||
select HAVE_GPIO_I2C if !(MACH_STM32F031 || MACH_STM32H7)
|
||||
select HAVE_GPIO_I2C if !MACH_STM32F031
|
||||
select HAVE_GPIO_SPI if !MACH_STM32F031
|
||||
select HAVE_GPIO_HARD_PWM if MACH_STM32F1 || MACH_STM32F4 || MACH_STM32H7
|
||||
select HAVE_GPIO_BITBANGING if !MACH_STM32F031
|
||||
select HAVE_GPIO_SDIO if MACH_STM32F4
|
||||
select HAVE_GPIO_HARD_PWM if MACH_STM32F070 || MACH_STM32F072 || MACH_STM32F1 || MACH_STM32F4 || MACH_STM32F7 || MACH_STM32G0 || MACH_STM32H7
|
||||
select HAVE_STRICT_TIMING
|
||||
select HAVE_CHIPID
|
||||
select HAVE_STEPPER_BOTH_EDGE
|
||||
select HAVE_BOOTLOADER_REQUEST
|
||||
select HAVE_LIMITED_CODE_SIZE if MACH_STM32F031 || MACH_STM32F042
|
||||
|
||||
config BOARD_DIRECTORY
|
||||
string
|
||||
@@ -50,6 +52,9 @@ choice
|
||||
config MACH_STM32F446
|
||||
bool "STM32F446"
|
||||
select MACH_STM32F4
|
||||
config MACH_STM32F765
|
||||
bool "STM32F765"
|
||||
select MACH_STM32F7
|
||||
config MACH_STM32F031
|
||||
bool "STM32F031"
|
||||
select MACH_STM32F0
|
||||
@@ -64,15 +69,45 @@ choice
|
||||
bool "STM32F072"
|
||||
select MACH_STM32F0
|
||||
select MACH_STM32F0x2
|
||||
config MACH_STM32G070
|
||||
bool "STM32G070"
|
||||
select MACH_STM32G0
|
||||
select MACH_STM32G07x
|
||||
config MACH_STM32G071
|
||||
bool "STM32G071"
|
||||
select MACH_STM32G0
|
||||
select MACH_STM32G07x
|
||||
config MACH_STM32G0B0
|
||||
bool "STM32G0B0"
|
||||
select MACH_STM32G0
|
||||
select MACH_STM32G0Bx
|
||||
config MACH_STM32G0B1
|
||||
bool "STM32G0B1"
|
||||
select MACH_STM32G0
|
||||
select MACH_STM32G0Bx
|
||||
config MACH_STM32G431
|
||||
bool "STM32G431"
|
||||
select MACH_STM32G4
|
||||
config MACH_STM32H723
|
||||
bool "STM32H723"
|
||||
select MACH_STM32H7
|
||||
config MACH_STM32H743
|
||||
bool "STM32H743"
|
||||
select MACH_STM32H7
|
||||
config MACH_STM32H750
|
||||
bool "STM32H750"
|
||||
select MACH_STM32H7
|
||||
config MACH_STM32L412
|
||||
bool "STM32L412"
|
||||
select MACH_STM32L4
|
||||
config MACH_N32G452
|
||||
bool "Nation N32G452"
|
||||
select MACH_N32G45x
|
||||
select MACH_STM32F1
|
||||
config MACH_N32G455
|
||||
bool "Nation N32G455"
|
||||
select MACH_N32G45x
|
||||
select MACH_STM32F1
|
||||
endchoice
|
||||
|
||||
config MACH_STM32F103x6
|
||||
@@ -87,32 +122,44 @@ config MACH_STM32F2
|
||||
bool
|
||||
config MACH_STM32F4
|
||||
bool
|
||||
config MACH_STM32F7
|
||||
bool
|
||||
config MACH_STM32G0
|
||||
bool
|
||||
config MACH_STM32G07x
|
||||
bool
|
||||
config MACH_STM32G0Bx
|
||||
bool
|
||||
config MACH_STM32G4
|
||||
bool
|
||||
config MACH_STM32H7
|
||||
bool
|
||||
config MACH_STM32F0x2 # F042, F072 series
|
||||
bool
|
||||
config MACH_STM32F4x5 # F405, F407, F429 series
|
||||
bool
|
||||
config MACH_STM32L4
|
||||
bool
|
||||
config MACH_N32G45x
|
||||
bool
|
||||
config HAVE_STM32_USBFS
|
||||
bool
|
||||
default y if MACH_STM32F0x2 || MACH_STM32G0
|
||||
default y if (MACH_STM32F103 || MACH_STM32F070) && !STM32_CLOCK_REF_INTERNAL
|
||||
default y if MACH_STM32F0x2 || MACH_STM32G0Bx || MACH_STM32L4 || MACH_STM32G4
|
||||
default y if (MACH_STM32F1 || MACH_STM32F070) && !STM32_CLOCK_REF_INTERNAL
|
||||
config HAVE_STM32_USBOTG
|
||||
bool
|
||||
default y if MACH_STM32F2 || MACH_STM32F4 || MACH_STM32H7
|
||||
default y if MACH_STM32F2 || MACH_STM32F4 || MACH_STM32F7 || MACH_STM32H7
|
||||
config HAVE_STM32_CANBUS
|
||||
bool
|
||||
default y if MACH_STM32F1 || MACH_STM32F2 || MACH_STM32F4x5 || MACH_STM32F446 || MACH_STM32F0x2
|
||||
config HAVE_STM32_FDCANBUS
|
||||
bool
|
||||
default y if MACH_STM32G0
|
||||
default y if MACH_STM32G0B1 || MACH_STM32H7 || MACH_STM32G4
|
||||
config HAVE_STM32_USBCANBUS
|
||||
bool
|
||||
depends on HAVE_STM32_USBFS || HAVE_STM32_USBOTG
|
||||
depends on HAVE_STM32_CANBUS || HAVE_STM32_FDCANBUS
|
||||
depends on !MACH_STM32F103
|
||||
depends on !MACH_STM32F1
|
||||
default y
|
||||
|
||||
config MCU
|
||||
@@ -128,9 +175,17 @@ config MCU
|
||||
default "stm32f407xx" if MACH_STM32F407
|
||||
default "stm32f429xx" if MACH_STM32F429
|
||||
default "stm32f446xx" if MACH_STM32F446
|
||||
default "stm32f765xx" if MACH_STM32F765
|
||||
default "stm32g070xx" if MACH_STM32G070
|
||||
default "stm32g071xx" if MACH_STM32G071
|
||||
default "stm32g0b0xx" if MACH_STM32G0B0
|
||||
default "stm32g0b1xx" if MACH_STM32G0B1
|
||||
default "stm32g431xx" if MACH_STM32G431
|
||||
default "stm32h723xx" if MACH_STM32H723
|
||||
default "stm32h743xx" if MACH_STM32H743
|
||||
default "stm32h750xx" if MACH_STM32H750
|
||||
default "stm32l412xx" if MACH_STM32L412
|
||||
default "stm32f103xe" if MACH_N32G45x
|
||||
|
||||
config CLOCK_FREQ
|
||||
int
|
||||
@@ -141,24 +196,33 @@ config CLOCK_FREQ
|
||||
default 84000000 if MACH_STM32F401
|
||||
default 168000000 if MACH_STM32F4x5
|
||||
default 180000000 if MACH_STM32F446
|
||||
default 216000000 if MACH_STM32F765
|
||||
default 64000000 if MACH_STM32G0
|
||||
default 150000000 if MACH_STM32G431
|
||||
default 400000000 if MACH_STM32H7 # 400Mhz is max Klipper currently supports
|
||||
default 80000000 if MACH_STM32L412
|
||||
default 64000000 if MACH_N32G45x && STM32_CLOCK_REF_INTERNAL
|
||||
default 128000000 if MACH_N32G45x
|
||||
|
||||
config FLASH_SIZE
|
||||
hex
|
||||
default 0x4000 if MACH_STM32F031
|
||||
default 0x8000 if MACH_STM32F042
|
||||
default 0x20000 if MACH_STM32F070 || MACH_STM32F072
|
||||
default 0x10000 if MACH_STM32F103 # Flash size of stm32f103x8 (64KiB)
|
||||
default 0x40000 if MACH_STM32F2 || MACH_STM32F401
|
||||
default 0x10000 if MACH_STM32F103 || MACH_STM32L412 # Flash size of stm32f103x8 (64KiB)
|
||||
default 0x40000 if MACH_STM32F2 || MACH_STM32F401 || MACH_STM32H723
|
||||
default 0x80000 if MACH_STM32F4x5 || MACH_STM32F446
|
||||
default 0x20000 if MACH_STM32G0B1
|
||||
default 0x20000 if MACH_STM32G0 || MACH_STM32G431
|
||||
default 0x20000 if MACH_STM32H750
|
||||
default 0x200000 if MACH_STM32H743
|
||||
default 0x200000 if MACH_STM32H743 || MACH_STM32F765
|
||||
default 0x20000 if MACH_N32G45x
|
||||
|
||||
config FLASH_BOOT_ADDRESS
|
||||
hex
|
||||
default 0x8000000
|
||||
|
||||
config RAM_START
|
||||
hex
|
||||
default 0x24000000 if MACH_STM32H743
|
||||
default 0x20000000
|
||||
|
||||
config RAM_SIZE
|
||||
@@ -168,12 +232,16 @@ config RAM_SIZE
|
||||
default 0x4000 if MACH_STM32F070 || MACH_STM32F072
|
||||
default 0x2800 if MACH_STM32F103x6
|
||||
default 0x5000 if MACH_STM32F103 && !MACH_STM32F103x6 # Ram size of stm32f103x8
|
||||
default 0x8000 if MACH_STM32G431
|
||||
default 0xa000 if MACH_STM32L412
|
||||
default 0x20000 if MACH_STM32F207
|
||||
default 0x10000 if MACH_STM32F401
|
||||
default 0x20000 if MACH_STM32F4x5 || MACH_STM32F446
|
||||
default 0x24000 if MACH_STM32G0B1
|
||||
default 0x20000 if MACH_STM32H750
|
||||
default 0x80000 if MACH_STM32H743
|
||||
default 0x80000 if MACH_STM32F765
|
||||
default 0x9000 if MACH_STM32G07x
|
||||
default 0x24000 if MACH_STM32G0Bx
|
||||
default 0x20000 if MACH_STM32H7
|
||||
default 0x10000 if MACH_N32G45x
|
||||
|
||||
config STACK_SIZE
|
||||
int
|
||||
@@ -189,6 +257,15 @@ config STM32F103GD_DISABLE_SWD
|
||||
and PA14 pins from being available. Selecting this option
|
||||
disables SWD at startup and thus makes these pins available.
|
||||
|
||||
config STM32_DFU_ROM_ADDRESS
|
||||
hex
|
||||
default 0 if !USB
|
||||
default 0x1fffc400 if MACH_STM32F042
|
||||
default 0x1fffc800 if MACH_STM32F072
|
||||
default 0x1fff0000 if MACH_STM32F4 || MACH_STM32F7 || MACH_STM32G0 || MACH_STM32G4 || MACH_STM32L4
|
||||
default 0x1ff09800 if MACH_STM32H7
|
||||
default 0
|
||||
|
||||
|
||||
######################################################################
|
||||
# Bootloader
|
||||
@@ -197,13 +274,13 @@ config STM32F103GD_DISABLE_SWD
|
||||
choice
|
||||
prompt "Bootloader offset"
|
||||
config STM32_FLASH_START_2000
|
||||
bool "8KiB bootloader" if MACH_STM32F103 || MACH_STM32F070 || MACH_STM32G0 || MACH_STM32F0x2
|
||||
bool "8KiB bootloader" if MACH_STM32F1 || MACH_STM32F070 || MACH_STM32G0 || MACH_STM32F0x2
|
||||
config STM32_FLASH_START_5000
|
||||
bool "20KiB bootloader" if MACH_STM32F103
|
||||
config STM32_FLASH_START_7000
|
||||
bool "28KiB bootloader" if MACH_STM32F103
|
||||
bool "28KiB bootloader" if MACH_STM32F1
|
||||
config STM32_FLASH_START_8000
|
||||
bool "32KiB bootloader" if MACH_STM32F1 || MACH_STM32F2 || MACH_STM32F4
|
||||
bool "32KiB bootloader" if MACH_STM32F1 || MACH_STM32F2 || MACH_STM32F4 || MACH_STM32F7
|
||||
config STM32_FLASH_START_8800
|
||||
bool "34KiB bootloader (Chitu v6 Bootloader)" if MACH_STM32F103
|
||||
config STM32_FLASH_START_20200
|
||||
@@ -211,7 +288,7 @@ choice
|
||||
config STM32_FLASH_START_C000
|
||||
bool "48KiB bootloader (MKS Robin Nano V3)" if MACH_STM32F4x5
|
||||
config STM32_FLASH_START_10000
|
||||
bool "64KiB bootloader" if MACH_STM32F103 || MACH_STM32F446 || MACH_STM32F401
|
||||
bool "64KiB bootloader" if MACH_STM32F103 || MACH_STM32F4
|
||||
|
||||
config STM32_FLASH_START_800
|
||||
bool "2KiB bootloader (HID Bootloader)" if MACH_STM32F103
|
||||
@@ -220,12 +297,12 @@ choice
|
||||
config STM32_FLASH_START_4000
|
||||
bool "16KiB bootloader (HID Bootloader)" if MACH_STM32F207 || MACH_STM32F401 || MACH_STM32F4x5 || MACH_STM32F103 || MACH_STM32F072
|
||||
config STM32_FLASH_START_20000
|
||||
bool "128KiB bootloader (SKR SE BX v2.0)" if MACH_STM32H743
|
||||
bool "128KiB bootloader (SKR SE BX v2.0)" if MACH_STM32H743 || MACH_STM32H723 || MACH_STM32F7
|
||||
|
||||
config STM32_FLASH_START_0000
|
||||
bool "No bootloader"
|
||||
endchoice
|
||||
config FLASH_START
|
||||
config FLASH_APPLICATION_ADDRESS
|
||||
hex
|
||||
default 0x8000800 if STM32_FLASH_START_800
|
||||
default 0x8001000 if STM32_FLASH_START_1000
|
||||
@@ -243,7 +320,7 @@ config FLASH_START
|
||||
|
||||
config ARMCM_RAM_VECTORTABLE
|
||||
bool
|
||||
default y if MACH_STM32F0 && FLASH_START != 0x8000000
|
||||
default y if MACH_STM32F0 && FLASH_APPLICATION_ADDRESS != 0x8000000
|
||||
default n
|
||||
|
||||
|
||||
@@ -259,6 +336,10 @@ choice
|
||||
bool "12 MHz crystal"
|
||||
config STM32_CLOCK_REF_16M
|
||||
bool "16 MHz crystal"
|
||||
config STM32_CLOCK_REF_20M
|
||||
bool "20 MHz crystal"
|
||||
config STM32_CLOCK_REF_24M
|
||||
bool "24 MHz crystal"
|
||||
config STM32_CLOCK_REF_25M
|
||||
bool "25 MHz crystal"
|
||||
config STM32_CLOCK_REF_INTERNAL
|
||||
@@ -267,6 +348,8 @@ endchoice
|
||||
config CLOCK_REF_FREQ
|
||||
int
|
||||
default 25000000 if STM32_CLOCK_REF_25M
|
||||
default 24000000 if STM32_CLOCK_REF_24M
|
||||
default 20000000 if STM32_CLOCK_REF_20M
|
||||
default 16000000 if STM32_CLOCK_REF_16M
|
||||
default 12000000 if STM32_CLOCK_REF_12M
|
||||
default 1 if STM32_CLOCK_REF_INTERNAL
|
||||
@@ -296,7 +379,7 @@ choice
|
||||
select USBSERIAL
|
||||
config STM32_USB_PB14_PB15
|
||||
bool "USB (on PB14/PB15)"
|
||||
depends on MACH_STM32H7
|
||||
depends on MACH_STM32H743 || MACH_STM32H750
|
||||
select USBSERIAL
|
||||
config STM32_SERIAL_USART1
|
||||
bool "Serial (on USART1 PA10/PA9)"
|
||||
@@ -308,7 +391,10 @@ choice
|
||||
bool "Serial (on USART2 PA3/PA2)" if LOW_LEVEL_OPTIONS
|
||||
select SERIAL
|
||||
config STM32_SERIAL_USART2_ALT_PA15_PA14
|
||||
bool "Serial (on USART2 PA15/PA14)" if LOW_LEVEL_OPTIONS && MACH_STM32F0
|
||||
bool "Serial (on USART2 PA15/PA14)" if LOW_LEVEL_OPTIONS && (MACH_STM32F0 || MACH_STM32G4)
|
||||
select SERIAL
|
||||
config STM32_SERIAL_USART2_ALT_PB4_PB3
|
||||
bool "Serial (on USART2 PB4/PB3)" if LOW_LEVEL_OPTIONS && MACH_STM32G4
|
||||
select SERIAL
|
||||
config STM32_SERIAL_USART2_ALT_PD6_PD5
|
||||
bool "Serial (on USART2 PD6/PD5)" if LOW_LEVEL_OPTIONS && !MACH_STM32F0
|
||||
@@ -325,6 +411,10 @@ choice
|
||||
bool "Serial (on UART4 PA0/PA1)"
|
||||
depends on MACH_STM32H7
|
||||
select SERIAL
|
||||
config STM32_SERIAL_USART5
|
||||
bool "Serial (on USART5 PD2/PD3)" if LOW_LEVEL_OPTIONS
|
||||
depends on MACH_STM32G0Bx
|
||||
select SERIAL
|
||||
config STM32_CANBUS_PA11_PA12
|
||||
bool "CAN bus (on PA11/PA12)"
|
||||
depends on HAVE_STM32_CANBUS || HAVE_STM32_FDCANBUS
|
||||
@@ -333,6 +423,10 @@ choice
|
||||
bool "CAN bus (on PA9/PA10)" if LOW_LEVEL_OPTIONS
|
||||
depends on HAVE_STM32_CANBUS && MACH_STM32F042
|
||||
select CANSERIAL
|
||||
config STM32_CANBUS_PA11_PB9
|
||||
bool "CAN bus (on PA11/PB9)"
|
||||
depends on HAVE_STM32_CANBUS || HAVE_STM32_FDCANBUS
|
||||
select CANSERIAL
|
||||
config STM32_MMENU_CANBUS_PB8_PB9
|
||||
bool "CAN bus (on PB8/PB9)" if LOW_LEVEL_OPTIONS
|
||||
depends on HAVE_STM32_CANBUS || HAVE_STM32_FDCANBUS
|
||||
@@ -347,16 +441,24 @@ choice
|
||||
select CANSERIAL
|
||||
config STM32_MMENU_CANBUS_PB12_PB13
|
||||
bool "CAN bus (on PB12/PB13)" if LOW_LEVEL_OPTIONS
|
||||
depends on HAVE_STM32_CANBUS && MACH_STM32F4
|
||||
depends on (HAVE_STM32_CANBUS && MACH_STM32F4) || HAVE_STM32_FDCANBUS
|
||||
select CANSERIAL
|
||||
config STM32_MMENU_CANBUS_PD0_PD1
|
||||
bool "CAN bus (on PD0/PD1)" if LOW_LEVEL_OPTIONS
|
||||
depends on HAVE_STM32_CANBUS
|
||||
depends on HAVE_STM32_CANBUS || HAVE_STM32_FDCANBUS
|
||||
select CANSERIAL
|
||||
config STM32_MMENU_CANBUS_PB0_PB1
|
||||
bool "CAN bus (on PB0/PB1)"
|
||||
depends on HAVE_STM32_FDCANBUS
|
||||
select CANSERIAL
|
||||
config STM32_MMENU_CANBUS_PD12_PD13
|
||||
bool "CAN bus (on PD12/PD13)"
|
||||
depends on HAVE_STM32_FDCANBUS
|
||||
select CANSERIAL
|
||||
config STM32_MMENU_CANBUS_PC2_PC3
|
||||
bool "CAN bus (on PC2/PC3)"
|
||||
depends on HAVE_STM32_FDCANBUS
|
||||
select CANSERIAL
|
||||
config STM32_USBCANBUS_PA11_PA12
|
||||
bool "USB to CAN bus bridge (USB on PA11/PA12)"
|
||||
depends on HAVE_STM32_USBCANBUS
|
||||
@@ -371,16 +473,22 @@ choice
|
||||
depends on HAVE_STM32_CANBUS && MACH_STM32F4
|
||||
config STM32_CMENU_CANBUS_PB5_PB6
|
||||
bool "CAN bus (on PB5/PB6)"
|
||||
depends on HAVE_STM32_CANBUS && MACH_STM32F4
|
||||
depends on (HAVE_STM32_CANBUS && MACH_STM32F4) || (HAVE_STM32_FDCANBUS && MACH_STM32G0B1)
|
||||
config STM32_CMENU_CANBUS_PB12_PB13
|
||||
bool "CAN bus (on PB12/PB13)"
|
||||
depends on HAVE_STM32_CANBUS && MACH_STM32F4
|
||||
depends on (HAVE_STM32_CANBUS && MACH_STM32F4) || HAVE_STM32_FDCANBUS
|
||||
config STM32_CMENU_CANBUS_PD0_PD1
|
||||
bool "CAN bus (on PD0/PD1)"
|
||||
depends on HAVE_STM32_CANBUS
|
||||
depends on HAVE_STM32_CANBUS || HAVE_STM32_FDCANBUS
|
||||
config STM32_CMENU_CANBUS_PB0_PB1
|
||||
bool "CAN bus (on PB0/PB1)"
|
||||
depends on HAVE_STM32_FDCANBUS
|
||||
config STM32_CMENU_CANBUS_PD12_PD13
|
||||
bool "CAN bus (on PD12/PD13)"
|
||||
depends on HAVE_STM32_FDCANBUS
|
||||
config STM32_CMENU_CANBUS_PC2_PC3
|
||||
bool "CAN bus (on PC2/PC3)"
|
||||
depends on HAVE_STM32_FDCANBUS
|
||||
endchoice
|
||||
|
||||
|
||||
@@ -402,5 +510,11 @@ config STM32_CANBUS_PD0_PD1
|
||||
config STM32_CANBUS_PB0_PB1
|
||||
bool
|
||||
default y if STM32_MMENU_CANBUS_PB0_PB1 || STM32_CMENU_CANBUS_PB0_PB1
|
||||
config STM32_CANBUS_PD12_PD13
|
||||
bool
|
||||
default y if STM32_MMENU_CANBUS_PD12_PD13 || STM32_CMENU_CANBUS_PD12_PD13
|
||||
config STM32_CANBUS_PC2_PC3
|
||||
bool
|
||||
default y if STM32_MMENU_CANBUS_PC2_PC3 || STM32_CMENU_CANBUS_PC2_PC3
|
||||
|
||||
endif
|
||||
|
||||
@@ -6,20 +6,29 @@ CROSS_PREFIX=arm-none-eabi-
|
||||
dirs-y += src/stm32 src/generic lib/fast-hash
|
||||
dirs-$(CONFIG_MACH_STM32F0) += lib/stm32f0
|
||||
dirs-$(CONFIG_MACH_STM32F1) += lib/stm32f1
|
||||
dirs-$(CONFIG_MACH_N32G45x) += lib/n32g45x
|
||||
dirs-$(CONFIG_MACH_STM32F2) += lib/stm32f2
|
||||
dirs-$(CONFIG_MACH_STM32F4) += lib/stm32f4
|
||||
dirs-$(CONFIG_MACH_STM32F7) += lib/stm32f7
|
||||
dirs-$(CONFIG_MACH_STM32G0) += lib/stm32g0
|
||||
dirs-$(CONFIG_MACH_STM32G4) += lib/stm32g4
|
||||
dirs-$(CONFIG_MACH_STM32H7) += lib/stm32h7
|
||||
dirs-$(CONFIG_MACH_STM32L4) += lib/stm32l4
|
||||
|
||||
MCU := $(shell echo $(CONFIG_MCU))
|
||||
MCU_UPPER := $(shell echo $(CONFIG_MCU) | tr a-z A-Z | tr X x)
|
||||
|
||||
CFLAGS-$(CONFIG_MACH_STM32F0) += -mcpu=cortex-m0 -Ilib/stm32f0/include
|
||||
CFLAGS-$(CONFIG_MACH_STM32F1) += -mcpu=cortex-m3 -Ilib/stm32f1/include
|
||||
CFLAGS-$(CONFIG_MACH_STM32F103) += -mcpu=cortex-m3
|
||||
CFLAGS-$(CONFIG_MACH_N32G45x) += -mcpu=cortex-m4 -Ilib/n32g45x/include
|
||||
CFLAGS-$(CONFIG_MACH_STM32F1) += -Ilib/stm32f1/include
|
||||
CFLAGS-$(CONFIG_MACH_STM32F2) += -mcpu=cortex-m3 -Ilib/stm32f2/include
|
||||
CFLAGS-$(CONFIG_MACH_STM32F4) += -mcpu=cortex-m4 -Ilib/stm32f4/include
|
||||
CFLAGS-$(CONFIG_MACH_STM32F7) += -mcpu=cortex-m7 -Ilib/stm32f7/include
|
||||
CFLAGS-$(CONFIG_MACH_STM32G0) += -mcpu=cortex-m0plus -Ilib/stm32g0/include
|
||||
CFLAGS-$(CONFIG_MACH_STM32G4) += -mcpu=cortex-m4 -Ilib/stm32g4/include
|
||||
CFLAGS-$(CONFIG_MACH_STM32H7) += -mcpu=cortex-m7 -Ilib/stm32h7/include
|
||||
CFLAGS-$(CONFIG_MACH_STM32L4) += -mcpu=cortex-m4 -Ilib/stm32l4/include
|
||||
CFLAGS += $(CFLAGS-y) -D$(MCU_UPPER) -mthumb -Ilib/cmsis-core -Ilib/fast-hash
|
||||
|
||||
CFLAGS_klipper.elf += --specs=nano.specs --specs=nosys.specs
|
||||
@@ -27,37 +36,55 @@ CFLAGS_klipper.elf += -T $(OUT)src/generic/armcm_link.ld
|
||||
$(OUT)klipper.elf: $(OUT)src/generic/armcm_link.ld
|
||||
|
||||
# Add source files
|
||||
src-y += stm32/watchdog.c stm32/gpio.c stm32/clockline.c generic/crc16_ccitt.c
|
||||
src-y += stm32/watchdog.c stm32/gpio.c stm32/clockline.c stm32/dfu_reboot.c
|
||||
src-y += generic/crc16_ccitt.c
|
||||
src-y += generic/armcm_boot.c generic/armcm_irq.c generic/armcm_reset.c
|
||||
src-$(CONFIG_MACH_STM32F0) += ../lib/stm32f0/system_stm32f0xx.c
|
||||
src-$(CONFIG_MACH_STM32F0) += generic/timer_irq.c stm32/stm32f0_timer.c
|
||||
src-$(CONFIG_MACH_STM32F0) += stm32/stm32f0.c stm32/gpioperiph.c
|
||||
src-$(CONFIG_MACH_STM32F0) += stm32/stm32f0_adc.c stm32/stm32f0_i2c.c
|
||||
src-$(CONFIG_MACH_STM32F1) += ../lib/stm32f1/system_stm32f1xx.c
|
||||
src-$(CONFIG_MACH_STM32F1) += stm32/stm32f1.c generic/armcm_timer.c
|
||||
src-$(CONFIG_MACH_STM32F1) += stm32/adc.c stm32/i2c.c
|
||||
src-$(CONFIG_MACH_STM32F103) += ../lib/stm32f1/system_stm32f1xx.c
|
||||
src-$(CONFIG_MACH_STM32F103) += stm32/adc.c
|
||||
src-$(CONFIG_MACH_N32G45x) += ../lib/stm32f1/system_stm32f1xx.c
|
||||
src-$(CONFIG_MACH_N32G45x) += ../lib/n32g45x/n32g45x_adc.c stm32/n32g45x_adc.c
|
||||
src-$(CONFIG_MACH_STM32F1) += stm32/stm32f1.c generic/armcm_timer.c stm32/i2c.c
|
||||
src-$(CONFIG_MACH_STM32F2) += ../lib/stm32f2/system_stm32f2xx.c
|
||||
src-$(CONFIG_MACH_STM32F2) += stm32/stm32f4.c generic/armcm_timer.c
|
||||
src-$(CONFIG_MACH_STM32F2) += stm32/gpioperiph.c stm32/adc.c stm32/i2c.c
|
||||
src-$(CONFIG_MACH_STM32F4) += ../lib/stm32f4/system_stm32f4xx.c
|
||||
src-$(CONFIG_MACH_STM32F4) += stm32/stm32f4.c generic/armcm_timer.c
|
||||
src-$(CONFIG_MACH_STM32F4) += stm32/gpioperiph.c stm32/adc.c stm32/i2c.c
|
||||
src-$(CONFIG_MACH_STM32F7) += ../lib/stm32f7/system_stm32f7xx.c
|
||||
src-$(CONFIG_MACH_STM32F7) += stm32/stm32f7.c generic/armcm_timer.c
|
||||
src-$(CONFIG_MACH_STM32F7) += stm32/gpioperiph.c stm32/adc.c stm32/stm32f0_i2c.c
|
||||
src-$(CONFIG_MACH_STM32G0) += generic/timer_irq.c stm32/stm32f0_timer.c
|
||||
src-$(CONFIG_MACH_STM32G0) += stm32/stm32g0.c stm32/gpioperiph.c
|
||||
src-$(CONFIG_MACH_STM32G0) += stm32/stm32f0_adc.c stm32/stm32f0_i2c.c
|
||||
src-$(CONFIG_MACH_STM32G4) += ../lib/stm32g4/system_stm32g4xx.c
|
||||
src-$(CONFIG_MACH_STM32G4) += stm32/stm32g4.c generic/armcm_timer.c
|
||||
src-$(CONFIG_MACH_STM32G4) += stm32/gpioperiph.c stm32/stm32h7_adc.c
|
||||
src-$(CONFIG_MACH_STM32G4) += stm32/stm32f0_i2c.c
|
||||
src-$(CONFIG_MACH_STM32H7) += ../lib/stm32h7/system_stm32h7xx.c
|
||||
src-$(CONFIG_MACH_STM32H7) += stm32/stm32h7.c generic/armcm_timer.c
|
||||
src-$(CONFIG_MACH_STM32H7) += stm32/gpioperiph.c stm32/stm32h7_adc.c
|
||||
src-$(CONFIG_MACH_STM32H7) += stm32/stm32f0_i2c.c
|
||||
src-$(CONFIG_MACH_STM32L4) += ../lib/stm32l4/system_stm32l4xx.c
|
||||
src-$(CONFIG_MACH_STM32L4) += stm32/stm32l4.c generic/armcm_timer.c
|
||||
src-$(CONFIG_MACH_STM32L4) += stm32/gpioperiph.c
|
||||
src-$(CONFIG_MACH_STM32L4) += stm32/stm32h7_adc.c stm32/stm32f0_i2c.c
|
||||
spi-src-y := stm32/spi.c
|
||||
spi-src-$(CONFIG_MACH_STM32H7) := stm32/stm32h7_spi.c
|
||||
src-$(CONFIG_HAVE_GPIO_SPI) += $(spi-src-y)
|
||||
sdio-src-y := stm32/sdio.c
|
||||
src-$(CONFIG_HAVE_GPIO_SDIO) += $(sdio-src-y)
|
||||
usb-src-$(CONFIG_HAVE_STM32_USBFS) := stm32/usbfs.c
|
||||
usb-src-$(CONFIG_HAVE_STM32_USBOTG) := stm32/usbotg.c
|
||||
src-$(CONFIG_USBSERIAL) += $(usb-src-y) stm32/chipid.c generic/usb_cdc.c
|
||||
serial-src-y := stm32/serial.c
|
||||
serial-src-$(CONFIG_MACH_STM32F0) := stm32/stm32f0_serial.c
|
||||
serial-src-$(CONFIG_MACH_STM32G0) := stm32/stm32f0_serial.c
|
||||
serial-src-$(CONFIG_MACH_STM32H7) := stm32/stm32h7_serial.c
|
||||
serial-src-$(CONFIG_MACH_STM32G4) := stm32/stm32f0_serial.c
|
||||
serial-src-$(CONFIG_MACH_STM32H7) := stm32/stm32f0_serial.c
|
||||
src-$(CONFIG_SERIAL) += $(serial-src-y) generic/serial_irq.c
|
||||
canbus-src-y := generic/canserial.c ../lib/fast-hash/fasthash.c
|
||||
canbus-src-$(CONFIG_HAVE_STM32_CANBUS) += stm32/can.c
|
||||
@@ -81,7 +108,7 @@ lib/hidflash/hid-flash:
|
||||
|
||||
flash: $(OUT)klipper.bin lib/hidflash/hid-flash
|
||||
@echo " Flashing $< to $(FLASH_DEVICE)"
|
||||
$(Q)$(PYTHON) ./scripts/flash_usb.py -t $(CONFIG_MCU) -d "$(FLASH_DEVICE)" -s "$(CONFIG_FLASH_START)" $(if $(NOSUDO),--no-sudo) $(OUT)klipper.bin
|
||||
$(Q)$(PYTHON) ./scripts/flash_usb.py -t $(CONFIG_MCU) -d "$(FLASH_DEVICE)" -s "$(CONFIG_FLASH_APPLICATION_ADDRESS)" $(if $(NOSUDO),--no-sudo) $(OUT)klipper.bin
|
||||
|
||||
serialflash: $(OUT)klipper.bin
|
||||
@echo " Flashing $< to $(FLASH_DEVICE) via stm32flash"
|
||||
|
||||
@@ -49,6 +49,7 @@
|
||||
|
||||
#if CONFIG_MACH_STM32F0
|
||||
#define SOC_CAN CAN
|
||||
#define FILTER_CAN CAN
|
||||
#define CAN_RX0_IRQn CEC_CAN_IRQn
|
||||
#define CAN_RX1_IRQn CEC_CAN_IRQn
|
||||
#define CAN_TX_IRQn CEC_CAN_IRQn
|
||||
@@ -58,6 +59,7 @@
|
||||
|
||||
#if CONFIG_MACH_STM32F1
|
||||
#define SOC_CAN CAN1
|
||||
#define FILTER_CAN CAN1
|
||||
#define CAN_RX0_IRQn CAN1_RX0_IRQn
|
||||
#define CAN_RX1_IRQn CAN1_RX1_IRQn
|
||||
#define CAN_TX_IRQn CAN1_TX_IRQn
|
||||
@@ -66,16 +68,17 @@
|
||||
#endif
|
||||
|
||||
#if CONFIG_MACH_STM32F4
|
||||
#warning CAN on STM32F4 is untested
|
||||
#if (CONFIG_STM32_CANBUS_PA11_PA12 || CONFIG_STM32_CANBUS_PB8_PB9 \
|
||||
|| CONFIG_STM32_CANBUS_PD0_PD1 || CONFIG_STM32_CANBUS_PI9_PH13)
|
||||
#define SOC_CAN CAN1
|
||||
#define FILTER_CAN CAN1
|
||||
#define CAN_RX0_IRQn CAN1_RX0_IRQn
|
||||
#define CAN_RX1_IRQn CAN1_RX1_IRQn
|
||||
#define CAN_TX_IRQn CAN1_TX_IRQn
|
||||
#define CAN_SCE_IRQn CAN1_SCE_IRQn
|
||||
#elif CONFIG_STM32_CANBUS_PB5_PB6 || CONFIG_STM32_CANBUS_PB12_PB13
|
||||
#define SOC_CAN CAN2
|
||||
#define FILTER_CAN CAN1
|
||||
#define CAN_RX0_IRQn CAN2_RX0_IRQn
|
||||
#define CAN_RX1_IRQn CAN2_RX1_IRQn
|
||||
#define CAN_TX_IRQn CAN2_TX_IRQn
|
||||
@@ -93,7 +96,7 @@
|
||||
|
||||
// Transmit a packet
|
||||
int
|
||||
canbus_send(struct canbus_msg *msg)
|
||||
canhw_send(struct canbus_msg *msg)
|
||||
{
|
||||
uint32_t tsr = SOC_CAN->TSR;
|
||||
if (!(tsr & (CAN_TSR_TME0|CAN_TSR_TME1|CAN_TSR_TME2))) {
|
||||
@@ -130,34 +133,39 @@ canbus_send(struct canbus_msg *msg)
|
||||
|
||||
// Setup the receive packet filter
|
||||
void
|
||||
canbus_set_filter(uint32_t id)
|
||||
canhw_set_filter(uint32_t id)
|
||||
{
|
||||
CAN_TypeDef *fcan = FILTER_CAN;
|
||||
/* Select the start slave bank */
|
||||
SOC_CAN->FMR |= CAN_FMR_FINIT;
|
||||
uint32_t fmr = fcan->FMR;
|
||||
if (FILTER_CAN != SOC_CAN)
|
||||
// Using CAN2 with filter on CAN1 - assign CAN2 to first filter
|
||||
fmr &= ~CAN_FMR_CAN2SB;
|
||||
fcan->FMR = fmr | CAN_FMR_FINIT;
|
||||
/* Initialisation mode for the filter */
|
||||
SOC_CAN->FA1R = 0;
|
||||
fcan->FA1R = 0;
|
||||
|
||||
if (CONFIG_CANBUS_FILTER) {
|
||||
uint32_t mask = CAN_TI0R_STID | CAN_TI0R_IDE | CAN_TI0R_RTR;
|
||||
SOC_CAN->sFilterRegister[0].FR1 = CANBUS_ID_ADMIN << CAN_RI0R_STID_Pos;
|
||||
SOC_CAN->sFilterRegister[0].FR2 = mask;
|
||||
SOC_CAN->sFilterRegister[1].FR1 = (id + 1) << CAN_RI0R_STID_Pos;
|
||||
SOC_CAN->sFilterRegister[1].FR2 = mask;
|
||||
SOC_CAN->sFilterRegister[2].FR1 = id << CAN_RI0R_STID_Pos;
|
||||
SOC_CAN->sFilterRegister[2].FR2 = mask;
|
||||
fcan->sFilterRegister[0].FR1 = CANBUS_ID_ADMIN << CAN_RI0R_STID_Pos;
|
||||
fcan->sFilterRegister[0].FR2 = mask;
|
||||
fcan->sFilterRegister[1].FR1 = (id + 1) << CAN_RI0R_STID_Pos;
|
||||
fcan->sFilterRegister[1].FR2 = mask;
|
||||
fcan->sFilterRegister[2].FR1 = id << CAN_RI0R_STID_Pos;
|
||||
fcan->sFilterRegister[2].FR2 = mask;
|
||||
} else {
|
||||
SOC_CAN->sFilterRegister[0].FR1 = 0;
|
||||
SOC_CAN->sFilterRegister[0].FR2 = 0;
|
||||
fcan->sFilterRegister[0].FR1 = 0;
|
||||
fcan->sFilterRegister[0].FR2 = 0;
|
||||
id = 0;
|
||||
}
|
||||
|
||||
/* 32-bit scale for the filter */
|
||||
SOC_CAN->FS1R = (1<<0) | (1<<1) | (1<<2);
|
||||
fcan->FS1R = (1<<0) | (1<<1) | (1<<2);
|
||||
|
||||
/* Filter activation */
|
||||
SOC_CAN->FA1R = (1<<0) | (id ? (1<<1) | (1<<2) : 0);
|
||||
fcan->FA1R = (1<<0) | (id ? (1<<1) | (1<<2) : 0);
|
||||
/* Leave the initialisation mode for the filter */
|
||||
SOC_CAN->FMR &= ~CAN_FMR_FINIT;
|
||||
fcan->FMR = fmr & ~CAN_FMR_FINIT;
|
||||
}
|
||||
|
||||
// This function handles CAN global interrupts
|
||||
@@ -242,7 +250,11 @@ compute_btr(uint32_t pclock, uint32_t bitrate)
|
||||
void
|
||||
can_init(void)
|
||||
{
|
||||
// Enable clock
|
||||
enable_pclock((uint32_t)SOC_CAN);
|
||||
if (FILTER_CAN != SOC_CAN)
|
||||
// Also enable CAN1 clock if using CAN2 with filter on CAN1
|
||||
enable_pclock((uint32_t)FILTER_CAN);
|
||||
|
||||
gpio_peripheral(GPIO_Rx, CAN_FUNCTION, 1);
|
||||
gpio_peripheral(GPIO_Tx, CAN_FUNCTION, 0);
|
||||
@@ -269,7 +281,7 @@ can_init(void)
|
||||
;
|
||||
|
||||
/*##-2- Configure the CAN Filter #######################################*/
|
||||
canbus_set_filter(0);
|
||||
canhw_set_filter(0);
|
||||
|
||||
/*##-3- Configure Interrupts #################################*/
|
||||
armcm_enable_irq(CAN_IRQHandler, CAN_RX0_IRQn, 0);
|
||||
|
||||
57
src/stm32/dfu_reboot.c
Normal file
57
src/stm32/dfu_reboot.c
Normal file
@@ -0,0 +1,57 @@
|
||||
// Reboot into stm32 ROM dfu bootloader
|
||||
//
|
||||
// Copyright (C) 2019-2022 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "internal.h" // NVIC_SystemReset
|
||||
#include "board/irq.h" // irq_disable
|
||||
|
||||
// Many stm32 chips have a USB capable "DFU bootloader" in their ROM.
|
||||
// In order to invoke that bootloader it is necessary to reset the
|
||||
// chip and jump to a chip specific hardware address.
|
||||
//
|
||||
// To reset the chip, the dfu_reboot() code sets a flag in memory (at
|
||||
// an arbitrary position that is unlikely to be overwritten during a
|
||||
// chip reset), and resets the chip. If dfu_reboot_check() sees that
|
||||
// flag on the next boot it will perform a code jump to the ROM
|
||||
// address.
|
||||
|
||||
// Location of ram address to set internal flag
|
||||
#if CONFIG_MACH_STM32H7
|
||||
#define USB_BOOT_FLAG_ADDR (0x24000000 + 0x8000) // Place flag in "AXI SRAM"
|
||||
#else
|
||||
#define USB_BOOT_FLAG_ADDR (CONFIG_RAM_START + CONFIG_RAM_SIZE - 1024)
|
||||
#endif
|
||||
|
||||
// Signature to set in memory to flag that a dfu reboot is requested
|
||||
#define USB_BOOT_FLAG 0x55534220424f4f54 // "USB BOOT"
|
||||
|
||||
// Flag that bootloader is desired and reboot
|
||||
void
|
||||
dfu_reboot(void)
|
||||
{
|
||||
if (!CONFIG_STM32_DFU_ROM_ADDRESS || !CONFIG_HAVE_BOOTLOADER_REQUEST)
|
||||
return;
|
||||
irq_disable();
|
||||
uint64_t *bflag = (void*)USB_BOOT_FLAG_ADDR;
|
||||
*bflag = USB_BOOT_FLAG;
|
||||
#if __CORTEX_M >= 7
|
||||
SCB_CleanDCache_by_Addr((void*)bflag, sizeof(*bflag));
|
||||
#endif
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
// Check if rebooting into system DFU Bootloader
|
||||
void
|
||||
dfu_reboot_check(void)
|
||||
{
|
||||
if (!CONFIG_STM32_DFU_ROM_ADDRESS || !CONFIG_HAVE_BOOTLOADER_REQUEST)
|
||||
return;
|
||||
if (*(uint64_t*)USB_BOOT_FLAG_ADDR != USB_BOOT_FLAG)
|
||||
return;
|
||||
*(uint64_t*)USB_BOOT_FLAG_ADDR = 0;
|
||||
uint32_t *sysbase = (uint32_t*)CONFIG_STM32_DFU_ROM_ADDRESS;
|
||||
asm volatile("mov sp, %0\n bx %1"
|
||||
: : "r"(sysbase[0]), "r"(sysbase[1]));
|
||||
}
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user