mirror of
https://github.com/QIDITECH/klipper.git
synced 2026-01-30 23:48:43 +03:00
klipper update
This commit is contained in:
139
src/Kconfig
Normal file
139
src/Kconfig
Normal file
@@ -0,0 +1,139 @@
|
||||
# Main Kconfig settings
|
||||
|
||||
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.
|
||||
|
||||
choice
|
||||
prompt "Micro-controller Architecture"
|
||||
config MACH_AVR
|
||||
bool "Atmega AVR"
|
||||
config MACH_ATSAM
|
||||
bool "SAM3/SAM4/SAM E70 (Due and Duet)"
|
||||
config MACH_ATSAMD
|
||||
bool "SAMD21/SAMD51"
|
||||
config MACH_LPC176X
|
||||
bool "LPC176x (Smoothieboard)"
|
||||
config MACH_STM32
|
||||
bool "STMicroelectronics STM32"
|
||||
config MACH_RP2040
|
||||
bool "Raspberry Pi RP2040"
|
||||
config MACH_PRU
|
||||
bool "Beaglebone PRU"
|
||||
config MACH_LINUX
|
||||
bool "Linux process"
|
||||
config MACH_SIMU
|
||||
bool "Host simulator"
|
||||
endchoice
|
||||
|
||||
source "src/avr/Kconfig"
|
||||
source "src/atsam/Kconfig"
|
||||
source "src/atsamd/Kconfig"
|
||||
source "src/lpc176x/Kconfig"
|
||||
source "src/stm32/Kconfig"
|
||||
source "src/rp2040/Kconfig"
|
||||
source "src/pru/Kconfig"
|
||||
source "src/linux/Kconfig"
|
||||
source "src/simulator/Kconfig"
|
||||
|
||||
# Generic configuration options for serial ports
|
||||
config SERIAL
|
||||
bool
|
||||
config SERIAL_BAUD
|
||||
depends on SERIAL
|
||||
int "Baud rate for serial port" if LOW_LEVEL_OPTIONS
|
||||
default 250000
|
||||
help
|
||||
Specify the baud rate of the serial port. This should be set
|
||||
to 250000. Read the FAQ before changing this value.
|
||||
|
||||
# Generic configuration options for USB
|
||||
config USBSERIAL
|
||||
bool
|
||||
config USBCANBUS
|
||||
bool
|
||||
config USB_VENDOR_ID
|
||||
default 0x1d50
|
||||
config USB_DEVICE_ID
|
||||
default 0x614e
|
||||
config USB_SERIAL_NUMBER_CHIPID
|
||||
depends on HAVE_CHIPID && (USBSERIAL || USBCANBUS)
|
||||
default y
|
||||
config USB_SERIAL_NUMBER
|
||||
default "12345"
|
||||
|
||||
menu "USB ids"
|
||||
depends on (USBSERIAL || USBCANBUS) && LOW_LEVEL_OPTIONS
|
||||
config USB_VENDOR_ID
|
||||
hex "USB vendor ID" if USBSERIAL
|
||||
config USB_DEVICE_ID
|
||||
hex "USB device ID" if USBSERIAL
|
||||
config USB_SERIAL_NUMBER_CHIPID
|
||||
bool "USB serial number from CHIPID" if HAVE_CHIPID
|
||||
config USB_SERIAL_NUMBER
|
||||
string "USB serial number" if !USB_SERIAL_NUMBER_CHIPID
|
||||
endmenu
|
||||
|
||||
# Generic configuration options for CANbus
|
||||
config CANSERIAL
|
||||
bool
|
||||
config CANBUS
|
||||
bool
|
||||
default y if CANSERIAL || USBCANBUS
|
||||
config CANBUS_FREQUENCY
|
||||
int "CAN bus speed" if LOW_LEVEL_OPTIONS && CANBUS
|
||||
default 500000
|
||||
config CANBUS_FILTER
|
||||
bool
|
||||
default y if CANSERIAL
|
||||
|
||||
# Support setting gpio state at startup
|
||||
config INITIAL_PINS
|
||||
string "GPIO pins to set at micro-controller startup"
|
||||
depends on LOW_LEVEL_OPTIONS
|
||||
help
|
||||
One may specify a comma separated list of gpio pins to set
|
||||
during the micro-controller startup sequence. By default the
|
||||
pins will be set to output high - preface a pin with a '!'
|
||||
character to set that pin to output low.
|
||||
|
||||
# The HAVE_x options allow boards to disable support for some commands
|
||||
# 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_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 INLINE_STEPPER_HACK
|
||||
# Enables gcc to inline stepper_event() into the main timer irq handler
|
||||
bool
|
||||
depends on HAVE_GPIO
|
||||
default y
|
||||
13
src/Makefile
Normal file
13
src/Makefile
Normal file
@@ -0,0 +1,13 @@
|
||||
# Main code build rules
|
||||
|
||||
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_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
|
||||
136
src/adccmds.c
Normal file
136
src/adccmds.c
Normal file
@@ -0,0 +1,136 @@
|
||||
// Commands for controlling GPIO analog-to-digital input pins
|
||||
//
|
||||
// Copyright (C) 2016 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "basecmd.h" // oid_alloc
|
||||
#include "board/gpio.h" // struct gpio_adc
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "command.h" // DECL_COMMAND
|
||||
#include "sched.h" // DECL_TASK
|
||||
|
||||
struct analog_in {
|
||||
struct timer timer;
|
||||
uint32_t rest_time, sample_time, next_begin_time;
|
||||
uint16_t value, min_value, max_value;
|
||||
struct gpio_adc pin;
|
||||
uint8_t invalid_count, range_check_count;
|
||||
uint8_t state, sample_count;
|
||||
};
|
||||
|
||||
static struct task_wake analog_wake;
|
||||
|
||||
static uint_fast8_t
|
||||
analog_in_event(struct timer *timer)
|
||||
{
|
||||
struct analog_in *a = container_of(timer, struct analog_in, timer);
|
||||
uint32_t sample_delay = gpio_adc_sample(a->pin);
|
||||
if (sample_delay) {
|
||||
a->timer.waketime += sample_delay;
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
uint16_t value = gpio_adc_read(a->pin);
|
||||
uint8_t state = a->state;
|
||||
if (state >= a->sample_count) {
|
||||
state = 0;
|
||||
} else {
|
||||
value += a->value;
|
||||
}
|
||||
a->value = value;
|
||||
a->state = state+1;
|
||||
if (a->state < a->sample_count) {
|
||||
a->timer.waketime += a->sample_time;
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
if (likely(a->value >= a->min_value && a->value <= a->max_value)) {
|
||||
a->invalid_count = 0;
|
||||
} else {
|
||||
a->invalid_count++;
|
||||
if (a->invalid_count >= a->range_check_count) {
|
||||
try_shutdown("ADC out of range");
|
||||
a->invalid_count = 0;
|
||||
}
|
||||
}
|
||||
sched_wake_task(&analog_wake);
|
||||
a->next_begin_time += a->rest_time;
|
||||
a->timer.waketime = a->next_begin_time;
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
|
||||
void
|
||||
command_config_analog_in(uint32_t *args)
|
||||
{
|
||||
struct gpio_adc pin = gpio_adc_setup(args[1]);
|
||||
struct analog_in *a = oid_alloc(
|
||||
args[0], command_config_analog_in, sizeof(*a));
|
||||
a->timer.func = analog_in_event;
|
||||
a->pin = pin;
|
||||
a->state = 1;
|
||||
}
|
||||
DECL_COMMAND(command_config_analog_in, "config_analog_in oid=%c pin=%u");
|
||||
|
||||
void
|
||||
command_query_analog_in(uint32_t *args)
|
||||
{
|
||||
struct analog_in *a = oid_lookup(args[0], command_config_analog_in);
|
||||
sched_del_timer(&a->timer);
|
||||
gpio_adc_cancel_sample(a->pin);
|
||||
a->next_begin_time = args[1];
|
||||
a->timer.waketime = a->next_begin_time;
|
||||
a->sample_time = args[2];
|
||||
a->sample_count = args[3];
|
||||
a->state = a->sample_count + 1;
|
||||
a->rest_time = args[4];
|
||||
a->min_value = args[5];
|
||||
a->max_value = args[6];
|
||||
a->range_check_count = args[7];
|
||||
if (! a->sample_count)
|
||||
return;
|
||||
sched_add_timer(&a->timer);
|
||||
}
|
||||
DECL_COMMAND(command_query_analog_in,
|
||||
"query_analog_in oid=%c clock=%u sample_ticks=%u sample_count=%c"
|
||||
" rest_ticks=%u min_value=%hu max_value=%hu range_check_count=%c");
|
||||
|
||||
void
|
||||
analog_in_task(void)
|
||||
{
|
||||
if (!sched_check_wake(&analog_wake))
|
||||
return;
|
||||
uint8_t oid;
|
||||
struct analog_in *a;
|
||||
foreach_oid(oid, a, command_config_analog_in) {
|
||||
if (a->state != a->sample_count)
|
||||
continue;
|
||||
irq_disable();
|
||||
if (a->state != a->sample_count) {
|
||||
irq_enable();
|
||||
continue;
|
||||
}
|
||||
uint16_t value = a->value;
|
||||
uint32_t next_begin_time = a->next_begin_time;
|
||||
a->state++;
|
||||
irq_enable();
|
||||
sendf("analog_in_state oid=%c next_clock=%u value=%hu"
|
||||
, oid, next_begin_time, value);
|
||||
}
|
||||
}
|
||||
DECL_TASK(analog_in_task);
|
||||
|
||||
void
|
||||
analog_in_shutdown(void)
|
||||
{
|
||||
uint8_t i;
|
||||
struct analog_in *a;
|
||||
foreach_oid(i, a, command_config_analog_in) {
|
||||
gpio_adc_cancel_sample(a->pin);
|
||||
if (a->sample_count) {
|
||||
a->state = a->sample_count + 1;
|
||||
a->next_begin_time += a->rest_time;
|
||||
a->timer.waketime = a->next_begin_time;
|
||||
sched_add_timer(&a->timer);
|
||||
}
|
||||
}
|
||||
}
|
||||
DECL_SHUTDOWN(analog_in_shutdown);
|
||||
102
src/atsam/Kconfig
Normal file
102
src/atsam/Kconfig
Normal file
@@ -0,0 +1,102 @@
|
||||
# Kconfig settings for Atmel SAM processors
|
||||
|
||||
if MACH_ATSAM
|
||||
|
||||
config ATSAM_SELECT
|
||||
bool
|
||||
default y
|
||||
select HAVE_GPIO
|
||||
select HAVE_GPIO_ADC
|
||||
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
|
||||
|
||||
config BOARD_DIRECTORY
|
||||
string
|
||||
default "atsam"
|
||||
|
||||
choice
|
||||
prompt "Processor model"
|
||||
config MACH_SAM3X8E
|
||||
bool "SAM3x8e (Arduino Due)"
|
||||
select MACH_SAM3X
|
||||
config MACH_SAM3X8C
|
||||
bool "SAM3x8c (Printrboard G2)"
|
||||
select MACH_SAM3X
|
||||
config MACH_SAM4S8C
|
||||
bool "SAM4s8c (Duet Maestro)"
|
||||
select MACH_SAM4S
|
||||
config MACH_SAM4E8E
|
||||
bool "SAM4e8e (Duet Wifi/Eth)"
|
||||
select MACH_SAM4E
|
||||
config MACH_SAME70Q20B
|
||||
bool "SAME70Q20B (Duet 3 6HC)"
|
||||
select MACH_SAME70
|
||||
endchoice
|
||||
|
||||
config MACH_SAM3X
|
||||
bool
|
||||
config MACH_SAM4
|
||||
bool
|
||||
config MACH_SAM4S
|
||||
bool
|
||||
select MACH_SAM4
|
||||
config MACH_SAM4E
|
||||
bool
|
||||
select MACH_SAM4
|
||||
config MACH_SAME70
|
||||
bool
|
||||
|
||||
config MCU
|
||||
string
|
||||
default "sam3x8e" if MACH_SAM3X8E
|
||||
default "sam3x8c" if MACH_SAM3X8C
|
||||
default "sam4s8c" if MACH_SAM4S8C
|
||||
default "sam4e8e" if MACH_SAM4E8E
|
||||
default "same70q20b" if MACH_SAME70Q20B
|
||||
|
||||
config CLOCK_FREQ
|
||||
int
|
||||
default 84000000 if MACH_SAM3X
|
||||
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 RAM_START
|
||||
hex
|
||||
default 0x20400000 if MACH_SAME70
|
||||
default 0x20000000
|
||||
|
||||
config RAM_SIZE
|
||||
hex
|
||||
default 0x18000 if MACH_SAM3X
|
||||
default 0x20000 if MACH_SAM4
|
||||
default 0x40000 if MACH_SAME70
|
||||
|
||||
config STACK_SIZE
|
||||
int
|
||||
default 512
|
||||
|
||||
choice
|
||||
prompt "Communication interface"
|
||||
config ATSAM_USB
|
||||
bool "USB"
|
||||
select USBSERIAL
|
||||
config ATSAM_SERIAL
|
||||
bool "Serial"
|
||||
select SERIAL
|
||||
endchoice
|
||||
|
||||
endif
|
||||
59
src/atsam/Makefile
Normal file
59
src/atsam/Makefile
Normal file
@@ -0,0 +1,59 @@
|
||||
# Additional ATSAM build rules
|
||||
|
||||
# Setup the toolchain
|
||||
CROSS_PREFIX=arm-none-eabi-
|
||||
|
||||
dirs-y += src/atsam src/generic
|
||||
dirs-$(CONFIG_MACH_SAM3X) += lib/sam3x/gcc
|
||||
dirs-$(CONFIG_MACH_SAM4S) += lib/sam4s/gcc
|
||||
dirs-$(CONFIG_MACH_SAM4E) += lib/sam4e/gcc
|
||||
dirs-$(CONFIG_MACH_SAME70) += lib/same70b/gcc
|
||||
|
||||
MCU := $(shell echo $(CONFIG_MCU) | tr a-z A-Z)
|
||||
|
||||
CFLAGS-$(CONFIG_MACH_SAM3X) += -mcpu=cortex-m3 -falign-loops=16
|
||||
CFLAGS-$(CONFIG_MACH_SAM4) += -mcpu=cortex-m4
|
||||
CFLAGS-$(CONFIG_MACH_SAME70) += -mcpu=cortex-m7
|
||||
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_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 += atsam/main.c atsam/gpio.c atsam/i2c.c atsam/spi.c
|
||||
src-y += generic/armcm_boot.c generic/armcm_irq.c generic/armcm_timer.c
|
||||
src-y += generic/crc16_ccitt.c
|
||||
usb-src-$(CONFIG_MACH_SAM3X) := atsam/sam3_usb.c
|
||||
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
|
||||
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
|
||||
src-$(CONFIG_MACH_SAM4E) += atsam/sam4e_afec.c atsam/sam4_cache.c
|
||||
src-$(CONFIG_MACH_SAM3X) += ../lib/sam3x/gcc/system_sam3xa.c
|
||||
src-$(CONFIG_MACH_SAM4S) += atsam/sam4s_sysinit.c
|
||||
src-$(CONFIG_MACH_SAM4E) += ../lib/sam4e/gcc/system_sam4e.c
|
||||
src-$(CONFIG_MACH_SAME70) += atsam/same70_sysinit.c atsam/sam4e_afec.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 $< $@
|
||||
|
||||
# Flash rules
|
||||
lib/bossac/bin/bossac:
|
||||
@echo " Building bossac"
|
||||
$(Q)make -C lib/bossac bin/bossac
|
||||
|
||||
flash: $(OUT)klipper.bin lib/bossac/bin/bossac
|
||||
@echo " Flashing $< to $(FLASH_DEVICE)"
|
||||
$(Q)$(PYTHON) ./scripts/flash_usb.py -t $(CONFIG_MCU) -d "$(FLASH_DEVICE)" $(OUT)klipper.bin
|
||||
107
src/atsam/adc.c
Normal file
107
src/atsam/adc.c
Normal file
@@ -0,0 +1,107 @@
|
||||
// Analog to digital support
|
||||
//
|
||||
// Copyright (C) 2016-2020 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_CLOCK_FREQ
|
||||
#include "board/irq.h" // irq_save
|
||||
#include "command.h" // shutdown
|
||||
#include "compiler.h" // ARRAY_SIZE
|
||||
#include "gpio.h" // gpio_adc_setup
|
||||
#include "internal.h" // GPIO
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
#define ADC_TEMPERATURE_PIN 0xfe
|
||||
DECL_ENUMERATION("pin", "ADC_TEMPERATURE", ADC_TEMPERATURE_PIN);
|
||||
|
||||
static const uint8_t adc_pins[] = {
|
||||
#if CONFIG_MACH_SAM3X
|
||||
GPIO('A', 2), GPIO('A', 3), GPIO('A', 4), GPIO('A', 6),
|
||||
GPIO('A', 22), GPIO('A', 23), GPIO('A', 24), GPIO('A', 16),
|
||||
GPIO('B', 12), GPIO('B', 13), GPIO('B', 17), GPIO('B', 18),
|
||||
GPIO('B', 19), GPIO('B', 20), GPIO('B', 21), ADC_TEMPERATURE_PIN
|
||||
#elif CONFIG_MACH_SAM4S
|
||||
GPIO('A', 17), GPIO('A', 18), GPIO('A', 19), GPIO('A', 20),
|
||||
GPIO('B', 0), GPIO('B', 1), GPIO('B', 2), GPIO('B', 3),
|
||||
GPIO('A', 21), GPIO('A', 22), GPIO('C', 13), GPIO('C', 15),
|
||||
GPIO('C', 12), GPIO('C', 29), GPIO('C', 30), ADC_TEMPERATURE_PIN
|
||||
#endif
|
||||
};
|
||||
|
||||
#define ADC_FREQ_MAX 20000000
|
||||
DECL_CONSTANT("ADC_MAX", 4095);
|
||||
|
||||
struct gpio_adc
|
||||
gpio_adc_setup(uint8_t pin)
|
||||
{
|
||||
// Find pin in adc_pins table
|
||||
int chan;
|
||||
for (chan=0; ; chan++) {
|
||||
if (chan >= ARRAY_SIZE(adc_pins))
|
||||
shutdown("Not a valid ADC pin");
|
||||
if (adc_pins[chan] == pin)
|
||||
break;
|
||||
}
|
||||
|
||||
if (!is_enabled_pclock(ID_ADC)) {
|
||||
// Setup ADC
|
||||
enable_pclock(ID_ADC);
|
||||
uint32_t prescal = get_pclock_frequency(ID_ADC) / (2*ADC_FREQ_MAX) - 1;
|
||||
ADC->ADC_MR = (ADC_MR_PRESCAL(prescal)
|
||||
| ADC_MR_STARTUP_SUT768
|
||||
| ADC_MR_TRANSFER(1));
|
||||
}
|
||||
|
||||
if (pin == ADC_TEMPERATURE_PIN) {
|
||||
// Enable temperature sensor
|
||||
ADC->ADC_ACR |= ADC_ACR_TSON;
|
||||
} else {
|
||||
// Place pin in input floating mode
|
||||
gpio_in_setup(pin, 0);
|
||||
}
|
||||
return (struct gpio_adc){ .chan = 1 << 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)
|
||||
{
|
||||
uint32_t chsr = ADC->ADC_CHSR & 0xffff;
|
||||
if (!chsr) {
|
||||
// Start sample
|
||||
ADC->ADC_CHER = g.chan;
|
||||
ADC->ADC_CR = ADC_CR_START;
|
||||
goto need_delay;
|
||||
}
|
||||
if (chsr != g.chan)
|
||||
// Sampling in progress on another channel
|
||||
goto need_delay;
|
||||
if (!(ADC->ADC_ISR & ADC_ISR_DRDY))
|
||||
// Conversion still in progress
|
||||
goto need_delay;
|
||||
// Conversion ready
|
||||
return 0;
|
||||
need_delay:
|
||||
return ADC_FREQ_MAX * 1000ULL / CONFIG_CLOCK_FREQ;
|
||||
}
|
||||
|
||||
// Read a value; use only after gpio_adc_sample() returns zero
|
||||
uint16_t
|
||||
gpio_adc_read(struct gpio_adc g)
|
||||
{
|
||||
ADC->ADC_CHDR = g.chan;
|
||||
return ADC->ADC_LCDR;
|
||||
}
|
||||
|
||||
// Cancel a sample that may have been started with gpio_adc_sample()
|
||||
void
|
||||
gpio_adc_cancel_sample(struct gpio_adc g)
|
||||
{
|
||||
irqstatus_t flag = irq_save();
|
||||
if ((ADC->ADC_CHSR & 0xffff) == g.chan)
|
||||
gpio_adc_read(g);
|
||||
irq_restore(flag);
|
||||
}
|
||||
74
src/atsam/chipid.c
Normal file
74
src/atsam/chipid.c
Normal file
@@ -0,0 +1,74 @@
|
||||
// Support for extracting the hardware chip id on sam3/sam4
|
||||
//
|
||||
// Copyright (C) 2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "generic/irq.h" // irq_disable
|
||||
#include "generic/usb_cdc.h" // usb_fill_serial
|
||||
#include "generic/usbstd.h" // usb_string_descriptor
|
||||
#include "internal.h" // EFC0
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
#define CHIP_UID_LEN 16
|
||||
|
||||
static struct {
|
||||
struct usb_string_descriptor desc;
|
||||
uint16_t data[CHIP_UID_LEN * 2];
|
||||
} cdc_chipid;
|
||||
|
||||
struct usb_string_descriptor *
|
||||
usbserial_get_serialid(void)
|
||||
{
|
||||
return &cdc_chipid.desc;
|
||||
}
|
||||
|
||||
// Compatibility definitions for sam4e8e
|
||||
#ifndef EFC0
|
||||
#define EFC0 EFC
|
||||
#define IFLASH0_ADDR IFLASH_ADDR
|
||||
#endif
|
||||
|
||||
void noinline __section(".ramfunc.read_chip_id")
|
||||
read_chip_id(uint32_t *id)
|
||||
{
|
||||
// Workaround sam3 errata
|
||||
uint32_t fmr = EFC0->EEFC_FMR;
|
||||
EFC0->EEFC_FMR = fmr | EEFC_FMR_SCOD;
|
||||
|
||||
// Send the STUI command
|
||||
while (!(EFC0->EEFC_FSR & EEFC_FSR_FRDY))
|
||||
;
|
||||
EFC0->EEFC_FCR = EEFC_FCR_FKEY_PASSWD | EEFC_FCR_FCMD_STUI;
|
||||
while (EFC0->EEFC_FSR & EEFC_FSR_FRDY)
|
||||
;
|
||||
|
||||
// Copy the id
|
||||
id[0] = *(uint32_t*)(IFLASH0_ADDR + 0x00);
|
||||
id[1] = *(uint32_t*)(IFLASH0_ADDR + 0x04);
|
||||
id[2] = *(uint32_t*)(IFLASH0_ADDR + 0x08);
|
||||
id[3] = *(uint32_t*)(IFLASH0_ADDR + 0x0c);
|
||||
|
||||
// Send the SPUI command
|
||||
EFC0->EEFC_FCR = EEFC_FCR_FKEY_PASSWD | EEFC_FCR_FCMD_SPUI;
|
||||
while (!(EFC0->EEFC_FSR & EEFC_FSR_FRDY))
|
||||
;
|
||||
|
||||
// Restore fmr
|
||||
EFC0->EEFC_FMR = fmr;
|
||||
}
|
||||
|
||||
void
|
||||
chipid_init(void)
|
||||
{
|
||||
if (!CONFIG_USB_SERIAL_NUMBER_CHIPID)
|
||||
return;
|
||||
|
||||
uint32_t id[4];
|
||||
irq_disable();
|
||||
read_chip_id(id);
|
||||
irq_enable();
|
||||
|
||||
usb_fill_serial(&cdc_chipid.desc, ARRAY_SIZE(cdc_chipid.data), id);
|
||||
}
|
||||
DECL_INIT(chipid_init);
|
||||
188
src/atsam/gpio.c
Normal file
188
src/atsam/gpio.c
Normal file
@@ -0,0 +1,188 @@
|
||||
// GPIO functions on sam3/sam4
|
||||
//
|
||||
// Copyright (C) 2016-2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "board/irq.h" // irq_save
|
||||
#include "command.h" // shutdown
|
||||
#include "compiler.h" // ARRAY_SIZE
|
||||
#include "gpio.h" // gpio_out_setup
|
||||
#include "internal.h" // gpio_peripheral
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
struct gpio_info {
|
||||
void *dev;
|
||||
uint8_t dev_id;
|
||||
};
|
||||
|
||||
DECL_ENUMERATION_RANGE("pin", "PA0", GPIO('A', 0), 32);
|
||||
DECL_ENUMERATION_RANGE("pin", "PB0", GPIO('B', 0), 32);
|
||||
#ifdef PIOC
|
||||
DECL_ENUMERATION_RANGE("pin", "PC0", GPIO('C', 0), 32);
|
||||
#endif
|
||||
#ifdef PIOD
|
||||
DECL_ENUMERATION_RANGE("pin", "PD0", GPIO('D', 0), 32);
|
||||
#endif
|
||||
#ifdef PIOE
|
||||
DECL_ENUMERATION_RANGE("pin", "PE0", GPIO('E', 0), 32);
|
||||
#endif
|
||||
|
||||
static const struct gpio_info digital_regs[] = {
|
||||
{ PIOA, ID_PIOA },
|
||||
{ PIOB, ID_PIOB },
|
||||
#ifdef PIOC
|
||||
{ PIOC, ID_PIOC },
|
||||
#endif
|
||||
#ifdef PIOD
|
||||
{ PIOD, ID_PIOD },
|
||||
#endif
|
||||
#ifdef PIOE
|
||||
{ PIOE, ID_PIOE },
|
||||
#endif
|
||||
};
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Pin multiplexing
|
||||
****************************************************************/
|
||||
|
||||
static void
|
||||
set_pull_up(Pio *regs, uint32_t bit, int32_t pull_up)
|
||||
{
|
||||
#if CONFIG_MACH_SAM3X
|
||||
if (pull_up > 0)
|
||||
regs->PIO_PUER = bit;
|
||||
else
|
||||
regs->PIO_PUDR = bit;
|
||||
#else
|
||||
if (pull_up > 0) {
|
||||
regs->PIO_PPDDR = bit;
|
||||
regs->PIO_PUER = bit;
|
||||
} else if (pull_up < 0) {
|
||||
regs->PIO_PUDR = bit;
|
||||
regs->PIO_PPDER = bit;
|
||||
} else {
|
||||
regs->PIO_PUDR = bit;
|
||||
regs->PIO_PPDDR = bit;
|
||||
}
|
||||
#endif
|
||||
#if CONFIG_MACH_SAM4S
|
||||
// Check if this pin is a "system IO pin" and disable if so
|
||||
if (regs == PIOB && (bit & 0x1cf0))
|
||||
MATRIX->CCFG_SYSIO |= bit;
|
||||
#elif CONFIG_MACH_SAME70
|
||||
if (regs == PIOB && (bit & 0x10f0))
|
||||
MATRIX->CCFG_SYSIO |= bit;
|
||||
#endif
|
||||
}
|
||||
|
||||
void
|
||||
gpio_peripheral(uint32_t gpio, char ptype, int32_t pull_up)
|
||||
{
|
||||
uint32_t bank = GPIO2PORT(gpio), bit = GPIO2BIT(gpio), pt = ptype - 'A';
|
||||
Pio *regs = digital_regs[bank].dev;
|
||||
|
||||
#if CONFIG_MACH_SAM3X
|
||||
regs->PIO_ABSR = (regs->PIO_ABSR & ~bit) | (pt & 0x01 ? bit : 0);
|
||||
#else
|
||||
regs->PIO_ABCDSR[0] = (regs->PIO_ABCDSR[0] & ~bit) | (pt & 0x01 ? bit : 0);
|
||||
regs->PIO_ABCDSR[1] = (regs->PIO_ABCDSR[1] & ~bit) | (pt & 0x02 ? bit : 0);
|
||||
#endif
|
||||
set_pull_up(regs, bit, pull_up);
|
||||
regs->PIO_PDR = bit;
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* General Purpose Input Output (GPIO) pins
|
||||
****************************************************************/
|
||||
|
||||
struct gpio_out
|
||||
gpio_out_setup(uint8_t pin, uint8_t val)
|
||||
{
|
||||
if (GPIO2PORT(pin) >= ARRAY_SIZE(digital_regs))
|
||||
goto fail;
|
||||
Pio *regs = digital_regs[GPIO2PORT(pin)].dev;
|
||||
struct gpio_out g = { .regs=regs, .bit=GPIO2BIT(pin) };
|
||||
gpio_out_reset(g, val);
|
||||
return g;
|
||||
fail:
|
||||
shutdown("Not an output pin");
|
||||
}
|
||||
|
||||
void
|
||||
gpio_out_reset(struct gpio_out g, uint8_t val)
|
||||
{
|
||||
Pio *regs = g.regs;
|
||||
irqstatus_t flag = irq_save();
|
||||
if (val)
|
||||
regs->PIO_SODR = g.bit;
|
||||
else
|
||||
regs->PIO_CODR = g.bit;
|
||||
regs->PIO_OER = g.bit;
|
||||
regs->PIO_OWER = g.bit;
|
||||
regs->PIO_PER = g.bit;
|
||||
set_pull_up(regs, g.bit, 0);
|
||||
irq_restore(flag);
|
||||
}
|
||||
|
||||
void
|
||||
gpio_out_toggle_noirq(struct gpio_out g)
|
||||
{
|
||||
Pio *regs = g.regs;
|
||||
regs->PIO_ODSR ^= g.bit;
|
||||
}
|
||||
|
||||
void
|
||||
gpio_out_toggle(struct gpio_out g)
|
||||
{
|
||||
irqstatus_t flag = irq_save();
|
||||
gpio_out_toggle_noirq(g);
|
||||
irq_restore(flag);
|
||||
}
|
||||
|
||||
void
|
||||
gpio_out_write(struct gpio_out g, uint8_t val)
|
||||
{
|
||||
Pio *regs = g.regs;
|
||||
if (val)
|
||||
regs->PIO_SODR = g.bit;
|
||||
else
|
||||
regs->PIO_CODR = g.bit;
|
||||
}
|
||||
|
||||
|
||||
struct gpio_in
|
||||
gpio_in_setup(uint8_t pin, int8_t pull_up)
|
||||
{
|
||||
if (GPIO2PORT(pin) >= ARRAY_SIZE(digital_regs))
|
||||
goto fail;
|
||||
if (CONFIG_MACH_SAM3X && pull_up < 0)
|
||||
goto fail;
|
||||
uint32_t port = GPIO2PORT(pin);
|
||||
enable_pclock(digital_regs[port].dev_id);
|
||||
struct gpio_in g = { .regs=digital_regs[port].dev, .bit=GPIO2BIT(pin) };
|
||||
gpio_in_reset(g, pull_up);
|
||||
return g;
|
||||
fail:
|
||||
shutdown("Not a valid input pin");
|
||||
}
|
||||
|
||||
void
|
||||
gpio_in_reset(struct gpio_in g, int8_t pull_up)
|
||||
{
|
||||
Pio *regs = g.regs;
|
||||
irqstatus_t flag = irq_save();
|
||||
set_pull_up(regs, g.bit, pull_up);
|
||||
regs->PIO_ODR = g.bit;
|
||||
regs->PIO_PER = g.bit;
|
||||
irq_restore(flag);
|
||||
}
|
||||
|
||||
uint8_t
|
||||
gpio_in_read(struct gpio_in g)
|
||||
{
|
||||
Pio *regs = g.regs;
|
||||
return !!(regs->PIO_PDSR & g.bit);
|
||||
}
|
||||
57
src/atsam/gpio.h
Normal file
57
src/atsam/gpio.h
Normal file
@@ -0,0 +1,57 @@
|
||||
#ifndef __ATSAM_GPIO_H
|
||||
#define __ATSAM_GPIO_H
|
||||
|
||||
#include <stdint.h> // uint32_t
|
||||
|
||||
struct gpio_out {
|
||||
void *regs;
|
||||
uint32_t bit;
|
||||
};
|
||||
struct gpio_out gpio_out_setup(uint8_t pin, uint8_t val);
|
||||
void gpio_out_reset(struct gpio_out g, uint8_t val);
|
||||
void gpio_out_toggle_noirq(struct gpio_out g);
|
||||
void gpio_out_toggle(struct gpio_out g);
|
||||
void gpio_out_write(struct gpio_out g, uint8_t val);
|
||||
|
||||
struct gpio_in {
|
||||
void *regs;
|
||||
uint32_t bit;
|
||||
};
|
||||
struct gpio_in gpio_in_setup(uint8_t pin, int8_t pull_up);
|
||||
void gpio_in_reset(struct gpio_in g, int8_t pull_up);
|
||||
uint8_t gpio_in_read(struct gpio_in g);
|
||||
|
||||
struct gpio_pwm {
|
||||
void *reg;
|
||||
};
|
||||
struct gpio_pwm gpio_pwm_setup(uint8_t pin, uint32_t cycle_time, uint8_t val);
|
||||
void gpio_pwm_write(struct gpio_pwm g, uint32_t val);
|
||||
|
||||
struct gpio_adc {
|
||||
uint32_t chan;
|
||||
};
|
||||
struct gpio_adc gpio_adc_setup(uint8_t pin);
|
||||
uint32_t gpio_adc_sample(struct gpio_adc g);
|
||||
uint16_t gpio_adc_read(struct gpio_adc g);
|
||||
void gpio_adc_cancel_sample(struct gpio_adc g);
|
||||
|
||||
struct spi_config {
|
||||
void *spidev;
|
||||
uint32_t cfg;
|
||||
};
|
||||
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 *twi;
|
||||
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
|
||||
233
src/atsam/hard_pwm.c
Normal file
233
src/atsam/hard_pwm.c
Normal file
@@ -0,0 +1,233 @@
|
||||
// Hardware PWM support on atsam
|
||||
//
|
||||
// Copyright (C) 2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "board/irq.h" // irq_save
|
||||
#include "command.h" // shutdown
|
||||
#include "gpio.h" // gpio_pwm_write
|
||||
#include "internal.h" // GPIO
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
#define MAX_PWM 255
|
||||
DECL_CONSTANT("PWM_MAX", MAX_PWM);
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* TC hardware device
|
||||
****************************************************************/
|
||||
|
||||
struct gpio_tc_info {
|
||||
uint8_t gpio, ptype, id;
|
||||
volatile void *reg;
|
||||
};
|
||||
|
||||
static const struct gpio_tc_info tc_regs[] = {
|
||||
#if CONFIG_MACH_SAM3X
|
||||
{ GPIO('B', 25), 'B', ID_TC0, &TC0->TC_CHANNEL[0].TC_RA },
|
||||
{ GPIO('A', 2), 'A', ID_TC1, &TC0->TC_CHANNEL[1].TC_RA },
|
||||
{ GPIO('A', 5), 'A', ID_TC2, &TC0->TC_CHANNEL[2].TC_RA },
|
||||
{ GPIO('B', 27), 'B', ID_TC0, &TC0->TC_CHANNEL[0].TC_RB },
|
||||
{ GPIO('A', 3), 'A', ID_TC1, &TC0->TC_CHANNEL[1].TC_RB },
|
||||
{ GPIO('A', 6), 'A', ID_TC2, &TC0->TC_CHANNEL[2].TC_RB },
|
||||
{ GPIO('B', 0), 'B', ID_TC3, &TC1->TC_CHANNEL[0].TC_RA },
|
||||
{ GPIO('B', 2), 'B', ID_TC4, &TC1->TC_CHANNEL[1].TC_RA },
|
||||
{ GPIO('B', 4), 'B', ID_TC5, &TC1->TC_CHANNEL[2].TC_RA },
|
||||
{ GPIO('B', 1), 'B', ID_TC3, &TC1->TC_CHANNEL[0].TC_RB },
|
||||
{ GPIO('B', 3), 'B', ID_TC4, &TC1->TC_CHANNEL[1].TC_RB },
|
||||
{ GPIO('B', 5), 'B', ID_TC5, &TC1->TC_CHANNEL[2].TC_RB },
|
||||
#if CONFIG_MACH_SAM3X8E
|
||||
{ GPIO('C', 25), 'B', ID_TC6, &TC2->TC_CHANNEL[0].TC_RA },
|
||||
{ GPIO('C', 28), 'B', ID_TC7, &TC2->TC_CHANNEL[1].TC_RA },
|
||||
{ GPIO('D', 7), 'B', ID_TC8, &TC2->TC_CHANNEL[2].TC_RA },
|
||||
{ GPIO('C', 26), 'B', ID_TC6, &TC2->TC_CHANNEL[0].TC_RB },
|
||||
{ GPIO('C', 29), 'B', ID_TC7, &TC2->TC_CHANNEL[1].TC_RB },
|
||||
{ GPIO('D', 8), 'B', ID_TC8, &TC2->TC_CHANNEL[2].TC_RB },
|
||||
#endif
|
||||
#elif CONFIG_MACH_SAM4
|
||||
{ GPIO('A', 0), 'B', ID_TC0, &TC0->TC_CHANNEL[0].TC_RA },
|
||||
{ GPIO('A', 15), 'B', ID_TC1, &TC0->TC_CHANNEL[1].TC_RA },
|
||||
{ GPIO('A', 26), 'B', ID_TC2, &TC0->TC_CHANNEL[2].TC_RA },
|
||||
{ GPIO('A', 1), 'B', ID_TC0, &TC0->TC_CHANNEL[0].TC_RB },
|
||||
{ GPIO('A', 16), 'B', ID_TC1, &TC0->TC_CHANNEL[1].TC_RB },
|
||||
{ GPIO('A', 27), 'B', ID_TC2, &TC0->TC_CHANNEL[2].TC_RB },
|
||||
{ GPIO('C', 23), 'B', ID_TC3, &TC1->TC_CHANNEL[0].TC_RA },
|
||||
{ GPIO('C', 26), 'B', ID_TC4, &TC1->TC_CHANNEL[1].TC_RA },
|
||||
{ GPIO('C', 29), 'B', ID_TC5, &TC1->TC_CHANNEL[2].TC_RA },
|
||||
{ GPIO('C', 24), 'B', ID_TC3, &TC1->TC_CHANNEL[0].TC_RB },
|
||||
{ GPIO('C', 27), 'B', ID_TC4, &TC1->TC_CHANNEL[1].TC_RB },
|
||||
{ GPIO('C', 30), 'B', ID_TC5, &TC1->TC_CHANNEL[2].TC_RB },
|
||||
#if CONFIG_MACH_SAM4E8E
|
||||
{ GPIO('C', 5), 'B', ID_TC6, &TC2->TC_CHANNEL[0].TC_RA },
|
||||
{ GPIO('C', 8), 'B', ID_TC7, &TC2->TC_CHANNEL[1].TC_RA },
|
||||
{ GPIO('C', 11), 'B', ID_TC8, &TC2->TC_CHANNEL[2].TC_RA },
|
||||
{ GPIO('C', 6), 'B', ID_TC6, &TC2->TC_CHANNEL[0].TC_RB },
|
||||
{ GPIO('C', 9), 'B', ID_TC7, &TC2->TC_CHANNEL[1].TC_RB },
|
||||
{ GPIO('C', 12), 'B', ID_TC8, &TC2->TC_CHANNEL[2].TC_RB },
|
||||
#endif
|
||||
#endif
|
||||
};
|
||||
|
||||
static inline int tc_is_tc(struct gpio_pwm g) {
|
||||
return (((uint32_t)g.reg & ~0xffff) == ((uint32_t)TC0 & ~0xffff));
|
||||
}
|
||||
static inline TcChannel *tc_from_reg(struct gpio_pwm g) {
|
||||
return (void*)((uint32_t)g.reg & ~0x3f);
|
||||
}
|
||||
static inline int tc_is_b(struct gpio_pwm g) {
|
||||
return (((uint32_t)g.reg & 0x3f)
|
||||
== ((uint32_t)&TC0->TC_CHANNEL[0].TC_RB & 0x3f));
|
||||
}
|
||||
|
||||
static void
|
||||
gpio_tc_write(struct gpio_pwm g, uint32_t val)
|
||||
{
|
||||
TcChannel *tc = tc_from_reg(g);
|
||||
uint32_t mask = TC_CMR_ACPA_Msk | TC_CMR_ACPC_Msk;
|
||||
uint32_t bits = TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_SET;
|
||||
if (!val)
|
||||
bits = TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_CLEAR;
|
||||
else if (val >= MAX_PWM)
|
||||
bits = TC_CMR_ACPA_SET | TC_CMR_ACPC_SET;
|
||||
if (tc_is_b(g)) {
|
||||
mask <<= 8;
|
||||
bits <<= 8;
|
||||
}
|
||||
irqstatus_t flag = irq_save();
|
||||
tc->TC_CMR = (tc->TC_CMR & ~mask) | bits;
|
||||
*(volatile uint32_t*)g.reg = val;
|
||||
irq_restore(flag);
|
||||
}
|
||||
|
||||
static struct gpio_pwm
|
||||
gpio_tc_setup(uint8_t pin, uint32_t cycle_time, uint8_t val)
|
||||
{
|
||||
// Find pin in tc_regs table
|
||||
const struct gpio_tc_info *p = tc_regs;
|
||||
for (; ; p++) {
|
||||
if (p >= &tc_regs[ARRAY_SIZE(tc_regs)])
|
||||
shutdown("Not a valid PWM pin");
|
||||
if (p->gpio == pin)
|
||||
break;
|
||||
}
|
||||
|
||||
// Map cycle_time to clock divisor
|
||||
uint32_t div = TC_CMR_TCCLKS_TIMER_CLOCK4;
|
||||
if (cycle_time < (MAX_PWM*8 + MAX_PWM*2) / 2)
|
||||
div = TC_CMR_TCCLKS_TIMER_CLOCK1;
|
||||
else if (cycle_time < (MAX_PWM*32 + MAX_PWM*8) / 2)
|
||||
div = TC_CMR_TCCLKS_TIMER_CLOCK2;
|
||||
else if (cycle_time < (MAX_PWM*128 + MAX_PWM*32) / 2)
|
||||
div = TC_CMR_TCCLKS_TIMER_CLOCK3;
|
||||
|
||||
// Enable clock
|
||||
enable_pclock(p->id);
|
||||
|
||||
// Enable PWM output
|
||||
struct gpio_pwm g = (struct gpio_pwm){ (void*)p->reg };
|
||||
TcChannel *tc = tc_from_reg(g);
|
||||
uint32_t prev_cmr = tc->TC_CMR;
|
||||
if (prev_cmr && (prev_cmr & TC_CMR_TCCLKS_Msk) != div)
|
||||
shutdown("PWM already programmed at different speed");
|
||||
gpio_peripheral(pin, p->ptype, 0);
|
||||
if (prev_cmr) {
|
||||
gpio_tc_write(g, val);
|
||||
} else {
|
||||
tc->TC_CMR = TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | div | TC_CMR_EEVT_XC0;
|
||||
gpio_tc_write(g, val);
|
||||
tc->TC_RC = MAX_PWM;
|
||||
tc->TC_CCR = TC_CCR_CLKEN | TC_CCR_SWTRG;
|
||||
}
|
||||
return g;
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* PWM hardware device
|
||||
****************************************************************/
|
||||
|
||||
struct gpio_pwm_info {
|
||||
uint8_t gpio, channel, ptype;
|
||||
};
|
||||
|
||||
static const struct gpio_pwm_info pwm_regs[] = {
|
||||
#if CONFIG_MACH_SAM3X
|
||||
{ GPIO('A', 21), 0, 'B' },
|
||||
{ GPIO('B', 16), 0, 'B' },
|
||||
{ GPIO('A', 12), 1, 'B' },
|
||||
{ GPIO('B', 17), 1, 'B' },
|
||||
{ GPIO('A', 20), 2, 'B' },
|
||||
{ GPIO('B', 18), 2, 'B' },
|
||||
{ GPIO('A', 0), 3, 'B' },
|
||||
{ GPIO('B', 19), 3, 'B' },
|
||||
#if CONFIG_MACH_SAM3X8E
|
||||
{ GPIO('C', 2), 0, 'B' },
|
||||
{ GPIO('C', 4), 1, 'B' },
|
||||
{ GPIO('C', 6), 2, 'B' },
|
||||
{ GPIO('C', 8), 3, 'B' },
|
||||
{ GPIO('C', 21), 4, 'B' },
|
||||
{ GPIO('C', 22), 5, 'B' },
|
||||
{ GPIO('C', 23), 6, 'B' },
|
||||
{ GPIO('C', 24), 7, 'B' },
|
||||
#endif
|
||||
#elif CONFIG_MACH_SAM4
|
||||
{ GPIO('A', 19), 0, 'B' },
|
||||
{ GPIO('B', 5), 0, 'B' },
|
||||
{ GPIO('C', 0), 0, 'B' },
|
||||
{ GPIO('C', 13), 0, 'B' },
|
||||
{ GPIO('A', 20), 1, 'B' },
|
||||
{ GPIO('B', 12), 1, 'A' },
|
||||
{ GPIO('C', 1), 1, 'B' },
|
||||
{ GPIO('C', 15), 1, 'B' },
|
||||
{ GPIO('A', 16), 2, 'C' },
|
||||
{ GPIO('A', 30), 2, 'A' },
|
||||
{ GPIO('B', 13), 2, 'A' },
|
||||
{ GPIO('C', 2), 2, 'B' },
|
||||
{ GPIO('A', 15), 3, 'C' },
|
||||
{ GPIO('C', 3), 3, 'B' },
|
||||
{ GPIO('C', 22), 3, 'B' },
|
||||
#endif
|
||||
};
|
||||
|
||||
struct gpio_pwm
|
||||
gpio_pwm_setup(uint8_t pin, uint32_t cycle_time, uint8_t val)
|
||||
{
|
||||
// Find pin in pwm_regs table
|
||||
const struct gpio_pwm_info *p = pwm_regs;
|
||||
for (; ; p++) {
|
||||
if (p >= &pwm_regs[ARRAY_SIZE(pwm_regs)])
|
||||
return gpio_tc_setup(pin, cycle_time, val);
|
||||
if (p->gpio == pin)
|
||||
break;
|
||||
}
|
||||
|
||||
// Map cycle_time to pwm clock divisor
|
||||
uint32_t div;
|
||||
for (div=0; div<10; div++)
|
||||
if (cycle_time < ((MAX_PWM << (div + 1)) + (MAX_PWM << div)) / 2)
|
||||
break;
|
||||
|
||||
// Enable clock
|
||||
enable_pclock(ID_PWM);
|
||||
|
||||
// Enable PWM output
|
||||
if (PWM->PWM_SR & (1 << p->channel))
|
||||
shutdown("PWM channel already in use");
|
||||
gpio_peripheral(pin, p->ptype, 0);
|
||||
PWM->PWM_CH_NUM[p->channel].PWM_CMR = div;
|
||||
PWM->PWM_CH_NUM[p->channel].PWM_CPRD = MAX_PWM;
|
||||
PWM->PWM_CH_NUM[p->channel].PWM_CDTY = val;
|
||||
PWM->PWM_ENA = 1 << p->channel;
|
||||
|
||||
return (struct gpio_pwm){ (void*)&PWM->PWM_CH_NUM[p->channel].PWM_CDTYUPD };
|
||||
}
|
||||
|
||||
void
|
||||
gpio_pwm_write(struct gpio_pwm g, uint32_t val)
|
||||
{
|
||||
if (tc_is_tc(g))
|
||||
gpio_tc_write(g, val);
|
||||
else
|
||||
*(volatile uint32_t*)g.reg = val;
|
||||
}
|
||||
195
src/atsam/i2c.c
Normal file
195
src/atsam/i2c.c
Normal file
@@ -0,0 +1,195 @@
|
||||
// SAM4 I2C Port
|
||||
//
|
||||
// Copyright (C) 2018 Florian Heilmann <Florian.Heilmann@gmx.net>
|
||||
// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "board/misc.h" // timer_from_us
|
||||
#include "command.h" // shutdown
|
||||
#include "gpio.h" // i2c_setup
|
||||
#include "internal.h" // gpio_peripheral
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
#if CONFIG_MACH_SAME70
|
||||
#include "same70_i2c.h" // Fixes for upstream header changes
|
||||
#endif
|
||||
|
||||
struct twi_info {
|
||||
void *dev;
|
||||
uint32_t dev_id;
|
||||
uint8_t scl_pin, sda_pin, periph;
|
||||
};
|
||||
|
||||
// I2C pin definitions
|
||||
#if CONFIG_MACH_SAM3X
|
||||
DECL_ENUMERATION_RANGE("i2c_bus", "twi0", 0, 2);
|
||||
DECL_CONSTANT_STR("BUS_PINS_twi0", "PA18,PA17");
|
||||
DECL_CONSTANT_STR("BUS_PINS_twi1", "PB13,PB12");
|
||||
#define PRD_CALC_NUM 4
|
||||
#elif CONFIG_MACH_SAM4
|
||||
DECL_ENUMERATION_RANGE("i2c_bus", "twi0", 0, 2);
|
||||
DECL_CONSTANT_STR("BUS_PINS_twi0", "PA4,PA3");
|
||||
DECL_CONSTANT_STR("BUS_PINS_twi1", "PB5,PB4");
|
||||
#define PRD_CALC_NUM 4
|
||||
#elif CONFIG_MACH_SAME70
|
||||
DECL_ENUMERATION_RANGE("i2c_bus", "twihs0", 0,3);
|
||||
DECL_CONSTANT_STR("BUS_PINS_twihs0", "PA4,PA3");
|
||||
DECL_CONSTANT_STR("BUS_PINS_twihs1", "PB5,PB4");
|
||||
DECL_CONSTANT_STR("BUS_PINS_twihs2", "PD28,PD27");
|
||||
#define PRD_CALC_NUM 3
|
||||
#endif
|
||||
|
||||
static const struct twi_info twi_bus[] = {
|
||||
#if CONFIG_MACH_SAM3X
|
||||
{ TWI0, ID_TWI0, GPIO('A', 18), GPIO('A', 17), 'A'},
|
||||
{ TWI1, ID_TWI1, GPIO('B', 13), GPIO('B', 12), 'A'},
|
||||
#elif CONFIG_MACH_SAM4
|
||||
{ TWI0, ID_TWI0, GPIO('A', 4), GPIO('A', 3), 'A'},
|
||||
{ TWI1, ID_TWI1, GPIO('B', 5), GPIO('B', 4), 'A'},
|
||||
#elif CONFIG_MACH_SAME70
|
||||
{ TWIHS0, ID_TWIHS0, GPIO('A', 4), GPIO('A', 3), 'A'},
|
||||
{ TWIHS1, ID_TWIHS1, GPIO('B', 5), GPIO('B', 4), 'A'},
|
||||
{ TWIHS2, ID_TWIHS2, GPIO('D', 28), GPIO('D', 27), 'C'},
|
||||
#endif
|
||||
};
|
||||
|
||||
static void
|
||||
init_pins(uint32_t bus)
|
||||
{
|
||||
const struct twi_info *si = &twi_bus[bus];
|
||||
gpio_peripheral(si->scl_pin, si->periph, 1);
|
||||
gpio_peripheral(si->sda_pin, si->periph, 1);
|
||||
enable_pclock(si->dev_id);
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_init(uint32_t bus, uint32_t rate)
|
||||
{
|
||||
Twi *p_twi = twi_bus[bus].dev;
|
||||
p_twi->TWI_IDR = 0xFFFFFFFF;
|
||||
(void)p_twi->TWI_SR;
|
||||
p_twi->TWI_CR = TWI_CR_SWRST;
|
||||
(void)p_twi->TWI_RHR;
|
||||
p_twi->TWI_CR = TWI_CR_MSDIS;
|
||||
p_twi->TWI_CR = TWI_CR_SVDIS;
|
||||
p_twi->TWI_CR = TWI_CR_MSEN;
|
||||
|
||||
uint32_t pclk = get_pclock_frequency(twi_bus[bus].dev_id);
|
||||
uint32_t cldiv = 0, chdiv = 0, ckdiv = 0;
|
||||
cldiv = pclk / ((rate > 384000 ? 384000 : rate) * 2) - PRD_CALC_NUM;
|
||||
|
||||
while ((cldiv > 255) && (ckdiv < 7)) {
|
||||
ckdiv++;
|
||||
cldiv /= 2;
|
||||
}
|
||||
|
||||
if (rate > 348000) {
|
||||
chdiv = pclk / ((2 * rate - 384000) * 2) - PRD_CALC_NUM;
|
||||
while ((chdiv > 255) && (ckdiv < 7)) {
|
||||
ckdiv++;
|
||||
chdiv /= 2;
|
||||
}
|
||||
} else {
|
||||
chdiv = cldiv;
|
||||
}
|
||||
p_twi->TWI_CWGR = (TWI_CWGR_CLDIV(cldiv) | TWI_CWGR_CHDIV(chdiv)
|
||||
| TWI_CWGR_CKDIV(ckdiv));
|
||||
}
|
||||
|
||||
static uint32_t
|
||||
addr_to_u32(uint8_t addr_len, uint8_t *addr)
|
||||
{
|
||||
uint32_t address = addr[0];
|
||||
if (addr_len > 1) {
|
||||
address <<= 8;
|
||||
address |= addr[1];
|
||||
}
|
||||
if (addr_len > 2) {
|
||||
address <<= 8;
|
||||
address |= addr[2];
|
||||
}
|
||||
if (addr_len > 3) {
|
||||
shutdown("Addresses larger than 3 bytes are not supported");
|
||||
}
|
||||
return address;
|
||||
}
|
||||
|
||||
struct i2c_config
|
||||
i2c_setup(uint32_t bus, uint32_t rate, uint8_t addr)
|
||||
{
|
||||
if (bus >= ARRAY_SIZE(twi_bus) || rate > 400000)
|
||||
shutdown("Invalid i2c_setup parameters!");
|
||||
Twi *p_twi = twi_bus[bus].dev;
|
||||
init_pins(bus);
|
||||
i2c_init(bus, rate);
|
||||
return (struct i2c_config){ .twi=p_twi, .addr=addr};
|
||||
}
|
||||
|
||||
void
|
||||
i2c_write(struct i2c_config config, uint8_t write_len, uint8_t *write)
|
||||
{
|
||||
Twi *p_twi = config.twi;
|
||||
uint32_t timeout = timer_read_time() + timer_from_us(5000);
|
||||
uint32_t status, bytes_to_send = write_len;
|
||||
p_twi->TWI_MMR = TWI_MMR_DADR(config.addr);
|
||||
for (;;) {
|
||||
status = p_twi->TWI_SR;
|
||||
if (status & TWI_SR_NACK)
|
||||
shutdown("I2C NACK error encountered!");
|
||||
if (!(status & TWI_SR_TXRDY)) {
|
||||
if (!timer_is_before(timer_read_time(), timeout))
|
||||
shutdown("I2C timeout occured");
|
||||
continue;
|
||||
}
|
||||
if (!bytes_to_send)
|
||||
break;
|
||||
p_twi->TWI_THR = *write++;
|
||||
bytes_to_send--;
|
||||
}
|
||||
p_twi->TWI_CR = TWI_CR_STOP;
|
||||
while (!(p_twi->TWI_SR & TWI_SR_TXCOMP))
|
||||
;
|
||||
}
|
||||
|
||||
void
|
||||
i2c_read(struct i2c_config config, uint8_t reg_len, uint8_t *reg
|
||||
, uint8_t read_len, uint8_t *read)
|
||||
{
|
||||
Twi *p_twi = config.twi;
|
||||
uint32_t timeout = timer_read_time() + timer_from_us(5000);
|
||||
uint32_t status, bytes_to_send = read_len;
|
||||
uint8_t stop = 0;
|
||||
p_twi->TWI_MMR = 0;
|
||||
p_twi->TWI_MMR = (TWI_MMR_MREAD | TWI_MMR_DADR(config.addr)
|
||||
| ((reg_len << TWI_MMR_IADRSZ_Pos) & TWI_MMR_IADRSZ_Msk));
|
||||
p_twi->TWI_IADR = 0;
|
||||
p_twi->TWI_IADR = addr_to_u32(reg_len, reg);
|
||||
if (bytes_to_send == 1) {
|
||||
p_twi->TWI_CR = TWI_CR_START | TWI_CR_STOP;
|
||||
stop = 1;
|
||||
} else {
|
||||
p_twi->TWI_CR = TWI_CR_START;
|
||||
stop = 0;
|
||||
}
|
||||
while (bytes_to_send > 0) {
|
||||
status = p_twi->TWI_SR;
|
||||
if (status & TWI_SR_NACK) {
|
||||
shutdown("I2C NACK error encountered!");
|
||||
}
|
||||
if (bytes_to_send == 1 && !stop) {
|
||||
p_twi->TWI_CR = TWI_CR_STOP;
|
||||
stop = 1;
|
||||
}
|
||||
if (!(status & TWI_SR_RXRDY)) {
|
||||
if (!timer_is_before(timer_read_time(), timeout))
|
||||
shutdown("I2C timeout occured");
|
||||
continue;
|
||||
}
|
||||
*read++ = p_twi->TWI_RHR;
|
||||
bytes_to_send--;
|
||||
}
|
||||
while (!(p_twi->TWI_SR & TWI_SR_TXCOMP))
|
||||
;
|
||||
(void)p_twi->TWI_SR;
|
||||
}
|
||||
27
src/atsam/internal.h
Normal file
27
src/atsam/internal.h
Normal file
@@ -0,0 +1,27 @@
|
||||
#ifndef __ATSAM_INTERNAL_H
|
||||
#define __ATSAM_INTERNAL_H
|
||||
// Local definitions for sam3/sam4 code
|
||||
|
||||
#include <stdint.h> // uint32_t
|
||||
#include "autoconf.h" // CONFIG_MACH_SAM3X
|
||||
|
||||
#if CONFIG_MACH_SAM3X
|
||||
#include "sam3xa.h"
|
||||
#elif CONFIG_MACH_SAM4S
|
||||
#include "sam4s.h"
|
||||
#elif CONFIG_MACH_SAM4E
|
||||
#include "sam4e.h"
|
||||
#elif CONFIG_MACH_SAME70
|
||||
#include "sam.h"
|
||||
#endif
|
||||
|
||||
#define GPIO(PORT, NUM) (((PORT)-'A') * 32 + (NUM))
|
||||
#define GPIO2PORT(PIN) ((PIN) / 32)
|
||||
#define GPIO2BIT(PIN) (1<<((PIN) % 32))
|
||||
|
||||
void gpio_peripheral(uint32_t gpio, char ptype, int32_t pull_up);
|
||||
int is_enabled_pclock(uint32_t id);
|
||||
void enable_pclock(uint32_t id);
|
||||
uint32_t get_pclock_frequency(uint32_t id);
|
||||
|
||||
#endif // internal.h
|
||||
135
src/atsam/main.c
Normal file
135
src/atsam/main.c
Normal file
@@ -0,0 +1,135 @@
|
||||
// Main starting point for SAM3/SAM4 boards
|
||||
//
|
||||
// Copyright (C) 2016-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "board/armcm_boot.h" // armcm_main
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "board/usb_cdc.h" // usb_request_bootloader
|
||||
#include "command.h" // DECL_COMMAND_FLAGS
|
||||
#include "internal.h" // WDT
|
||||
#include "sched.h" // sched_main
|
||||
|
||||
#define FREQ_PERIPH_DIV (CONFIG_MACH_SAME70 ? 2 : 1)
|
||||
#define FREQ_PERIPH (CONFIG_CLOCK_FREQ / FREQ_PERIPH_DIV)
|
||||
|
||||
/****************************************************************
|
||||
* watchdog handler
|
||||
****************************************************************/
|
||||
|
||||
void
|
||||
watchdog_reset(void)
|
||||
{
|
||||
WDT->WDT_CR = 0xA5000001;
|
||||
}
|
||||
DECL_TASK(watchdog_reset);
|
||||
|
||||
void
|
||||
watchdog_init(void)
|
||||
{
|
||||
uint32_t timeout = 500 * 32768 / 128 / 1000; // 500ms timeout
|
||||
WDT->WDT_MR = WDT_MR_WDRSTEN | WDT_MR_WDV(timeout) | WDT_MR_WDD(timeout);
|
||||
}
|
||||
DECL_INIT(watchdog_init);
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Peripheral clocks
|
||||
****************************************************************/
|
||||
|
||||
// Check if a peripheral clock has been enabled
|
||||
int
|
||||
is_enabled_pclock(uint32_t id)
|
||||
{
|
||||
if (id < 32)
|
||||
return !!(PMC->PMC_PCSR0 & (1 << id));
|
||||
else
|
||||
return !!(PMC->PMC_PCSR1 & (1 << (id - 32)));
|
||||
}
|
||||
|
||||
// Enable a peripheral clock
|
||||
void
|
||||
enable_pclock(uint32_t id)
|
||||
{
|
||||
if (id < 32)
|
||||
PMC->PMC_PCER0 = 1 << id;
|
||||
else
|
||||
PMC->PMC_PCER1 = 1 << (id - 32);
|
||||
}
|
||||
|
||||
// Return the frequency of the given peripheral clock
|
||||
uint32_t
|
||||
get_pclock_frequency(uint32_t id)
|
||||
{
|
||||
return FREQ_PERIPH;
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Resets
|
||||
****************************************************************/
|
||||
|
||||
#if CONFIG_MACH_SAME70
|
||||
#define RST_PARAMS ((0xA5 << RSTC_CR_KEY_Pos) | RSTC_CR_PROCRST)
|
||||
#else
|
||||
#define RST_PARAMS ((0xA5 << RSTC_CR_KEY_Pos) | RSTC_CR_PROCRST \
|
||||
| RSTC_CR_PERRST)
|
||||
#endif
|
||||
|
||||
void
|
||||
command_reset(uint32_t *args)
|
||||
{
|
||||
irq_disable();
|
||||
RSTC->RSTC_CR = RST_PARAMS;
|
||||
for (;;)
|
||||
;
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_reset, HF_IN_SHUTDOWN, "reset");
|
||||
|
||||
#if CONFIG_MACH_SAM3X || CONFIG_MACH_SAM4S
|
||||
#define EFC_HW EFC0
|
||||
#elif CONFIG_MACH_SAM4E || CONFIG_MACH_SAME70
|
||||
#define EFC_HW EFC
|
||||
#endif
|
||||
|
||||
void noinline __aligned(16) // align for predictable flash code access
|
||||
usb_request_bootloader(void)
|
||||
{
|
||||
irq_disable();
|
||||
// Request boot from ROM (instead of boot from flash)
|
||||
while ((EFC_HW->EEFC_FSR & EEFC_FSR_FRDY) == 0)
|
||||
;
|
||||
EFC_HW->EEFC_FCR = (EEFC_FCR_FCMD_CGPB | EEFC_FCR_FARG(1)
|
||||
| EEFC_FCR_FKEY_PASSWD);
|
||||
while ((EFC_HW->EEFC_FSR & EEFC_FSR_FRDY) == 0)
|
||||
;
|
||||
// Reboot
|
||||
RSTC->RSTC_CR = RST_PARAMS;
|
||||
for (;;)
|
||||
;
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Startup
|
||||
****************************************************************/
|
||||
|
||||
static void
|
||||
matrix_init(void)
|
||||
{
|
||||
// The ATSAM sram is in a "no default master" state at reset
|
||||
// (despite the specs). That typically adds 1 wait cycle to every
|
||||
// memory access. Set it to "last access master" to avoid that.
|
||||
MATRIX->MATRIX_SCFG[0] = (MATRIX_SCFG_SLOT_CYCLE(64)
|
||||
| MATRIX_SCFG_DEFMSTR_TYPE(1));
|
||||
}
|
||||
|
||||
// Main entry point - called from armcm_boot.c:ResetHandler()
|
||||
void
|
||||
armcm_main(void)
|
||||
{
|
||||
SystemInit();
|
||||
matrix_init();
|
||||
sched_main();
|
||||
}
|
||||
234
src/atsam/sam3_usb.c
Normal file
234
src/atsam/sam3_usb.c
Normal file
@@ -0,0 +1,234 @@
|
||||
// Hardware interface to USB on SAM3X
|
||||
//
|
||||
// Copyright (C) 2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // NULL
|
||||
#include "board/armcm_boot.h" // armcm_enable_irq
|
||||
#include "board/usb_cdc.h" // usb_notify_ep0
|
||||
#include "board/usb_cdc_ep.h" // USB_CDC_EP_BULK_IN
|
||||
#include "internal.h" // UOTGHS
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
#if CONFIG_MACH_SAME70
|
||||
#include "same70_usb.h" // Fixes for upstream header changes
|
||||
#define CFG_UOTGHS_CTRL (UOTGHS_CTRL_UIMOD | UOTGHS_CTRL_USBE)
|
||||
#else
|
||||
#define CFG_UOTGHS_CTRL (UOTGHS_CTRL_UIMOD | UOTGHS_CTRL_OTGPADE | \
|
||||
UOTGHS_CTRL_USBE)
|
||||
#endif
|
||||
|
||||
#define EP_SIZE(s) ((s)==64 ? UOTGHS_DEVEPTCFG_EPSIZE_64_BYTE : \
|
||||
((s)==32 ? UOTGHS_DEVEPTCFG_EPSIZE_32_BYTE : \
|
||||
((s)==16 ? UOTGHS_DEVEPTCFG_EPSIZE_16_BYTE : \
|
||||
UOTGHS_DEVEPTCFG_EPSIZE_8_BYTE)))
|
||||
|
||||
#define usb_fifo(ep) ((void*)UOTGHS_RAM_ADDR + ((ep) * 0x8000))
|
||||
|
||||
static void
|
||||
usb_write_packet(uint32_t ep, const uint8_t *data, uint32_t len)
|
||||
{
|
||||
uint8_t *dest = usb_fifo(ep);
|
||||
while (len--)
|
||||
*dest++ = *data++;
|
||||
}
|
||||
|
||||
static void
|
||||
usb_read_packet(uint32_t ep, uint8_t *data, uint32_t len)
|
||||
{
|
||||
uint8_t *src = usb_fifo(ep);
|
||||
while (len--)
|
||||
*data++ = *src++;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_read_bulk_out(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
uint32_t eps = UOTGHS->UOTGHS_DEVEPTISR[USB_CDC_EP_BULK_OUT];
|
||||
if (!(eps & UOTGHS_DEVEPTISR_RXOUTI)) {
|
||||
// No data ready
|
||||
UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_PEP_0 << USB_CDC_EP_BULK_OUT;
|
||||
return -1;
|
||||
}
|
||||
uint32_t len = (eps&UOTGHS_DEVEPTISR_BYCT_Msk) >> UOTGHS_DEVEPTISR_BYCT_Pos;
|
||||
usb_read_packet(USB_CDC_EP_BULK_OUT, data, len > max_len ? max_len : len);
|
||||
UOTGHS->UOTGHS_DEVEPTICR[USB_CDC_EP_BULK_OUT] = UOTGHS_DEVEPTICR_RXOUTIC;
|
||||
UOTGHS->UOTGHS_DEVEPTIDR[USB_CDC_EP_BULK_OUT] = UOTGHS_DEVEPTIDR_FIFOCONC;
|
||||
return len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_send_bulk_in(void *data, uint_fast8_t len)
|
||||
{
|
||||
uint32_t eps = UOTGHS->UOTGHS_DEVEPTISR[USB_CDC_EP_BULK_IN];
|
||||
if (!(eps & UOTGHS_DEVEPTISR_TXINI)) {
|
||||
// Buffer full
|
||||
UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_PEP_0 << USB_CDC_EP_BULK_IN;
|
||||
return -1;
|
||||
}
|
||||
usb_write_packet(USB_CDC_EP_BULK_IN, data, len);
|
||||
UOTGHS->UOTGHS_DEVEPTICR[USB_CDC_EP_BULK_IN] = UOTGHS_DEVEPTICR_TXINIC;
|
||||
UOTGHS->UOTGHS_DEVEPTIDR[USB_CDC_EP_BULK_IN] = UOTGHS_DEVEPTIDR_FIFOCONC;
|
||||
return len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_read_ep0(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
uint32_t eps = UOTGHS->UOTGHS_DEVEPTISR[0];
|
||||
if (eps & UOTGHS_DEVEPTISR_RXSTPI)
|
||||
return -2;
|
||||
if (!(eps & UOTGHS_DEVEPTISR_RXOUTI)) {
|
||||
// Not ready to receive data
|
||||
UOTGHS->UOTGHS_DEVEPTIER[0] = UOTGHS_DEVEPTIER_RXOUTES;
|
||||
UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_PEP_0 << 0;
|
||||
return -1;
|
||||
}
|
||||
usb_read_packet(0, data, max_len);
|
||||
if (UOTGHS->UOTGHS_DEVEPTISR[0] & UOTGHS_DEVEPTISR_RXSTPI)
|
||||
return -2;
|
||||
UOTGHS->UOTGHS_DEVEPTICR[0] = UOTGHS_DEVEPTICR_RXOUTIC;
|
||||
return max_len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_read_ep0_setup(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
uint32_t eps = UOTGHS->UOTGHS_DEVEPTISR[0];
|
||||
if (!(eps & UOTGHS_DEVEPTISR_RXSTPI)) {
|
||||
// No data ready to read
|
||||
UOTGHS->UOTGHS_DEVEPTIDR[0] = (UOTGHS_DEVEPTIDR_TXINEC
|
||||
| UOTGHS_DEVEPTIDR_RXOUTEC);
|
||||
UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_PEP_0 << 0;
|
||||
return -1;
|
||||
}
|
||||
usb_read_packet(0, data, max_len);
|
||||
UOTGHS->UOTGHS_DEVEPTICR[0] = (UOTGHS_DEVEPTICR_RXSTPIC
|
||||
| UOTGHS_DEVEPTICR_RXOUTIC);
|
||||
return max_len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_send_ep0(const void *data, uint_fast8_t len)
|
||||
{
|
||||
uint32_t eps = UOTGHS->UOTGHS_DEVEPTISR[0];
|
||||
if (eps & (UOTGHS_DEVEPTISR_RXSTPI | UOTGHS_DEVEPTISR_RXOUTI))
|
||||
return -2;
|
||||
if (!(eps & UOTGHS_DEVEPTISR_TXINI)) {
|
||||
// Not ready to send
|
||||
UOTGHS->UOTGHS_DEVEPTIER[0] = (UOTGHS_DEVEPTIER_TXINES
|
||||
| UOTGHS_DEVEPTIER_RXOUTES);
|
||||
UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_PEP_0 << 0;
|
||||
return -1;
|
||||
}
|
||||
usb_write_packet(0, data, len);
|
||||
UOTGHS->UOTGHS_DEVEPTICR[0] = UOTGHS_DEVEPTICR_TXINIC;
|
||||
return len;
|
||||
}
|
||||
|
||||
void
|
||||
usb_stall_ep0(void)
|
||||
{
|
||||
UOTGHS->UOTGHS_DEVEPTIER[0] = UOTGHS_DEVEPTIER_STALLRQS;
|
||||
UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_PEP_0 << 0;
|
||||
}
|
||||
|
||||
static uint8_t set_address;
|
||||
|
||||
void
|
||||
usb_set_address(uint_fast8_t addr)
|
||||
{
|
||||
set_address = addr | UOTGHS_DEVCTRL_ADDEN;
|
||||
usb_send_ep0(NULL, 0);
|
||||
UOTGHS->UOTGHS_DEVEPTIER[0] = UOTGHS_DEVEPTIER_TXINES;
|
||||
UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_PEP_0 << 0;
|
||||
}
|
||||
|
||||
void
|
||||
usb_set_configure(void)
|
||||
{
|
||||
UOTGHS->UOTGHS_DEVEPT = ((UOTGHS_DEVEPT_EPEN0 << 0)
|
||||
| (UOTGHS_DEVEPT_EPEN0 << USB_CDC_EP_BULK_OUT)
|
||||
| (UOTGHS_DEVEPT_EPEN0 << USB_CDC_EP_BULK_IN)
|
||||
| (UOTGHS_DEVEPT_EPEN0 << USB_CDC_EP_ACM));
|
||||
|
||||
UOTGHS->UOTGHS_DEVEPTCFG[USB_CDC_EP_BULK_OUT] = (
|
||||
EP_SIZE(USB_CDC_EP_BULK_OUT_SIZE)
|
||||
| UOTGHS_DEVEPTCFG_EPTYPE_BLK | UOTGHS_DEVEPTCFG_EPBK_2_BANK
|
||||
| UOTGHS_DEVEPTCFG_ALLOC);
|
||||
UOTGHS->UOTGHS_DEVEPTIER[USB_CDC_EP_BULK_OUT] = UOTGHS_DEVEPTIER_RXOUTES;
|
||||
UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_PEP_0 << USB_CDC_EP_BULK_OUT;
|
||||
|
||||
UOTGHS->UOTGHS_DEVEPTCFG[USB_CDC_EP_BULK_IN] = (
|
||||
EP_SIZE(USB_CDC_EP_BULK_IN_SIZE) | UOTGHS_DEVEPTCFG_EPDIR_IN
|
||||
| UOTGHS_DEVEPTCFG_EPTYPE_BLK | UOTGHS_DEVEPTCFG_EPBK_2_BANK
|
||||
| UOTGHS_DEVEPTCFG_ALLOC);
|
||||
UOTGHS->UOTGHS_DEVEPTIER[USB_CDC_EP_BULK_IN] = UOTGHS_DEVEPTIER_TXINES;
|
||||
UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_PEP_0 << USB_CDC_EP_BULK_IN;
|
||||
|
||||
UOTGHS->UOTGHS_DEVEPTCFG[USB_CDC_EP_ACM] = (
|
||||
EP_SIZE(USB_CDC_EP_ACM_SIZE) | UOTGHS_DEVEPTCFG_EPDIR_IN
|
||||
| UOTGHS_DEVEPTCFG_EPTYPE_INTRPT | UOTGHS_DEVEPTCFG_EPBK_2_BANK
|
||||
| UOTGHS_DEVEPTCFG_ALLOC);
|
||||
}
|
||||
|
||||
// Configure endpoint 0 after usb reset completes
|
||||
static void
|
||||
handle_end_reset(void)
|
||||
{
|
||||
UOTGHS->UOTGHS_DEVEPT = UOTGHS_DEVEPT_EPEN0 << 0;
|
||||
UOTGHS->UOTGHS_DEVEPTCFG[0] = (
|
||||
EP_SIZE(USB_CDC_EP0_SIZE)
|
||||
| UOTGHS_DEVEPTCFG_EPTYPE_CTRL | UOTGHS_DEVEPTCFG_EPBK_1_BANK
|
||||
| UOTGHS_DEVEPTCFG_ALLOC);
|
||||
UOTGHS->UOTGHS_DEVEPTIER[0] = UOTGHS_DEVEPTIER_RXSTPES;
|
||||
UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_PEP_0 << 0;
|
||||
|
||||
UOTGHS->UOTGHS_DEVICR = UOTGHS_DEVICR_EORSTC;
|
||||
}
|
||||
|
||||
void
|
||||
UOTGHS_Handler(void)
|
||||
{
|
||||
uint32_t s = UOTGHS->UOTGHS_DEVISR;
|
||||
if (s & UOTGHS_DEVISR_EORST) {
|
||||
handle_end_reset();
|
||||
return;
|
||||
}
|
||||
UOTGHS->UOTGHS_DEVIDR = s;
|
||||
if (s & (UOTGHS_DEVISR_PEP_0 << 0)) {
|
||||
usb_notify_ep0();
|
||||
|
||||
if (set_address
|
||||
&& (UOTGHS->UOTGHS_DEVEPTISR[0] & UOTGHS_DEVEPTISR_TXINI)) {
|
||||
// Ack from set_address command sent - now update address
|
||||
UOTGHS->UOTGHS_DEVCTRL = (set_address
|
||||
| UOTGHS_DEVCTRL_SPDCONF_FORCED_FS);
|
||||
set_address = 0;
|
||||
}
|
||||
}
|
||||
if (s & (UOTGHS_DEVISR_PEP_0 << USB_CDC_EP_BULK_OUT))
|
||||
usb_notify_bulk_out();
|
||||
if (s & (UOTGHS_DEVISR_PEP_0 << USB_CDC_EP_BULK_IN))
|
||||
usb_notify_bulk_in();
|
||||
}
|
||||
|
||||
void
|
||||
usbserial_init(void)
|
||||
{
|
||||
// Setup USB clock
|
||||
enable_pclock(ID_UOTGHS);
|
||||
PMC->CKGR_UCKR = CKGR_UCKR_UPLLCOUNT(3) | CKGR_UCKR_UPLLEN;
|
||||
while (!(PMC->PMC_SR & PMC_SR_LOCKU))
|
||||
;
|
||||
|
||||
// Enable USB
|
||||
UOTGHS->UOTGHS_CTRL = CFG_UOTGHS_CTRL;
|
||||
UOTGHS->UOTGHS_DEVCTRL = UOTGHS_DEVCTRL_SPDCONF_FORCED_FS;
|
||||
|
||||
// Enable interrupts
|
||||
armcm_enable_irq(UOTGHS_Handler, UOTGHS_IRQn, 1);
|
||||
UOTGHS->UOTGHS_DEVIER = UOTGHS_DEVIER_EORSTES;
|
||||
}
|
||||
DECL_INIT(usbserial_init);
|
||||
16
src/atsam/sam4_cache.c
Normal file
16
src/atsam/sam4_cache.c
Normal file
@@ -0,0 +1,16 @@
|
||||
// SAM4 cache enable
|
||||
//
|
||||
// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "sam4e.h" // CMCC
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
void
|
||||
sam4_cache_init(void)
|
||||
{
|
||||
if (!(CMCC->CMCC_SR & CMCC_SR_CSTS))
|
||||
CMCC->CMCC_CTRL = CMCC_CTRL_CEN;
|
||||
}
|
||||
DECL_INIT(sam4_cache_init);
|
||||
218
src/atsam/sam4_usb.c
Normal file
218
src/atsam/sam4_usb.c
Normal file
@@ -0,0 +1,218 @@
|
||||
// Hardware interface to SAM4 USB Device Port
|
||||
//
|
||||
// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // NULL
|
||||
#include "board/armcm_boot.h" // armcm_enable_irq
|
||||
#include "board/irq.h" // irq_disable
|
||||
#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
|
||||
#include "internal.h" // UDP
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
#define CSR_EP0 (UDP_CSR_EPTYPE_CTRL | UDP_CSR_EPEDS)
|
||||
#define CSR_ACM (UDP_CSR_EPTYPE_INT_IN | UDP_CSR_EPEDS)
|
||||
#define CSR_BULK_OUT (UDP_CSR_EPTYPE_BULK_OUT | UDP_CSR_EPEDS)
|
||||
#define CSR_BULK_IN (UDP_CSR_EPTYPE_BULK_IN | UDP_CSR_EPEDS)
|
||||
|
||||
static void
|
||||
usb_write_packet(uint32_t ep, const uint8_t *data, uint32_t len)
|
||||
{
|
||||
while (len--)
|
||||
UDP->UDP_FDR[ep] = *data++;
|
||||
}
|
||||
|
||||
static uint32_t
|
||||
usb_read_packet(uint32_t ep, uint32_t csr, uint8_t *data, uint32_t max_len)
|
||||
{
|
||||
uint32_t pk_len = (csr & UDP_CSR_RXBYTECNT_Msk) >> UDP_CSR_RXBYTECNT_Pos;
|
||||
uint32_t len = pk_len < max_len ? pk_len : max_len, orig_len = len;
|
||||
while (len--)
|
||||
*data++ = UDP->UDP_FDR[ep];
|
||||
return orig_len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_read_bulk_out(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
static uint32_t next_bk = UDP_CSR_RX_DATA_BK0;
|
||||
const uint32_t other_irqs = (UDP_CSR_RXSETUP | UDP_CSR_STALLSENT
|
||||
| UDP_CSR_TXCOMP);
|
||||
uint32_t csr = UDP->UDP_CSR[USB_CDC_EP_BULK_OUT];
|
||||
uint32_t bk = csr & (UDP_CSR_RX_DATA_BK0 | UDP_CSR_RX_DATA_BK1);
|
||||
if (!bk) {
|
||||
// Not ready to receive data
|
||||
if (csr & other_irqs)
|
||||
UDP->UDP_CSR[USB_CDC_EP_BULK_OUT] = (
|
||||
CSR_BULK_OUT | UDP_CSR_RX_DATA_BK0 | UDP_CSR_RX_DATA_BK1);
|
||||
UDP->UDP_IER = 1<<USB_CDC_EP_BULK_OUT;
|
||||
return -1;
|
||||
}
|
||||
uint32_t len = usb_read_packet(USB_CDC_EP_BULK_OUT, csr, data, max_len);
|
||||
if (bk == (UDP_CSR_RX_DATA_BK0 | UDP_CSR_RX_DATA_BK1))
|
||||
bk = next_bk;
|
||||
next_bk = bk ^ (UDP_CSR_RX_DATA_BK0 | UDP_CSR_RX_DATA_BK1);
|
||||
UDP->UDP_CSR[USB_CDC_EP_BULK_OUT] = CSR_BULK_OUT | next_bk;
|
||||
return len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_send_bulk_in(void *data, uint_fast8_t len)
|
||||
{
|
||||
const uint32_t other_irqs = (UDP_CSR_RXSETUP | UDP_CSR_STALLSENT
|
||||
| UDP_CSR_RX_DATA_BK0 | UDP_CSR_RX_DATA_BK1);
|
||||
uint32_t csr = UDP->UDP_CSR[USB_CDC_EP_BULK_IN];
|
||||
if (csr & UDP_CSR_TXPKTRDY) {
|
||||
// Not ready to send
|
||||
if (csr & other_irqs)
|
||||
UDP->UDP_CSR[USB_CDC_EP_BULK_IN] = CSR_BULK_IN | UDP_CSR_TXCOMP;
|
||||
UDP->UDP_IER = 1<<USB_CDC_EP_BULK_IN;
|
||||
return -1;
|
||||
}
|
||||
usb_write_packet(USB_CDC_EP_BULK_IN, data, len);
|
||||
UDP->UDP_CSR[USB_CDC_EP_BULK_IN] = CSR_BULK_IN | UDP_CSR_TXPKTRDY;
|
||||
return len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_read_ep0(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
const uint32_t other_irqs = (UDP_CSR_RXSETUP | UDP_CSR_STALLSENT
|
||||
| UDP_CSR_TXCOMP | UDP_CSR_RX_DATA_BK1);
|
||||
uint32_t csr = UDP->UDP_CSR[0];
|
||||
if (csr & other_irqs)
|
||||
return -2;
|
||||
if (!(csr & UDP_CSR_RX_DATA_BK0)) {
|
||||
// Not ready to receive data
|
||||
UDP->UDP_IER = 1<<0;
|
||||
return -1;
|
||||
}
|
||||
uint32_t len = usb_read_packet(0, csr, data, max_len);
|
||||
if (UDP->UDP_CSR[0] & other_irqs)
|
||||
return -2;
|
||||
UDP->UDP_CSR[0] = CSR_EP0 | other_irqs;
|
||||
return len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_read_ep0_setup(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
const uint32_t other_irqs = (UDP_CSR_STALLSENT | UDP_CSR_TXCOMP
|
||||
| UDP_CSR_RX_DATA_BK0 | UDP_CSR_RX_DATA_BK1);
|
||||
uint32_t csr = UDP->UDP_CSR[0];
|
||||
if (!(csr & UDP_CSR_RXSETUP)) {
|
||||
// No data ready to read
|
||||
if (csr & other_irqs)
|
||||
UDP->UDP_CSR[0] = CSR_EP0 | UDP_CSR_RXSETUP;
|
||||
UDP->UDP_IER = 1<<0;
|
||||
return -1;
|
||||
}
|
||||
uint32_t len = usb_read_packet(0, csr, data, max_len);
|
||||
uint32_t dir = *(uint8_t*)data & 0x80 ? UDP_CSR_DIR : 0;
|
||||
UDP->UDP_CSR[0] = CSR_EP0 | dir;
|
||||
return len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_send_ep0(const void *data, uint_fast8_t len)
|
||||
{
|
||||
const uint32_t other_irqs = (UDP_CSR_RXSETUP | UDP_CSR_STALLSENT
|
||||
| UDP_CSR_RX_DATA_BK0 | UDP_CSR_RX_DATA_BK1);
|
||||
uint32_t csr = UDP->UDP_CSR[0];
|
||||
if (csr & other_irqs)
|
||||
return -2;
|
||||
if (csr & UDP_CSR_TXPKTRDY) {
|
||||
// Not ready to send
|
||||
UDP->UDP_IER = 1<<0;
|
||||
return -1;
|
||||
}
|
||||
usb_write_packet(0, data, len);
|
||||
uint32_t dir = csr & UDP_CSR_DIR;
|
||||
UDP->UDP_CSR[0] = CSR_EP0 | dir | UDP_CSR_TXPKTRDY | other_irqs;
|
||||
return len;
|
||||
}
|
||||
|
||||
void
|
||||
usb_stall_ep0(void)
|
||||
{
|
||||
UDP->UDP_CSR[0] = CSR_EP0 | UDP_CSR_FORCESTALL;
|
||||
UDP->UDP_IER = 1<<0;
|
||||
}
|
||||
|
||||
static uint32_t set_address;
|
||||
|
||||
void
|
||||
usb_set_address(uint_fast8_t addr)
|
||||
{
|
||||
set_address = addr | UDP_FADDR_FEN;
|
||||
usb_send_ep0(NULL, 0);
|
||||
UDP->UDP_IER = 1<<0;
|
||||
}
|
||||
|
||||
void
|
||||
usb_set_configure(void)
|
||||
{
|
||||
UDP->UDP_CSR[USB_CDC_EP_ACM] = CSR_ACM;
|
||||
UDP->UDP_CSR[USB_CDC_EP_BULK_OUT] = CSR_BULK_OUT;
|
||||
UDP->UDP_CSR[USB_CDC_EP_BULK_IN] = CSR_BULK_IN;
|
||||
UDP->UDP_GLB_STAT |= UDP_GLB_STAT_CONFG;
|
||||
}
|
||||
|
||||
// Configure endpoint 0 after usb reset completes
|
||||
static void
|
||||
handle_end_reset(void)
|
||||
{
|
||||
UDP->UDP_ICR = UDP_ISR_ENDBUSRES;
|
||||
|
||||
UDP->UDP_CSR[0] = CSR_EP0;
|
||||
UDP->UDP_IER = 1<<0;
|
||||
|
||||
UDP->UDP_TXVC = UDP_TXVC_PUON;
|
||||
}
|
||||
|
||||
void
|
||||
UDP_Handler(void)
|
||||
{
|
||||
uint32_t s = UDP->UDP_ISR;
|
||||
UDP->UDP_IDR = s;
|
||||
if (s & UDP_ISR_ENDBUSRES)
|
||||
handle_end_reset();
|
||||
if (s & UDP_ISR_RXRSM)
|
||||
UDP->UDP_ICR = UDP_ISR_RXRSM;
|
||||
if (s & (1<<0)) {
|
||||
usb_notify_ep0();
|
||||
|
||||
if (set_address && UDP->UDP_CSR[0] & UDP_CSR_TXCOMP) {
|
||||
// Ack from set_address command sent - now update address
|
||||
UDP->UDP_FADDR = set_address;
|
||||
UDP->UDP_GLB_STAT |= UDP_GLB_STAT_FADDEN;
|
||||
set_address = 0;
|
||||
}
|
||||
}
|
||||
if (s & (1<<USB_CDC_EP_BULK_OUT))
|
||||
usb_notify_bulk_out();
|
||||
if (s & (1<<USB_CDC_EP_BULK_IN))
|
||||
usb_notify_bulk_in();
|
||||
}
|
||||
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_USB", "PB10,PB11");
|
||||
|
||||
void
|
||||
usbserial_init(void)
|
||||
{
|
||||
// Enable clocks
|
||||
enable_pclock(ID_UDP);
|
||||
PMC->PMC_USB = PMC_USB_USBDIV(5 - 1); // PLLA=240Mhz; divide by 5 for 48Mhz
|
||||
PMC->PMC_SCER = PMC_SCER_UDP;
|
||||
|
||||
// Enable USB pullup
|
||||
UDP->UDP_TXVC = UDP_TXVC_PUON | UDP_TXVC_TXVDIS;
|
||||
|
||||
// Enable interrupts
|
||||
UDP->UDP_ICR = 0xffffffff;
|
||||
armcm_enable_irq(UDP_Handler, UDP_IRQn, 1);
|
||||
}
|
||||
DECL_INIT(usbserial_init);
|
||||
241
src/atsam/sam4e_afec.c
Normal file
241
src/atsam/sam4e_afec.c
Normal file
@@ -0,0 +1,241 @@
|
||||
// SAM4e8e Analog Front-End Converter (AFEC) support
|
||||
//
|
||||
// Copyright (C) 2018 Florian Heilmann <Florian.Heilmann@gmx.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_CLOCK_FREQ
|
||||
#include "command.h" // shutdown
|
||||
#include "gpio.h" // gpio_adc_setup
|
||||
#include "internal.h" // GPIO, AFEC0
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
#if CONFIG_MACH_SAME70
|
||||
#include "same70_afec.h" // Fixes for upstream header changes
|
||||
#endif
|
||||
|
||||
#define ADC_TEMPERATURE_PIN 0xfe
|
||||
DECL_ENUMERATION("pin", "ADC_TEMPERATURE", ADC_TEMPERATURE_PIN);
|
||||
|
||||
static const uint8_t afec_pins[] = {
|
||||
//remove first channel, since it offsets the channel number: GPIO('A', 8),
|
||||
#if CONFIG_MACH_SAM4E
|
||||
GPIO('A', 17), GPIO('A', 18), GPIO('A', 19),
|
||||
GPIO('A', 20), GPIO('B', 0), GPIO('B', 1), GPIO('C', 13),
|
||||
GPIO('C', 15), GPIO('C', 12), GPIO('C', 29), GPIO('C', 30),
|
||||
GPIO('C', 31), GPIO('C', 26), GPIO('C', 27), GPIO('C',0),
|
||||
ADC_TEMPERATURE_PIN,
|
||||
// AFEC1
|
||||
GPIO('B', 2), GPIO('B', 3), GPIO('A', 21), GPIO('A', 22),
|
||||
GPIO('C', 1), GPIO('C', 2), GPIO('C', 3), GPIO('C', 4),
|
||||
#elif CONFIG_MACH_SAME70
|
||||
GPIO('D', 30), GPIO('A', 21), GPIO('B', 3), GPIO('E', 5),
|
||||
GPIO('E', 4), GPIO('B', 2), GPIO('A', 17), GPIO('A', 18),
|
||||
GPIO('A', 19), GPIO('A', 20), GPIO('B', 0),
|
||||
ADC_TEMPERATURE_PIN,
|
||||
// AFEC1
|
||||
GPIO('B', 1), GPIO('C', 13), GPIO('C', 15), GPIO('C', 12),
|
||||
GPIO('C', 29), GPIO('C', 30), GPIO('C', 31), GPIO('C', 26),
|
||||
GPIO('C', 27), GPIO('C', 0), GPIO('E', 3), GPIO('E', 0),
|
||||
#endif
|
||||
};
|
||||
|
||||
#if CONFIG_MACH_SAM4E
|
||||
#define AFEC1_START 16 // The first 16 pins are on afec0
|
||||
#define CFG_AFE_MR (AFE_MR_ANACH_ALLOWED | \
|
||||
AFE_MR_PRESCAL(pclk / (2 * ADC_FREQ_MAX) - 1) | \
|
||||
AFE_MR_SETTLING_AST3 | \
|
||||
AFE_MR_TRACKTIM(2) | \
|
||||
AFE_MR_TRANSFER(1) | \
|
||||
AFE_MR_STARTUP_SUT64)
|
||||
#define CFG_AFE_ACR AFE_ACR_IBCTL(1)
|
||||
#define CFG_AFE_IDR 0xDF00FFFF
|
||||
#define CFG_AFE_COCR (0x800 & AFE_COCR_AOFF_Msk)
|
||||
|
||||
#elif CONFIG_MACH_SAME70
|
||||
#define AFEC1_START 12 // The first 12 pins are on afec0
|
||||
#define CFG_AFE_MR (AFEC_MR_ONE | \
|
||||
AFE_MR_PRESCAL (pclk / (ADC_FREQ_MAX) -1) | \
|
||||
AFE_MR_TRANSFER(2) | \
|
||||
AFE_MR_STARTUP_SUT64)
|
||||
#define CFG_AFE_ACR (AFE_ACR_IBCTL(1) | AFEC_ACR_PGA0EN | AFEC_ACR_PGA1EN)
|
||||
#define CFG_AFE_IDR 0x47000FFF
|
||||
#define CFG_AFE_COCR (0x200 & AFE_COCR_AOFF_Msk)
|
||||
#endif
|
||||
|
||||
static inline struct gpio_adc
|
||||
pin_to_gpio_adc(uint8_t pin)
|
||||
{
|
||||
int chan;
|
||||
for (chan=0; ; chan++) {
|
||||
if (chan >= ARRAY_SIZE(afec_pins))
|
||||
shutdown("Not a valid ADC pin");
|
||||
if (afec_pins[chan] == pin) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
return (struct gpio_adc){ .chan=chan };
|
||||
}
|
||||
|
||||
static inline Afec *
|
||||
gpio_adc_to_afec(struct gpio_adc g)
|
||||
{
|
||||
return (g.chan >= AFEC1_START ? AFEC1 : AFEC0);
|
||||
}
|
||||
|
||||
static inline uint32_t
|
||||
gpio_adc_to_afec_chan(struct gpio_adc g)
|
||||
{
|
||||
return (g.chan >= AFEC1_START ? g.chan - AFEC1_START : g.chan);
|
||||
}
|
||||
|
||||
#define ADC_FREQ_MAX 6000000UL
|
||||
DECL_CONSTANT("ADC_MAX", 4095);
|
||||
|
||||
static int
|
||||
init_afec(Afec* afec) {
|
||||
|
||||
// Enable PMC
|
||||
enable_pclock(afec == AFEC0 ? ID_AFEC0 : ID_AFEC1);
|
||||
|
||||
// If busy, return busy
|
||||
if ((afec->AFE_ISR & AFE_ISR_DRDY) == AFE_ISR_DRDY) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Reset
|
||||
afec->AFE_CR = AFE_CR_SWRST;
|
||||
|
||||
// Configure afec
|
||||
uint32_t pclk = get_pclock_frequency(afec == AFEC0 ? ID_AFEC0 : ID_AFEC1);
|
||||
afec->AFE_MR = CFG_AFE_MR;
|
||||
afec->AFE_EMR = AFE_EMR_TAG | \
|
||||
AFE_EMR_RES_NO_AVERAGE | \
|
||||
AFE_EMR_STM;
|
||||
afec->AFE_ACR = CFG_AFE_ACR;
|
||||
|
||||
// Disable interrupts
|
||||
afec->AFE_IDR = CFG_AFE_IDR;
|
||||
|
||||
// Disable SW triggering
|
||||
uint32_t mr = afec->AFE_MR;
|
||||
|
||||
mr &= ~(AFE_MR_TRGSEL_Msk | AFE_MR_TRGEN | AFE_MR_FREERUN_ON);
|
||||
mr |= AFE_MR_TRGEN_DIS;
|
||||
afec->AFE_MR = mr;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void
|
||||
gpio_afec_init(void) {
|
||||
|
||||
while(init_afec(AFEC0) != 0) {
|
||||
(void)(AFEC0->AFE_LCDR & AFE_LCDR_LDATA_Msk);
|
||||
}
|
||||
while(init_afec(AFEC1) != 0) {
|
||||
(void)(AFEC1->AFE_LCDR & AFE_LCDR_LDATA_Msk);
|
||||
}
|
||||
|
||||
}
|
||||
DECL_INIT(gpio_afec_init);
|
||||
|
||||
struct gpio_adc
|
||||
gpio_adc_setup(uint8_t pin)
|
||||
{
|
||||
struct gpio_adc adc_pin = pin_to_gpio_adc(pin);
|
||||
Afec *afec = gpio_adc_to_afec(adc_pin);
|
||||
uint32_t afec_chan = gpio_adc_to_afec_chan(adc_pin);
|
||||
|
||||
//config channel
|
||||
uint32_t reg = afec->AFE_DIFFR;
|
||||
reg &= ~(1u << afec_chan);
|
||||
afec->AFE_DIFFR = reg;
|
||||
reg = afec->AFE_CGR;
|
||||
reg &= ~(0x03u << (2 * afec_chan));
|
||||
afec->AFE_CGR = reg;
|
||||
|
||||
// Configure channel
|
||||
// afec_ch_get_config_defaults(&ch_cfg);
|
||||
// afec_ch_set_config(afec, afec_chan, &ch_cfg);
|
||||
// Remove default internal offset from channel
|
||||
// See Atmel Appnote AT03078 Section 1.5 for SAM4E,
|
||||
// datasheet section 52.6.11 for SAME70
|
||||
afec->AFE_CSELR = afec_chan;
|
||||
afec->AFE_COCR = CFG_AFE_COCR;
|
||||
|
||||
// Enable and calibrate Channel
|
||||
afec->AFE_CHER = 1 << afec_chan;
|
||||
|
||||
#if CONFIG_MACH_SAM4E
|
||||
reg = afec->AFE_CHSR;
|
||||
afec->AFE_CDOR = reg;
|
||||
afec->AFE_CR = AFE_CR_AUTOCAL;
|
||||
#endif
|
||||
|
||||
return adc_pin;
|
||||
}
|
||||
|
||||
enum { AFE_DUMMY=0xff };
|
||||
uint8_t active_channel = AFE_DUMMY;
|
||||
|
||||
// Try to sample a value. Returns zero if sample ready, otherwise
|
||||
// returns the number of clock ticks the caller should wait before
|
||||
// retrying this function.
|
||||
uint32_t
|
||||
gpio_adc_sample(struct gpio_adc g)
|
||||
{
|
||||
Afec *afec = gpio_adc_to_afec(g);
|
||||
uint32_t afec_chan = gpio_adc_to_afec_chan(g);
|
||||
if (active_channel == g.chan) {
|
||||
if ((afec->AFE_ISR & AFE_ISR_DRDY)
|
||||
&& (afec->AFE_ISR & (1 << afec_chan))) {
|
||||
// Sample now ready
|
||||
return 0;
|
||||
} else {
|
||||
// Busy
|
||||
goto need_delay;
|
||||
}
|
||||
} else if (active_channel != AFE_DUMMY) {
|
||||
goto need_delay;
|
||||
}
|
||||
|
||||
afec->AFE_CHDR = 0x803F; // Disable all channels
|
||||
afec->AFE_CHER = 1 << afec_chan;
|
||||
|
||||
active_channel = g.chan;
|
||||
|
||||
for (uint32_t chan = 0; chan < 16; ++chan)
|
||||
{
|
||||
if ((afec->AFE_ISR & (1 << chan)) != 0)
|
||||
{
|
||||
afec->AFE_CSELR = chan;
|
||||
(void)(afec->AFE_CDR);
|
||||
}
|
||||
}
|
||||
afec->AFE_CR = AFE_CR_START;
|
||||
|
||||
need_delay:
|
||||
// about 400 mcu clock cycles or 40 afec cycles
|
||||
return ADC_FREQ_MAX * 10000ULL / CONFIG_CLOCK_FREQ;
|
||||
}
|
||||
|
||||
// Read a value; use only after gpio_adc_sample() returns zero
|
||||
uint16_t
|
||||
gpio_adc_read(struct gpio_adc g)
|
||||
{
|
||||
Afec *afec = gpio_adc_to_afec(g);
|
||||
uint32_t afec_chan = gpio_adc_to_afec_chan(g);
|
||||
active_channel = AFE_DUMMY;
|
||||
afec->AFE_CSELR = afec_chan;
|
||||
return afec->AFE_CDR;
|
||||
}
|
||||
|
||||
// Cancel a sample that may have been started with gpio_adc_sample()
|
||||
void
|
||||
gpio_adc_cancel_sample(struct gpio_adc g)
|
||||
{
|
||||
if (active_channel == g.chan) {
|
||||
active_channel = AFE_DUMMY;
|
||||
}
|
||||
}
|
||||
71
src/atsam/sam4s_sysinit.c
Normal file
71
src/atsam/sam4s_sysinit.c
Normal file
@@ -0,0 +1,71 @@
|
||||
// This code is from lib/sam4e/gcc/system_sam4e.c - it is unclear why
|
||||
// it is not defined in the Atmel sam4s cmsis code.
|
||||
|
||||
#include "internal.h"
|
||||
|
||||
/* Clock Settings (120MHz) */
|
||||
#define SYS_BOARD_OSCOUNT (CKGR_MOR_MOSCXTST(0x8U))
|
||||
#define SYS_BOARD_PLLAR (CKGR_PLLAR_ONE \
|
||||
| CKGR_PLLAR_MULA(0x13U) \
|
||||
| CKGR_PLLAR_PLLACOUNT(0x3fU) \
|
||||
| CKGR_PLLAR_DIVA(0x1U))
|
||||
#define SYS_BOARD_MCKR (PMC_MCKR_PRES_CLK_2 | PMC_MCKR_CSS_PLLA_CLK)
|
||||
|
||||
/* Key to unlock MOR register */
|
||||
#define SYS_CKGR_MOR_KEY_VALUE CKGR_MOR_KEY(0x37)
|
||||
|
||||
uint32_t SystemCoreClock = CHIP_FREQ_MAINCK_RC_4MHZ;
|
||||
|
||||
void SystemInit( void )
|
||||
{
|
||||
/* Set FWS according to SYS_BOARD_MCKR configuration */
|
||||
EFC0->EEFC_FMR = EEFC_FMR_FWS(5) | EEFC_FMR_CLOE;
|
||||
|
||||
/* Initialize main oscillator */
|
||||
if ( !(PMC->CKGR_MOR & CKGR_MOR_MOSCSEL) )
|
||||
{
|
||||
PMC->CKGR_MOR = (SYS_CKGR_MOR_KEY_VALUE | SYS_BOARD_OSCOUNT
|
||||
| CKGR_MOR_MOSCRCEN | CKGR_MOR_MOSCXTEN);
|
||||
|
||||
while ( !(PMC->PMC_SR & PMC_SR_MOSCXTS) )
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
/* Switch to 3-20MHz Xtal oscillator */
|
||||
PMC->CKGR_MOR = (SYS_CKGR_MOR_KEY_VALUE | SYS_BOARD_OSCOUNT
|
||||
| CKGR_MOR_MOSCRCEN | CKGR_MOR_MOSCXTEN
|
||||
| CKGR_MOR_MOSCSEL);
|
||||
|
||||
while ( !(PMC->PMC_SR & PMC_SR_MOSCSELS) )
|
||||
{
|
||||
}
|
||||
|
||||
PMC->PMC_MCKR = ((PMC->PMC_MCKR & ~(uint32_t)PMC_MCKR_CSS_Msk)
|
||||
| PMC_MCKR_CSS_MAIN_CLK);
|
||||
|
||||
while ( !(PMC->PMC_SR & PMC_SR_MCKRDY) )
|
||||
{
|
||||
}
|
||||
|
||||
/* Initialize PLLA */
|
||||
PMC->CKGR_PLLAR = SYS_BOARD_PLLAR;
|
||||
while ( !(PMC->PMC_SR & PMC_SR_LOCKA) )
|
||||
{
|
||||
}
|
||||
|
||||
/* Switch to main clock */
|
||||
PMC->PMC_MCKR = ((SYS_BOARD_MCKR & ~PMC_MCKR_CSS_Msk)
|
||||
| PMC_MCKR_CSS_MAIN_CLK);
|
||||
while ( !(PMC->PMC_SR & PMC_SR_MCKRDY) )
|
||||
{
|
||||
}
|
||||
|
||||
/* Switch to PLLA */
|
||||
PMC->PMC_MCKR = SYS_BOARD_MCKR;
|
||||
while ( !(PMC->PMC_SR & PMC_SR_MCKRDY) )
|
||||
{
|
||||
}
|
||||
|
||||
SystemCoreClock = CHIP_FREQ_CPU_MAX;
|
||||
}
|
||||
38
src/atsam/same70_afec.h
Normal file
38
src/atsam/same70_afec.h
Normal file
@@ -0,0 +1,38 @@
|
||||
#ifndef __SAME70_AFEC_H
|
||||
#define __SAME70_AFEC_H
|
||||
|
||||
// A series of redefinitions as upstream changed the name of the peripheral
|
||||
#define AFE_ACR AFEC_ACR
|
||||
#define AFE_ACR_IBCTL AFEC_ACR_IBCTL
|
||||
#define AFE_CDR AFEC_CDR
|
||||
#define AFE_CGR AFEC_CGR
|
||||
#define AFE_CHDR AFEC_CHDR
|
||||
#define AFE_CHER AFEC_CHER
|
||||
#define AFE_COCR AFEC_COCR
|
||||
#define AFE_COCR_AOFF_Msk AFEC_COCR_AOFF_Msk
|
||||
#define AFE_CR AFEC_CR
|
||||
#define AFE_CR_START AFEC_CR_START
|
||||
#define AFE_CR_SWRST AFEC_CR_SWRST
|
||||
#define AFE_DIFFR AFEC_DIFFR
|
||||
#define AFE_DUMMY AFEC_DUMMY
|
||||
#define AFE_EMR AFEC_EMR
|
||||
#define AFE_EMR_RES_NO_AVERAGE AFEC_EMR_RES_NO_AVERAGE
|
||||
#define AFE_EMR_STM AFEC_EMR_STM
|
||||
#define AFE_EMR_TAG AFEC_EMR_TAG
|
||||
#define AFE_IDR AFEC_IDR
|
||||
#define AFE_ISR AFEC_ISR
|
||||
#define AFE_LCDR AFEC_LCDR
|
||||
#define AFE_LCDR_LDATA_Msk AFEC_LCDR_LDATA_Msk
|
||||
#define AFE_MR_FREERUN_ON AFEC_MR_FREERUN_ON
|
||||
#define AFE_MR_PRESCAL AFEC_MR_PRESCAL
|
||||
#define AFE_MR_STARTUP_SUT64 AFEC_MR_STARTUP_SUT64
|
||||
#define AFE_MR_TRANSFER AFEC_MR_TRANSFER
|
||||
#define AFE_MR_TRGEN AFEC_MR_TRGEN
|
||||
#define AFE_MR_TRGEN_DIS AFEC_MR_TRGEN_DIS
|
||||
#define AFE_MR_TRGSEL_Msk AFEC_MR_TRGSEL_Msk
|
||||
#define AFE_ISR_DRDY AFEC_ISR_DRDY
|
||||
#define AFE_MR AFEC_MR
|
||||
#define AFE_CSELR AFEC_CSELR
|
||||
#define AFE_CHSR AFEC_CHSR
|
||||
|
||||
#endif // same70_afec.h
|
||||
33
src/atsam/same70_i2c.h
Normal file
33
src/atsam/same70_i2c.h
Normal file
@@ -0,0 +1,33 @@
|
||||
#ifndef __SAME70_I2C_H
|
||||
#define __SAME70_I2C_H
|
||||
|
||||
// A series of redefinitions as upstream changed the name of the peripheral
|
||||
#define Twi Twihs
|
||||
#define TWI_CR TWIHS_CR
|
||||
#define TWI_CR_MSDIS TWIHS_CR_MSDIS
|
||||
#define TWI_CR_MSEN TWIHS_CR_MSEN
|
||||
#define TWI_CR_START TWIHS_CR_START
|
||||
#define TWI_CR_STOP TWIHS_CR_STOP
|
||||
#define TWI_CR_SVDIS TWIHS_CR_SVDIS
|
||||
#define TWI_CR_SWRST TWIHS_CR_SWRST
|
||||
#define TWI_CWGR TWIHS_CWGR
|
||||
#define TWI_CWGR_CHDIV TWIHS_CWGR_CHDIV
|
||||
#define TWI_CWGR_CKDIV TWIHS_CWGR_CKDIV
|
||||
#define TWI_CWGR_CLDIV TWIHS_CWGR_CLDIV
|
||||
#define TWI_IADR TWIHS_IADR
|
||||
#define TWI_IDR TWIHS_IDR
|
||||
#define TWI_MMR TWIHS_MMR
|
||||
#define TWI_MMR_DADR TWIHS_MMR_DADR
|
||||
#define TWI_MMR_IADRSZ_Msk TWIHS_MMR_IADRSZ_Msk
|
||||
#define TWI_MMR_IADRSZ_Pos TWIHS_MMR_IADRSZ_Pos
|
||||
#define TWI_MMR_MREAD TWIHS_MMR_MREAD
|
||||
#define TWI_RHR TWIHS_RHR
|
||||
#define TWI_SR TWIHS_SR
|
||||
#define TWI_SR_NAC TWIHS_SR_NACK
|
||||
#define TWI_SR_NACK TWIHS_SR_NACK
|
||||
#define TWI_SR_RXRDY TWIHS_SR_RXRDY
|
||||
#define TWI_SR_TXCOMP TWIHS_SR_TXCOMP
|
||||
#define TWI_SR_TXRDY TWIHS_SR_TXRDY
|
||||
#define TWI_THR TWIHS_THR
|
||||
|
||||
#endif // same70_i2c.h
|
||||
74
src/atsam/same70_sysinit.c
Normal file
74
src/atsam/same70_sysinit.c
Normal file
@@ -0,0 +1,74 @@
|
||||
// This code is from lib/sam4e/gcc/system_sam4e.c and modified for the SAM E70
|
||||
|
||||
#include "internal.h"
|
||||
|
||||
/* Clock Settings (300MHz) */
|
||||
#define SYS_BOARD_OSCOUNT (CKGR_MOR_MOSCXTST(0x8U))
|
||||
#define SYS_BOARD_PLLAR (CKGR_PLLAR_ONE \
|
||||
| CKGR_PLLAR_MULA(0x18U) \
|
||||
| CKGR_PLLAR_PLLACOUNT(0x3fU) \
|
||||
| CKGR_PLLAR_DIVA_BYPASS)
|
||||
#define SYS_BOARD_MCKR (PMC_MCKR_MDIV_PCK_DIV2 | PMC_MCKR_CSS_PLLA_CLK)
|
||||
|
||||
/* Key to unlock MOR register */
|
||||
#define SYS_CKGR_MOR_KEY_VALUE CKGR_MOR_KEY(0x37)
|
||||
|
||||
uint32_t SystemCoreClock = CHIP_FREQ_MAINCK_RC_12MHZ;
|
||||
|
||||
void SystemInit( void )
|
||||
{
|
||||
/* Set FWS according to SYS_BOARD_MCKR configuration */
|
||||
EFC->EEFC_FMR = EEFC_FMR_FWS(6) | EEFC_FMR_CLOE;
|
||||
|
||||
/* Initialize main oscillator */
|
||||
if ( !(PMC->CKGR_MOR & CKGR_MOR_MOSCSEL) )
|
||||
{
|
||||
PMC->CKGR_MOR = (SYS_CKGR_MOR_KEY_VALUE | SYS_BOARD_OSCOUNT
|
||||
| CKGR_MOR_MOSCRCEN | CKGR_MOR_MOSCXTEN);
|
||||
|
||||
while ( !(PMC->PMC_SR & PMC_SR_MOSCXTS) )
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
/* Switch to 3-20MHz Xtal oscillator */
|
||||
PMC->CKGR_MOR = (SYS_CKGR_MOR_KEY_VALUE | SYS_BOARD_OSCOUNT
|
||||
| CKGR_MOR_MOSCRCEN | CKGR_MOR_MOSCXTEN
|
||||
| CKGR_MOR_MOSCSEL);
|
||||
|
||||
while ( !(PMC->PMC_SR & PMC_SR_MOSCSELS) )
|
||||
{
|
||||
}
|
||||
|
||||
PMC->PMC_MCKR = ((PMC->PMC_MCKR & ~(uint32_t)PMC_MCKR_CSS_Msk)
|
||||
| PMC_MCKR_CSS_MAIN_CLK);
|
||||
|
||||
while ( !(PMC->PMC_SR & PMC_SR_MCKRDY) )
|
||||
{
|
||||
}
|
||||
|
||||
/* Initialize PLLA */
|
||||
PMC->CKGR_PLLAR = SYS_BOARD_PLLAR;
|
||||
while ( !(PMC->PMC_SR & PMC_SR_LOCKA) )
|
||||
{
|
||||
}
|
||||
|
||||
/* Switch to main clock */
|
||||
PMC->PMC_MCKR = ((SYS_BOARD_MCKR & ~PMC_MCKR_CSS_Msk)
|
||||
| PMC_MCKR_CSS_MAIN_CLK);
|
||||
while ( !(PMC->PMC_SR & PMC_SR_MCKRDY) )
|
||||
{
|
||||
}
|
||||
|
||||
/* Switch to PLLA */
|
||||
PMC->PMC_MCKR = SYS_BOARD_MCKR;
|
||||
while ( !(PMC->PMC_SR & PMC_SR_MCKRDY) )
|
||||
{
|
||||
}
|
||||
|
||||
SystemCoreClock = CHIP_FREQ_CPU_MAX;
|
||||
|
||||
// Configure PCK6 for TC use
|
||||
PMC->PMC_PCK[6] = PMC_PCK_CSS_MCK | PMC_PCK_PRES(2);
|
||||
PMC->PMC_SCER = PMC_SCER_PCK6;
|
||||
}
|
||||
61
src/atsam/same70_usb.h
Normal file
61
src/atsam/same70_usb.h
Normal file
@@ -0,0 +1,61 @@
|
||||
#ifndef __SAME70_USB_H
|
||||
#define __SAME70_USB_H
|
||||
|
||||
// Missing in upstream headers
|
||||
#define USBHS_RAM_ADDR 0xa0100000u
|
||||
|
||||
// A series of redefinitions as upstream changed the name of the peripheral
|
||||
#define UOTGHS USBHS
|
||||
#define UOTGHS_RAM_ADDR USBHS_RAM_ADDR
|
||||
#define ID_UOTGHS ID_USBHS
|
||||
#define UOTGHS_IRQn USBHS_IRQn
|
||||
#define UOTGHS_CTRL USBHS_CTRL
|
||||
#define UOTGHS_CTRL_UIMOD USBHS_CTRL_UIMOD
|
||||
#define UOTGHS_CTRL_USBE USBHS_CTRL_USBE
|
||||
#define UOTGHS_DEVCTRL USBHS_DEVCTRL
|
||||
#define UOTGHS_DEVCTRL_ADDEN USBHS_DEVCTRL_ADDEN
|
||||
#define UOTGHS_DEVCTRL_SPDCONF_FORCED_FS USBHS_DEVCTRL_SPDCONF_FORCED_FS
|
||||
#define UOTGHS_DEVEPT USBHS_DEVEPT
|
||||
#define UOTGHS_DEVEPT_EPEN0 USBHS_DEVEPT_EPEN0
|
||||
#define UOTGHS_DEVEPTCFG USBHS_DEVEPTCFG
|
||||
#define UOTGHS_DEVEPTCFG_ALLOC USBHS_DEVEPTCFG_ALLOC
|
||||
#define UOTGHS_DEVEPTCFG_EPBK_1_BANK USBHS_DEVEPTCFG_EPBK_1_BANK
|
||||
#define UOTGHS_DEVEPTCFG_EPBK_2_BANK USBHS_DEVEPTCFG_EPBK_2_BANK
|
||||
#define UOTGHS_DEVEPTCFG_EPDIR_IN USBHS_DEVEPTCFG_EPDIR_IN
|
||||
#define UOTGHS_DEVEPTCFG_EPSIZE_8_BYTE USBHS_DEVEPTCFG_EPSIZE_8_BYTE
|
||||
#define UOTGHS_DEVEPTCFG_EPSIZE_16_BYTE USBHS_DEVEPTCFG_EPSIZE_16_BYTE
|
||||
#define UOTGHS_DEVEPTCFG_EPSIZE_32_BYTE USBHS_DEVEPTCFG_EPSIZE_32_BYTE
|
||||
#define UOTGHS_DEVEPTCFG_EPSIZE_64_BYTE USBHS_DEVEPTCFG_EPSIZE_64_BYTE
|
||||
#define UOTGHS_DEVEPTCFG_EPTYPE_BLK USBHS_DEVEPTCFG_EPTYPE_BLK
|
||||
#define UOTGHS_DEVEPTCFG_EPTYPE_CTRL USBHS_DEVEPTCFG_EPTYPE_CTRL
|
||||
#define UOTGHS_DEVEPTCFG_EPTYPE_INTRPT USBHS_DEVEPTCFG_EPTYPE_INTRPT
|
||||
#define UOTGHS_DEVEPTICR USBHS_DEVEPTICR
|
||||
#define UOTGHS_DEVEPTICR_RXOUTIC USBHS_DEVEPTICR_RXOUTIC
|
||||
#define UOTGHS_DEVEPTICR_RXSTPIC USBHS_DEVEPTICR_RXSTPIC
|
||||
#define UOTGHS_DEVEPTICR_TXINIC USBHS_DEVEPTICR_TXINIC
|
||||
#define UOTGHS_DEVEPTIDR USBHS_DEVEPTIDR
|
||||
#define UOTGHS_DEVEPTIDR_FIFOCONC USBHS_DEVEPTIDR_FIFOCONC
|
||||
#define UOTGHS_DEVEPTIDR_RXOUTEC USBHS_DEVEPTIDR_RXOUTEC
|
||||
#define UOTGHS_DEVEPTIDR_TXINEC USBHS_DEVEPTIDR_TXINEC
|
||||
#define UOTGHS_DEVEPTIER USBHS_DEVEPTIER
|
||||
#define UOTGHS_DEVEPTIER_RXOUTES USBHS_DEVEPTIER_RXOUTES
|
||||
#define UOTGHS_DEVEPTIER_RXSTPES USBHS_DEVEPTIER_RXSTPES
|
||||
#define UOTGHS_DEVEPTIER_STALLRQS USBHS_DEVEPTIER_STALLRQS
|
||||
#define UOTGHS_DEVEPTIER_TXINES USBHS_DEVEPTIER_TXINES
|
||||
#define UOTGHS_DEVEPTISR USBHS_DEVEPTISR
|
||||
#define UOTGHS_DEVEPTISR_BYCT_Msk USBHS_DEVEPTISR_BYCT_Msk
|
||||
#define UOTGHS_DEVEPTISR_BYCT_Pos USBHS_DEVEPTISR_BYCT_Pos
|
||||
#define UOTGHS_DEVEPTISR_RXOUTI USBHS_DEVEPTISR_RXOUTI
|
||||
#define UOTGHS_DEVEPTISR_RXSTPI USBHS_DEVEPTISR_RXSTPI
|
||||
#define UOTGHS_DEVEPTISR_TXINI USBHS_DEVEPTISR_TXINI
|
||||
#define UOTGHS_DEVICR USBHS_DEVICR
|
||||
#define UOTGHS_DEVICR_EORSTC USBHS_DEVICR_EORSTC
|
||||
#define UOTGHS_DEVIDR USBHS_DEVIDR
|
||||
#define UOTGHS_DEVIER USBHS_DEVIER
|
||||
#define UOTGHS_DEVIER_EORSTES USBHS_DEVIER_EORSTES
|
||||
#define UOTGHS_DEVIER_PEP_0 USBHS_DEVIER_PEP_0
|
||||
#define UOTGHS_DEVISR USBHS_DEVISR
|
||||
#define UOTGHS_DEVISR_EORST USBHS_DEVISR_EORST
|
||||
#define UOTGHS_DEVISR_PEP_0 USBHS_DEVISR_PEP_0
|
||||
|
||||
#endif // same70_usb.h
|
||||
86
src/atsam/serial.c
Normal file
86
src/atsam/serial.c
Normal file
@@ -0,0 +1,86 @@
|
||||
// sam3/sam4 serial port
|
||||
//
|
||||
// Copyright (C) 2016-2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_SERIAL_BAUD
|
||||
#include "board/armcm_boot.h" // armcm_enable_irq
|
||||
#include "board/serial_irq.h" // serial_rx_data
|
||||
#include "command.h" // DECL_CONSTANT_STR
|
||||
#include "internal.h" // gpio_peripheral
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
// Serial port pins
|
||||
#if CONFIG_MACH_SAM3X
|
||||
#define UARTx_IRQn UART_IRQn
|
||||
static Uart * const Port = UART;
|
||||
static const uint32_t Pmc_id = ID_UART;
|
||||
static const uint32_t rx_pin = GPIO('A', 8), tx_pin = GPIO('A', 9);
|
||||
static const char uart_periph = 'A';
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PA8,PA9");
|
||||
#elif CONFIG_MACH_SAM4S
|
||||
#define UARTx_IRQn UART1_IRQn
|
||||
static Uart * const Port = UART1;
|
||||
static const uint32_t Pmc_id = ID_UART1;
|
||||
static const uint32_t rx_pin = GPIO('B', 2), tx_pin = GPIO('B', 3);
|
||||
static const char uart_periph = 'A';
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PB2,PB3");
|
||||
#elif CONFIG_MACH_SAM4E
|
||||
#define UARTx_IRQn UART0_IRQn
|
||||
static Uart * const Port = UART0;
|
||||
static const uint32_t Pmc_id = ID_UART0;
|
||||
static const uint32_t rx_pin = GPIO('A', 9), tx_pin = GPIO('A', 10);
|
||||
static const char uart_periph = 'A';
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PA9,PA10");
|
||||
#elif CONFIG_MACH_SAME70
|
||||
#define UARTx_IRQn UART2_IRQn
|
||||
static Uart * const Port = UART2;
|
||||
static const uint32_t Pmc_id = ID_UART2;
|
||||
static const uint32_t rx_pin = GPIO('D', 25), tx_pin = GPIO('D', 26);
|
||||
static const char uart_periph = 'C';
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PD25,PD26");
|
||||
#endif
|
||||
|
||||
void
|
||||
UARTx_Handler(void)
|
||||
{
|
||||
uint32_t status = Port->UART_SR;
|
||||
if (status & UART_SR_RXRDY)
|
||||
serial_rx_byte(Port->UART_RHR);
|
||||
if (status & UART_SR_TXRDY) {
|
||||
uint8_t data;
|
||||
int ret = serial_get_tx_byte(&data);
|
||||
if (ret)
|
||||
Port->UART_IDR = UART_IDR_TXRDY;
|
||||
else
|
||||
Port->UART_THR = data;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
serial_enable_tx_irq(void)
|
||||
{
|
||||
Port->UART_IER = UART_IDR_TXRDY;
|
||||
}
|
||||
|
||||
void
|
||||
serial_init(void)
|
||||
{
|
||||
gpio_peripheral(rx_pin, uart_periph, 1);
|
||||
gpio_peripheral(tx_pin, uart_periph, 0);
|
||||
|
||||
// Reset uart
|
||||
enable_pclock(Pmc_id);
|
||||
Port->UART_CR = (UART_CR_RSTRX | UART_CR_RSTTX
|
||||
| UART_CR_RXDIS | UART_CR_TXDIS);
|
||||
Port->UART_IDR = 0xFFFFFFFF;
|
||||
|
||||
// Enable uart
|
||||
Port->UART_MR = (UART_MR_PAR_NO | UART_MR_CHMODE_NORMAL);
|
||||
Port->UART_BRGR = get_pclock_frequency(Pmc_id) / (16 * CONFIG_SERIAL_BAUD);
|
||||
Port->UART_IER = UART_IER_RXRDY;
|
||||
armcm_enable_irq(UARTx_Handler, UARTx_IRQn, 0);
|
||||
Port->UART_CR = UART_CR_RXEN | UART_CR_TXEN;
|
||||
}
|
||||
DECL_INIT(serial_init);
|
||||
341
src/atsam/spi.c
Normal file
341
src/atsam/spi.c
Normal file
@@ -0,0 +1,341 @@
|
||||
// SPI transmissions on sam3
|
||||
//
|
||||
// Copyright (C) 2018 Petri Honkala <cruwaller@gmail.com>
|
||||
// Copyright (C) 2018 Florian Heilmann <Florian.Heilmann@gmx.net>
|
||||
// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "command.h" // shutdown
|
||||
#include "gpio.h" // spi_setup
|
||||
#include "internal.h" // gpio_peripheral
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
#if CONFIG_MACH_SAME70 // Fixes for upstream header changes
|
||||
#define US_MR_CHMODE_NORMAL US_MR_USART_CHMODE_NORMAL
|
||||
#define US_MR_CPHA US_MR_SPI_CPHA
|
||||
#define US_MR_CPOL US_MR_SPI_CPOL
|
||||
#endif
|
||||
|
||||
/****************************************************************
|
||||
* SPI/USART buses and pins
|
||||
****************************************************************/
|
||||
|
||||
struct spi_info {
|
||||
void *dev;
|
||||
uint32_t dev_id;
|
||||
uint8_t miso_pin, mosi_pin, sck_pin, rx_periph, tx_periph, sck_periph;
|
||||
};
|
||||
|
||||
#if CONFIG_MACH_SAM3X
|
||||
DECL_ENUMERATION("spi_bus", "spi0", 0);
|
||||
DECL_ENUMERATION_RANGE("spi_bus", "usart0", 1, 3);
|
||||
DECL_CONSTANT_STR("BUS_PINS_spi0", "PA25,PA26,PA27");
|
||||
DECL_CONSTANT_STR("BUS_PINS_usart0", "PA10,PA11,PA17");
|
||||
DECL_CONSTANT_STR("BUS_PINS_usart1", "PA12,PA13,PA16");
|
||||
DECL_CONSTANT_STR("BUS_PINS_usart2", "PB21,PB20,PB24");
|
||||
#elif CONFIG_MACH_SAM4S
|
||||
DECL_ENUMERATION("spi_bus", "spi", 0);
|
||||
DECL_ENUMERATION_RANGE("spi_bus", "usart0", 1, 2);
|
||||
DECL_CONSTANT_STR("BUS_PINS_spi", "PA12,PA13,PA14");
|
||||
DECL_CONSTANT_STR("BUS_PINS_usart0", "PA5,PA6,PA2");
|
||||
DECL_CONSTANT_STR("BUS_PINS_usart1", "PA21,PA22,PA23");
|
||||
#elif CONFIG_MACH_SAM4E
|
||||
DECL_ENUMERATION("spi_bus", "spi", 0);
|
||||
DECL_ENUMERATION_RANGE("spi_bus", "usart0", 1, 2);
|
||||
DECL_CONSTANT_STR("BUS_PINS_spi", "PA12,PA13,PA14");
|
||||
DECL_CONSTANT_STR("BUS_PINS_usart0", "PB0,PB1,PB13");
|
||||
DECL_CONSTANT_STR("BUS_PINS_usart1", "PA21,PA22,PA23");
|
||||
#elif CONFIG_MACH_SAME70
|
||||
DECL_ENUMERATION_RANGE("spi_bus", "spi0", 0, 2);
|
||||
DECL_ENUMERATION_RANGE("spi_bus", "usart0", 2, 3);
|
||||
DECL_CONSTANT_STR("BUS_PINS_spi0", "PD20,PD21,PD22");
|
||||
DECL_CONSTANT_STR("BUS_PINS_usart0", "PB0,PB1,PB13");
|
||||
DECL_CONSTANT_STR("BUS_PINS_usart1", "PA21,PB4,PA23");
|
||||
DECL_CONSTANT_STR("BUS_PINS_usart2", "PD15,PD16,PD17");
|
||||
#endif
|
||||
|
||||
static const struct spi_info spi_bus[] = {
|
||||
#if CONFIG_MACH_SAM3X
|
||||
{ SPI0, ID_SPI0,
|
||||
GPIO('A', 25), GPIO('A', 26), GPIO('A', 27), 'A', 'A', 'A'},
|
||||
{ USART0, ID_USART0,
|
||||
GPIO('A', 10), GPIO('A', 11), GPIO('A', 17), 'A', 'A', 'B'},
|
||||
{ USART1, ID_USART1,
|
||||
GPIO('A', 12), GPIO('A', 13), GPIO('A', 16), 'A', 'A', 'A'},
|
||||
{ USART2, ID_USART2,
|
||||
GPIO('B', 21), GPIO('B', 20), GPIO('B', 24), 'A', 'A', 'A'},
|
||||
#elif CONFIG_MACH_SAM4S
|
||||
{ SPI, ID_SPI,
|
||||
GPIO('A', 12), GPIO('A', 13), GPIO('A', 14), 'A', 'A', 'A'},
|
||||
{ USART0, ID_USART0,
|
||||
GPIO('A', 5), GPIO('A', 6), GPIO('A', 2), 'A', 'A', 'B'},
|
||||
{ USART1, ID_USART1,
|
||||
GPIO('A', 21), GPIO('A', 22), GPIO('A', 23), 'A', 'A', 'A'},
|
||||
#elif CONFIG_MACH_SAM4E
|
||||
{ SPI, ID_SPI,
|
||||
GPIO('A', 12), GPIO('A', 13), GPIO('A', 14), 'A', 'A', 'A'},
|
||||
{ USART0, ID_USART0,
|
||||
GPIO('B', 0), GPIO('B', 1), GPIO('B', 13), 'C', 'C', 'C'},
|
||||
{ USART1, ID_USART1,
|
||||
GPIO('A', 21), GPIO('A', 22), GPIO('A', 23), 'A', 'A', 'A'},
|
||||
#elif CONFIG_MACH_SAME70
|
||||
{ SPI0, ID_SPI0,
|
||||
GPIO('D', 20), GPIO('D', 21), GPIO('D', 22), 'B', 'B', 'B'},
|
||||
{ SPI1, ID_SPI1,
|
||||
GPIO('C', 26), GPIO('C', 27), GPIO('C', 24), 'C', 'C', 'C'},
|
||||
{ USART0, ID_USART0,
|
||||
GPIO('B', 0), GPIO('B', 1), GPIO('B', 13), 'C', 'C', 'C'},
|
||||
{ USART1, ID_USART1,
|
||||
GPIO('A', 21), GPIO('B', 4), GPIO('A', 23), 'A', 'D', 'A'},
|
||||
{ USART2, ID_USART2,
|
||||
GPIO('D', 15), GPIO('D', 16), GPIO('D', 17), 'B', 'B', 'B'},
|
||||
#endif
|
||||
};
|
||||
|
||||
static int
|
||||
is_spihw(void *dev)
|
||||
{
|
||||
#if CONFIG_MACH_SAM3X
|
||||
return dev == SPI0;
|
||||
#elif CONFIG_MACH_SAME70
|
||||
return (dev == SPI0) || (dev == SPI1);
|
||||
#else
|
||||
return dev == SPI;
|
||||
#endif
|
||||
}
|
||||
|
||||
static void
|
||||
init_pins(uint32_t bus)
|
||||
{
|
||||
const struct spi_info *si = &spi_bus[bus];
|
||||
gpio_peripheral(si->sck_pin, si->sck_periph, 0);
|
||||
gpio_peripheral(si->miso_pin, si->rx_periph, 1);
|
||||
gpio_peripheral(si->mosi_pin, si->tx_periph, 0);
|
||||
enable_pclock(si->dev_id);
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* SPI hardware
|
||||
****************************************************************/
|
||||
|
||||
#define CHANNEL 0 // Use same channel for all
|
||||
|
||||
static void
|
||||
spihw_init(uint32_t bus)
|
||||
{
|
||||
init_pins(bus);
|
||||
Spi *pSpi = spi_bus[bus].dev;
|
||||
|
||||
/* Disable SPI */
|
||||
pSpi->SPI_CR = SPI_CR_SPIDIS;
|
||||
/* Execute a software reset of the SPI twice */
|
||||
pSpi->SPI_CR = SPI_CR_SWRST;
|
||||
pSpi->SPI_CR = SPI_CR_SWRST;
|
||||
|
||||
pSpi->SPI_MR = ( SPI_MR_MSTR | // Set master mode
|
||||
SPI_MR_MODFDIS | // Disable fault detection
|
||||
SPI_MR_PCS(CHANNEL) // Fixes peripheral select
|
||||
);
|
||||
pSpi->SPI_IDR = 0xffffffff; // Disable ISRs
|
||||
|
||||
/* Clear Chip Select Registers */
|
||||
pSpi->SPI_CSR[0] = 0;
|
||||
pSpi->SPI_CSR[1] = 0;
|
||||
pSpi->SPI_CSR[2] = 0;
|
||||
pSpi->SPI_CSR[3] = 0;
|
||||
|
||||
/* Set basic channel config */
|
||||
pSpi->SPI_CSR[CHANNEL] = 0;
|
||||
/* Enable SPI */
|
||||
pSpi->SPI_CR = SPI_CR_SPIEN;
|
||||
}
|
||||
|
||||
static struct spi_config
|
||||
spihw_setup(uint32_t bus, uint8_t mode, uint32_t rate)
|
||||
{
|
||||
// Make sure bus is enabled
|
||||
spihw_init(bus);
|
||||
|
||||
uint32_t clockDiv, pclk = get_pclock_frequency(ID_USART0);
|
||||
if (rate < pclk / 255) {
|
||||
clockDiv = 255;
|
||||
} else if (rate >= pclk / 2) {
|
||||
clockDiv = 2;
|
||||
} else {
|
||||
clockDiv = pclk / (rate + 1) + 1;
|
||||
}
|
||||
|
||||
/****** Will be written to SPI_CSRx register ******/
|
||||
// CSAAT : Chip Select Active After Transfer
|
||||
uint32_t config = SPI_CSR_CSAAT;
|
||||
config |= SPI_CSR_BITS_8_BIT; // TODO: support for SPI_CSR_BITS_16_BIT
|
||||
// NOTE: NCPHA is inverted, CPHA normal!!
|
||||
switch(mode) {
|
||||
case 0:
|
||||
config |= SPI_CSR_NCPHA;
|
||||
break;
|
||||
case 1:
|
||||
config |= 0;
|
||||
break;
|
||||
case 2:
|
||||
config |= SPI_CSR_NCPHA;
|
||||
config |= SPI_CSR_CPOL;
|
||||
break;
|
||||
case 3:
|
||||
config |= SPI_CSR_CPOL;
|
||||
break;
|
||||
};
|
||||
|
||||
config |= ((clockDiv & 0xffu) << SPI_CSR_SCBR_Pos);
|
||||
return (struct spi_config){ .spidev = spi_bus[bus].dev, .cfg = config };
|
||||
}
|
||||
|
||||
static void
|
||||
spihw_prepare(struct spi_config config)
|
||||
{
|
||||
Spi *pSpi = config.spidev;
|
||||
pSpi->SPI_CSR[CHANNEL] = config.cfg;
|
||||
}
|
||||
|
||||
static void
|
||||
spihw_transfer(struct spi_config config, uint8_t receive_data
|
||||
, uint8_t len, uint8_t *data)
|
||||
{
|
||||
Spi *pSpi = config.spidev;
|
||||
if (receive_data) {
|
||||
while (len--) {
|
||||
pSpi->SPI_TDR = *data;
|
||||
// wait for receive register
|
||||
while (!(pSpi->SPI_SR & SPI_SR_RDRF))
|
||||
;
|
||||
// get data
|
||||
*data++ = pSpi->SPI_RDR;
|
||||
}
|
||||
} else {
|
||||
while (len--) {
|
||||
pSpi->SPI_TDR = *data++;
|
||||
// wait for receive register
|
||||
while (!(pSpi->SPI_SR & SPI_SR_RDRF))
|
||||
;
|
||||
// read data (to clear RDRF)
|
||||
pSpi->SPI_RDR;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* USART hardware
|
||||
****************************************************************/
|
||||
|
||||
static struct spi_config
|
||||
usart_setup(uint32_t bus, uint8_t mode, uint32_t rate)
|
||||
{
|
||||
init_pins(bus);
|
||||
Usart *p_usart = spi_bus[bus].dev;
|
||||
|
||||
p_usart->US_MR = 0;
|
||||
p_usart->US_RTOR = 0;
|
||||
p_usart->US_TTGR = 0;
|
||||
|
||||
p_usart->US_CR = US_CR_RSTTX | US_CR_RSTRX | US_CR_TXDIS | US_CR_RXDIS;
|
||||
|
||||
uint32_t pclk = get_pclock_frequency(ID_USART0);
|
||||
uint32_t br = DIV_ROUND_UP(pclk, rate);
|
||||
p_usart->US_BRGR = br << US_BRGR_CD_Pos;
|
||||
|
||||
uint32_t reg = US_MR_CHRL_8_BIT |
|
||||
US_MR_USART_MODE_SPI_MASTER |
|
||||
US_MR_CLKO |
|
||||
US_MR_CHMODE_NORMAL;
|
||||
switch (mode) {
|
||||
case 0:
|
||||
reg |= US_MR_CPHA;
|
||||
reg &= ~US_MR_CPOL;
|
||||
break;
|
||||
case 1:
|
||||
reg &= ~US_MR_CPHA;
|
||||
reg &= ~US_MR_CPOL;
|
||||
break;
|
||||
case 2:
|
||||
reg |= US_MR_CPHA;
|
||||
reg |= US_MR_CPOL;
|
||||
break;
|
||||
case 3:
|
||||
reg &= ~US_MR_CPHA;
|
||||
reg |= US_MR_CPOL;
|
||||
break;
|
||||
}
|
||||
|
||||
p_usart->US_MR |= reg;
|
||||
p_usart->US_CR = US_CR_RXEN | US_CR_TXEN;
|
||||
return (struct spi_config){ .spidev=p_usart, .cfg=p_usart->US_MR };
|
||||
}
|
||||
|
||||
static void
|
||||
usart_prepare(struct spi_config config)
|
||||
{
|
||||
}
|
||||
|
||||
static void
|
||||
usart_transfer(struct spi_config config, uint8_t receive_data
|
||||
, uint8_t len, uint8_t *data)
|
||||
{
|
||||
Usart *p_usart = config.spidev;
|
||||
if (receive_data) {
|
||||
for (uint32_t i = 0; i < len; ++i) {
|
||||
uint32_t co = (uint32_t)*data & 0x000000FF;
|
||||
while(!(p_usart->US_CSR & US_CSR_TXRDY)) {}
|
||||
p_usart->US_THR = US_THR_TXCHR(co);
|
||||
uint32_t ci = 0;
|
||||
while(!(p_usart->US_CSR & US_CSR_RXRDY)) {}
|
||||
ci = p_usart->US_RHR & US_RHR_RXCHR_Msk;
|
||||
*data++ = (uint8_t)ci;
|
||||
}
|
||||
} else {
|
||||
for (uint32_t i = 0; i < len; ++i) {
|
||||
uint32_t co = (uint32_t)*data & 0x000000FF;
|
||||
while(!(p_usart->US_CSR & US_CSR_TXRDY)) {}
|
||||
p_usart->US_THR = US_THR_TXCHR(co);
|
||||
while(!(p_usart->US_CSR & US_CSR_RXRDY)) {}
|
||||
(void)(p_usart->US_RHR & US_RHR_RXCHR_Msk);
|
||||
(void)*data++;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Interface
|
||||
****************************************************************/
|
||||
|
||||
struct spi_config
|
||||
spi_setup(uint32_t bus, uint8_t mode, uint32_t rate)
|
||||
{
|
||||
if (bus >= ARRAY_SIZE(spi_bus))
|
||||
shutdown("Invalid spi bus");
|
||||
if (is_spihw(spi_bus[bus].dev))
|
||||
return spihw_setup(bus, mode, rate);
|
||||
return usart_setup(bus, mode, rate);
|
||||
}
|
||||
|
||||
void
|
||||
spi_prepare(struct spi_config config)
|
||||
{
|
||||
if (is_spihw(config.spidev))
|
||||
spihw_prepare(config);
|
||||
else
|
||||
usart_prepare(config);
|
||||
}
|
||||
|
||||
void
|
||||
spi_transfer(struct spi_config config, uint8_t receive_data
|
||||
, uint8_t len, uint8_t *data)
|
||||
{
|
||||
if (is_spihw(config.spidev))
|
||||
spihw_transfer(config, receive_data, len, data);
|
||||
else
|
||||
usart_transfer(config, receive_data, len, data);
|
||||
}
|
||||
10
src/atsam/usb_cdc_ep.h
Normal file
10
src/atsam/usb_cdc_ep.h
Normal file
@@ -0,0 +1,10 @@
|
||||
#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
|
||||
147
src/atsamd/Kconfig
Normal file
147
src/atsamd/Kconfig
Normal file
@@ -0,0 +1,147 @@
|
||||
# Kconfig settings for Atmel SAMD processors
|
||||
|
||||
if MACH_ATSAMD
|
||||
|
||||
config ATSAMD_SELECT
|
||||
bool
|
||||
default y
|
||||
select HAVE_GPIO
|
||||
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_STRICT_TIMING
|
||||
select HAVE_CHIPID
|
||||
select HAVE_STEPPER_BOTH_EDGE
|
||||
|
||||
config HAVE_SERCOM
|
||||
depends on HAVE_GPIO_I2C || HAVE_GPIO_SPI
|
||||
bool
|
||||
default y
|
||||
|
||||
config BOARD_DIRECTORY
|
||||
string
|
||||
default "atsamd"
|
||||
|
||||
choice
|
||||
prompt "Processor model"
|
||||
config MACH_SAMD21G18
|
||||
bool "SAMD21G18 (Arduino Zero)"
|
||||
select MACH_SAMD21
|
||||
config MACH_SAMD21E18
|
||||
bool "SAMD21E18 (Adafruit Trinket M0)"
|
||||
select MACH_SAMD21
|
||||
config MACH_SAMD21E15
|
||||
bool "SAMD21E15"
|
||||
select MACH_SAMD21
|
||||
config MACH_SAMD51G19
|
||||
bool "SAMD51G19 (Adafruit ItsyBitsy M4)"
|
||||
select MACH_SAMD51
|
||||
config MACH_SAMD51J19
|
||||
bool "SAMD51J19 (Adafruit Metro M4)"
|
||||
select MACH_SAMD51
|
||||
config MACH_SAMD51N19
|
||||
bool "SAMD51N19"
|
||||
select MACH_SAMD51
|
||||
config MACH_SAMD51P20
|
||||
bool "SAMD51P20 (Adafruit Grand Central)"
|
||||
select MACH_SAMD51
|
||||
endchoice
|
||||
|
||||
config MACH_SAMD21
|
||||
bool
|
||||
config MACH_SAMD51
|
||||
bool
|
||||
|
||||
config MCU
|
||||
string
|
||||
default "samd21g18a" if MACH_SAMD21G18
|
||||
default "samd21e18a" if MACH_SAMD21E18
|
||||
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
|
||||
|
||||
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
|
||||
|
||||
config RAM_START
|
||||
hex
|
||||
default 0x20000000
|
||||
|
||||
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
|
||||
|
||||
config STACK_SIZE
|
||||
int
|
||||
default 512
|
||||
|
||||
choice
|
||||
prompt "Clock Reference"
|
||||
config CLOCK_REF_X32K
|
||||
bool "32.768Khz crystal"
|
||||
config CLOCK_REF_X25M
|
||||
bool "25Mhz crystal" if MACH_SAMD51
|
||||
config CLOCK_REF_INTERNAL
|
||||
bool "Internal clock"
|
||||
endchoice
|
||||
|
||||
choice
|
||||
depends on MACH_SAMD51 && LOW_LEVEL_OPTIONS
|
||||
prompt "Processor speed"
|
||||
config SAMD51_FREQ_120
|
||||
bool "120 MHz (standard)"
|
||||
config SAMD51_FREQ_150
|
||||
bool "150 MHz (overclock)"
|
||||
config SAMD51_FREQ_180
|
||||
bool "180 MHz (overclock)"
|
||||
config SAMD51_FREQ_200
|
||||
bool "200 MHz (overclock)"
|
||||
endchoice
|
||||
|
||||
config CLOCK_FREQ
|
||||
int
|
||||
default 48000000 if MACH_SAMD21
|
||||
default 150000000 if SAMD51_FREQ_150
|
||||
default 180000000 if SAMD51_FREQ_180
|
||||
default 200000000 if SAMD51_FREQ_200
|
||||
default 120000000 if MACH_SAMD51
|
||||
|
||||
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
|
||||
|
||||
choice
|
||||
prompt "Communication interface"
|
||||
config ATSAMD_USB
|
||||
bool "USB"
|
||||
select USBSERIAL
|
||||
config ATSAMD_SERIAL
|
||||
bool "Serial"
|
||||
select SERIAL
|
||||
endchoice
|
||||
|
||||
endif
|
||||
56
src/atsamd/Makefile
Normal file
56
src/atsamd/Makefile
Normal file
@@ -0,0 +1,56 @@
|
||||
# Additional atsamd build rules
|
||||
|
||||
# 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
|
||||
|
||||
MCU := $(shell echo $(CONFIG_MCU) | tr a-z A-Z)
|
||||
|
||||
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_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 += 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
|
||||
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_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
|
||||
|
||||
# Build the additional hex and bin output files
|
||||
target-y += $(OUT)klipper.bin $(OUT)klipper.elf.hex
|
||||
|
||||
$(OUT)klipper.bin: $(OUT)klipper.elf
|
||||
@echo " Creating bin file $@"
|
||||
$(Q)$(OBJCOPY) -O binary $< $@
|
||||
|
||||
$(OUT)klipper.elf.hex: $(OUT)klipper.elf
|
||||
@echo " Creating hex file $@"
|
||||
$(Q)$(OBJCOPY) -j .text -j .relocate -O ihex $< $@
|
||||
|
||||
# Flash rules
|
||||
lib/bossac/bin/bossac:
|
||||
@echo " Building bossac"
|
||||
$(Q)make -C lib/bossac bin/bossac
|
||||
|
||||
BOSSAC_OFFSET-$(CONFIG_MACH_SAMD21) := 0x2000
|
||||
BOSSAC_OFFSET-$(CONFIG_MACH_SAMD51) := 0x4000
|
||||
|
||||
flash: $(OUT)klipper.bin lib/bossac/bin/bossac
|
||||
@echo " Flashing $< to $(FLASH_DEVICE)"
|
||||
$(Q)$(PYTHON) ./scripts/flash_usb.py -t $(CONFIG_MCU) -d "$(FLASH_DEVICE)" -s "$(BOSSAC_OFFSET-y)" $(OUT)klipper.bin
|
||||
210
src/atsamd/adc.c
Normal file
210
src/atsamd/adc.c
Normal file
@@ -0,0 +1,210 @@
|
||||
// Analog to Digital Converter support
|
||||
//
|
||||
// Copyright (C) 2018-2020 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "command.h" // shutdown
|
||||
#include "gpio.h" // gpio_adc_read
|
||||
#include "internal.h" // GPIO
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
#define ADC_TEMPERATURE_PIN 0xfe
|
||||
DECL_ENUMERATION("pin", "ADC_TEMPERATURE", ADC_TEMPERATURE_PIN);
|
||||
|
||||
#if CONFIG_MACH_SAMD21
|
||||
|
||||
#define SAMD51_ADC_SYNC(ADC, BIT)
|
||||
static const uint8_t adc_pins[] = {
|
||||
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('B', 0), GPIO('B', 1),
|
||||
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
|
||||
|
||||
#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), GPIO('B', 0), GPIO('B', 1), GPIO('B', 2),
|
||||
GPIO('B', 3),
|
||||
/* ADC1 */
|
||||
GPIO('B', 8), GPIO('B', 9), GPIO('A', 8), GPIO('A', 9), GPIO('C', 2),
|
||||
GPIO('C', 3), GPIO('B', 4), GPIO('B', 5), GPIO('B', 6), GPIO('B', 7),
|
||||
GPIO('C', 0), GPIO('C', 1), GPIO('C', 30), GPIO('C', 31), GPIO('D', 0),
|
||||
GPIO('D', 1)
|
||||
};
|
||||
#endif
|
||||
|
||||
DECL_CONSTANT("ADC_MAX", 4095);
|
||||
|
||||
static struct gpio_adc gpio_adc_pin_to_struct(uint8_t pin)
|
||||
{
|
||||
// Find pin in adc_pins table
|
||||
uint8_t chan;
|
||||
for (chan=0; ; chan++) {
|
||||
if (chan >= ARRAY_SIZE(adc_pins))
|
||||
shutdown("Not a valid ADC pin");
|
||||
if (adc_pins[chan] == pin)
|
||||
break;
|
||||
}
|
||||
#if CONFIG_MACH_SAMD21
|
||||
Adc* reg = ADC;
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
Adc* reg = (chan < 16 ? ADC0 : ADC1);
|
||||
chan %= 16;
|
||||
#endif
|
||||
return (struct gpio_adc){ .regs=reg, .chan=chan };
|
||||
}
|
||||
|
||||
|
||||
static void
|
||||
adc_init(void)
|
||||
{
|
||||
static uint8_t have_run_init;
|
||||
if (have_run_init)
|
||||
return;
|
||||
have_run_init = 1;
|
||||
|
||||
#if CONFIG_MACH_SAMD21
|
||||
// Enable adc clock
|
||||
enable_pclock(ADC_GCLK_ID, ID_ADC);
|
||||
// Load calibraiton info
|
||||
uint32_t bias = GET_FUSE(ADC_FUSES_BIASCAL);
|
||||
uint32_t li0 = GET_FUSE(ADC_FUSES_LINEARITY_0);
|
||||
uint32_t li5 = GET_FUSE(ADC_FUSES_LINEARITY_1);
|
||||
uint32_t lin = li0 | (li5 << 5);
|
||||
ADC->CALIB.reg = ADC_CALIB_BIAS_CAL(bias) | ADC_CALIB_LINEARITY_CAL(lin);
|
||||
|
||||
// Setup and enable adc
|
||||
ADC->REFCTRL.reg = ADC_REFCTRL_REFSEL_INTVCC1;
|
||||
ADC->CTRLB.reg = ADC_CTRLB_PRESCALER_DIV128;
|
||||
ADC->SAMPCTRL.reg = 63;
|
||||
ADC->CTRLA.reg = ADC_CTRLA_ENABLE;
|
||||
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
// Enable adc clock
|
||||
enable_pclock(ADC0_GCLK_ID, ID_ADC0);
|
||||
enable_pclock(ADC1_GCLK_ID, ID_ADC1);
|
||||
|
||||
// Load calibration info
|
||||
// ADC0
|
||||
uint32_t refbuf = GET_FUSE(ADC0_FUSES_BIASREFBUF);
|
||||
uint32_t r2r = GET_FUSE(ADC0_FUSES_BIASR2R);
|
||||
uint32_t comp = GET_FUSE(ADC0_FUSES_BIASCOMP);
|
||||
ADC0->CALIB.reg = (ADC0_FUSES_BIASREFBUF(refbuf)
|
||||
| ADC0_FUSES_BIASR2R(r2r) | ADC0_FUSES_BIASCOMP(comp));
|
||||
|
||||
// ADC1
|
||||
refbuf = GET_FUSE(ADC1_FUSES_BIASREFBUF);
|
||||
r2r = GET_FUSE(ADC1_FUSES_BIASR2R);
|
||||
comp = GET_FUSE(ADC1_FUSES_BIASCOMP);
|
||||
ADC1->CALIB.reg = (ADC0_FUSES_BIASREFBUF(refbuf)
|
||||
| ADC0_FUSES_BIASR2R(r2r) | ADC0_FUSES_BIASCOMP(comp));
|
||||
|
||||
// Setup and enable
|
||||
// ADC0
|
||||
ADC0->REFCTRL.reg = ADC_REFCTRL_REFSEL_INTVCC1;
|
||||
while(ADC0->SYNCBUSY.reg & ADC_SYNCBUSY_REFCTRL);
|
||||
ADC0->SAMPCTRL.reg = ADC_SAMPCTRL_SAMPLEN(63);
|
||||
while (ADC0->SYNCBUSY.reg & ADC_SYNCBUSY_SAMPCTRL);
|
||||
ADC0->CTRLA.reg = (ADC_CTRLA_PRESCALER(ADC_CTRLA_PRESCALER_DIV32_Val)
|
||||
| ADC_CTRLA_ENABLE);
|
||||
|
||||
// ADC1
|
||||
ADC1->REFCTRL.reg = ADC_REFCTRL_REFSEL_INTVCC1;
|
||||
while(ADC1->SYNCBUSY.reg & ADC_SYNCBUSY_REFCTRL);
|
||||
ADC1->SAMPCTRL.reg = ADC_SAMPCTRL_SAMPLEN(63);
|
||||
while(ADC1->SYNCBUSY.reg & ADC_SYNCBUSY_SAMPCTRL);
|
||||
ADC1->CTRLA.reg = (ADC_CTRLA_PRESCALER(ADC_CTRLA_PRESCALER_DIV32_Val)
|
||||
| ADC_CTRLA_ENABLE);
|
||||
#endif
|
||||
}
|
||||
|
||||
struct gpio_adc
|
||||
gpio_adc_setup(uint8_t pin)
|
||||
{
|
||||
// Enable ADC
|
||||
adc_init();
|
||||
|
||||
if (pin == ADC_TEMPERATURE_PIN) {
|
||||
#if CONFIG_MACH_SAMD21
|
||||
SYSCTRL->VREF.reg |= SYSCTRL_VREF_TSEN;
|
||||
return (struct gpio_adc){ .regs=ADC,
|
||||
.chan=ADC_INPUTCTRL_MUXPOS_TEMP_Val };
|
||||
#else
|
||||
SUPC->VREF.reg |= SUPC_VREF_TSEN;
|
||||
return (struct gpio_adc){ .regs=ADC0,
|
||||
.chan=ADC_INPUTCTRL_MUXPOS_PTAT_Val };
|
||||
#endif
|
||||
}
|
||||
|
||||
// Set pin in ADC mode
|
||||
gpio_peripheral(pin, 'B', 0);
|
||||
|
||||
return gpio_adc_pin_to_struct(pin);
|
||||
}
|
||||
|
||||
enum { ADC_DUMMY=0xff };
|
||||
static uint8_t last_analog_read = ADC_DUMMY;
|
||||
|
||||
// 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)
|
||||
{
|
||||
Adc *reg = g.regs;
|
||||
if (last_analog_read == g.chan) {
|
||||
if (reg->INTFLAG.reg & ADC_INTFLAG_RESRDY)
|
||||
// Sample now ready
|
||||
return 0;
|
||||
// ADC is still busy
|
||||
goto need_delay;
|
||||
}
|
||||
if (last_analog_read != ADC_DUMMY)
|
||||
// Sample on another channel in progress
|
||||
goto need_delay;
|
||||
last_analog_read = g.chan;
|
||||
|
||||
// Set the channel to sample
|
||||
reg->INPUTCTRL.reg = (ADC_INPUTCTRL_MUXPOS(g.chan)
|
||||
| ADC_INPUTCTRL_MUXNEG_GND
|
||||
#if CONFIG_MACH_SAMD21
|
||||
| ADC_INPUTCTRL_GAIN_DIV2
|
||||
#endif
|
||||
);
|
||||
|
||||
SAMD51_ADC_SYNC(reg, INPUTCTRL);
|
||||
// Start the sample
|
||||
reg->SWTRIG.reg = ADC_SWTRIG_START;
|
||||
SAMD51_ADC_SYNC(reg, SWTRIG);
|
||||
|
||||
// Schedule next attempt after sample is likely to be complete
|
||||
need_delay:
|
||||
return 42 * 128 + 200; // 42 == 1 + (63+1)/2 + 1 + 12/2 + 1.5
|
||||
}
|
||||
|
||||
// Read a value; use only after gpio_adc_sample() returns zero
|
||||
uint16_t
|
||||
gpio_adc_read(struct gpio_adc g)
|
||||
{
|
||||
last_analog_read = ADC_DUMMY;
|
||||
return ((Adc *)g.regs)->RESULT.reg;
|
||||
}
|
||||
|
||||
// Cancel a sample that may have been started with gpio_adc_sample()
|
||||
void
|
||||
gpio_adc_cancel_sample(struct gpio_adc g)
|
||||
{
|
||||
Adc * reg = g.regs;
|
||||
if (last_analog_read == g.chan) {
|
||||
reg->SWTRIG.reg = ADC_SWTRIG_FLUSH;
|
||||
SAMD51_ADC_SYNC(reg, SWTRIG);
|
||||
reg->INTFLAG.reg = ADC_INTFLAG_RESRDY;
|
||||
last_analog_read = ADC_DUMMY;
|
||||
}
|
||||
}
|
||||
45
src/atsamd/chipid.c
Normal file
45
src/atsamd/chipid.c
Normal file
@@ -0,0 +1,45 @@
|
||||
// Support for extracting the hardware chip id on atsamd
|
||||
//
|
||||
// Copyright (C) 2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_USB_SERIAL_NUMBER_CHIPID
|
||||
#include "generic/usb_cdc.h" // usb_fill_serial
|
||||
#include "generic/usbstd.h" // usb_string_descriptor
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
#define CHIP_UID_LEN 16
|
||||
|
||||
static struct {
|
||||
struct usb_string_descriptor desc;
|
||||
uint16_t data[CHIP_UID_LEN * 2];
|
||||
} cdc_chipid;
|
||||
|
||||
struct usb_string_descriptor *
|
||||
usbserial_get_serialid(void)
|
||||
{
|
||||
return &cdc_chipid.desc;
|
||||
}
|
||||
|
||||
void
|
||||
chipid_init(void)
|
||||
{
|
||||
if (!CONFIG_USB_SERIAL_NUMBER_CHIPID)
|
||||
return;
|
||||
|
||||
uint32_t id[4];
|
||||
if (CONFIG_MACH_SAMD21) {
|
||||
id[0] = *(uint32_t*)0x0080A00C;
|
||||
id[1] = *(uint32_t*)0x0080A040;
|
||||
id[2] = *(uint32_t*)0x0080A044;
|
||||
id[3] = *(uint32_t*)0x0080A048;
|
||||
} else {
|
||||
id[0] = *(uint32_t*)0x008061FC;
|
||||
id[1] = *(uint32_t*)0x00806010;
|
||||
id[2] = *(uint32_t*)0x00806014;
|
||||
id[3] = *(uint32_t*)0x00806018;
|
||||
}
|
||||
usb_fill_serial(&cdc_chipid.desc, ARRAY_SIZE(cdc_chipid.data), id);
|
||||
}
|
||||
DECL_INIT(chipid_init);
|
||||
126
src/atsamd/clock.c
Normal file
126
src/atsamd/clock.c
Normal file
@@ -0,0 +1,126 @@
|
||||
// Code to setup peripheral clocks on the SAMD21
|
||||
//
|
||||
// Copyright (C) 2018-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// 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 CLKGEN_ULP32K 2
|
||||
|
||||
#define FREQ_MAIN 48000000
|
||||
#define FREQ_32K 32768
|
||||
|
||||
// Configure a clock generator using a given source as input
|
||||
static inline void
|
||||
gen_clock(uint32_t clkgen_id, uint32_t flags)
|
||||
{
|
||||
GCLK->GENDIV.reg = GCLK_GENDIV_ID(clkgen_id);
|
||||
GCLK->GENCTRL.reg = GCLK_GENCTRL_ID(clkgen_id) | flags | GCLK_GENCTRL_GENEN;
|
||||
}
|
||||
|
||||
// Route a peripheral clock to a given clkgen
|
||||
static inline void
|
||||
route_pclock(uint32_t pclk_id, uint32_t clkgen_id)
|
||||
{
|
||||
GCLK->CLKCTRL.reg = (GCLK_CLKCTRL_ID(pclk_id)
|
||||
| GCLK_CLKCTRL_GEN(clkgen_id) | GCLK_CLKCTRL_CLKEN);
|
||||
while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY)
|
||||
;
|
||||
}
|
||||
|
||||
// Enable a peripheral clock and power to that peripheral
|
||||
void
|
||||
enable_pclock(uint32_t pclk_id, uint32_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;
|
||||
}
|
||||
|
||||
// Return the frequency of the given peripheral clock
|
||||
uint32_t
|
||||
get_pclock_frequency(uint32_t pclk_id)
|
||||
{
|
||||
return FREQ_MAIN;
|
||||
}
|
||||
|
||||
#if CONFIG_CLOCK_REF_X32K
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_crystal", "PA0,PA1");
|
||||
#endif
|
||||
|
||||
// Initialize the clocks using an external 32K crystal
|
||||
static void
|
||||
clock_init_32k(void)
|
||||
{
|
||||
// Enable external 32Khz crystal
|
||||
uint32_t val = (SYSCTRL_XOSC32K_STARTUP(6)
|
||||
| SYSCTRL_XOSC32K_XTALEN | SYSCTRL_XOSC32K_EN32K);
|
||||
SYSCTRL->XOSC32K.reg = val;
|
||||
SYSCTRL->XOSC32K.reg = val | SYSCTRL_XOSC32K_ENABLE;
|
||||
while (!(SYSCTRL->PCLKSR.reg & SYSCTRL_PCLKSR_XOSC32KRDY))
|
||||
;
|
||||
|
||||
// Generate 48Mhz clock on DPLL (with XOSC32K as reference)
|
||||
SYSCTRL->DPLLCTRLA.reg = 0;
|
||||
uint32_t mul = DIV_ROUND_CLOSEST(FREQ_MAIN, FREQ_32K);
|
||||
SYSCTRL->DPLLRATIO.reg = SYSCTRL_DPLLRATIO_LDR(mul - 1);
|
||||
SYSCTRL->DPLLCTRLB.reg = SYSCTRL_DPLLCTRLB_LBYPASS;
|
||||
SYSCTRL->DPLLCTRLA.reg = SYSCTRL_DPLLCTRLA_ENABLE;
|
||||
uint32_t mask = SYSCTRL_DPLLSTATUS_CLKRDY | SYSCTRL_DPLLSTATUS_LOCK;
|
||||
while ((SYSCTRL->DPLLSTATUS.reg & mask) != mask)
|
||||
;
|
||||
|
||||
// Switch main clock to DPLL clock
|
||||
gen_clock(CLKGEN_MAIN, GCLK_GENCTRL_SRC_DPLL96M);
|
||||
}
|
||||
|
||||
// Initialize clocks from factory calibrated internal clock
|
||||
static void
|
||||
clock_init_internal(void)
|
||||
{
|
||||
// Configure DFLL48M clock in open loop mode
|
||||
SYSCTRL->DFLLCTRL.reg = 0;
|
||||
uint32_t coarse = GET_FUSE(FUSES_DFLL48M_COARSE_CAL);
|
||||
uint32_t fine = GET_FUSE(FUSES_DFLL48M_FINE_CAL);
|
||||
SYSCTRL->DFLLVAL.reg = (SYSCTRL_DFLLVAL_COARSE(coarse)
|
||||
| SYSCTRL_DFLLVAL_FINE(fine));
|
||||
if (CONFIG_USBSERIAL) {
|
||||
// Enable USB clock recovery mode
|
||||
uint32_t mul = DIV_ROUND_CLOSEST(FREQ_MAIN, 1000);
|
||||
SYSCTRL->DFLLMUL.reg = (SYSCTRL_DFLLMUL_FSTEP(10)
|
||||
| SYSCTRL_DFLLMUL_MUL(mul));
|
||||
SYSCTRL->DFLLCTRL.reg = (SYSCTRL_DFLLCTRL_MODE | SYSCTRL_DFLLCTRL_USBCRM
|
||||
| SYSCTRL_DFLLCTRL_CCDIS
|
||||
| SYSCTRL_DFLLCTRL_ENABLE);
|
||||
} else {
|
||||
SYSCTRL->DFLLCTRL.reg = SYSCTRL_DFLLCTRL_ENABLE;
|
||||
}
|
||||
while (!(SYSCTRL->PCLKSR.reg & SYSCTRL_PCLKSR_DFLLRDY))
|
||||
;
|
||||
|
||||
// Switch main clock to DFLL48M clock
|
||||
gen_clock(CLKGEN_MAIN, GCLK_GENCTRL_SRC_DFLL48M);
|
||||
}
|
||||
|
||||
void
|
||||
SystemInit(void)
|
||||
{
|
||||
// Setup flash to work with 48Mhz clock
|
||||
NVMCTRL->CTRLB.reg = NVMCTRL_CTRLB_RWS_HALF;
|
||||
|
||||
// Reset GCLK
|
||||
GCLK->CTRL.reg = GCLK_CTRL_SWRST;
|
||||
while (GCLK->CTRL.reg & GCLK_CTRL_SWRST)
|
||||
;
|
||||
|
||||
// Init clocks
|
||||
if (CONFIG_CLOCK_REF_X32K)
|
||||
clock_init_32k();
|
||||
else
|
||||
clock_init_internal();
|
||||
}
|
||||
150
src/atsamd/gpio.c
Normal file
150
src/atsamd/gpio.c
Normal file
@@ -0,0 +1,150 @@
|
||||
// samd gpio functions
|
||||
//
|
||||
// Copyright (C) 2018-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// 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" // shutdown
|
||||
#include "gpio.h" // gpio_out_setup
|
||||
#include "internal.h" // gpio_peripheral
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Pin multiplexing
|
||||
****************************************************************/
|
||||
|
||||
void
|
||||
gpio_peripheral(uint32_t gpio, char ptype, int32_t pull_up)
|
||||
{
|
||||
uint32_t bank = GPIO2PORT(gpio), bit = gpio % 32;
|
||||
PortGroup *pg = &PORT->Group[bank];
|
||||
if (ptype) {
|
||||
volatile uint8_t *pmux = &pg->PMUX[bit/2].reg;
|
||||
uint8_t shift = (bit & 1) ? 4 : 0, mask = ~(0xf << shift);
|
||||
*pmux = (*pmux & mask) | ((ptype - 'A') << shift);
|
||||
}
|
||||
if (pull_up) {
|
||||
if (pull_up > 0)
|
||||
pg->OUTSET.reg = (1<<bit);
|
||||
else
|
||||
pg->OUTCLR.reg = (1<<bit);
|
||||
}
|
||||
|
||||
pg->PINCFG[bit].reg = ((ptype ? PORT_PINCFG_PMUXEN : 0)
|
||||
| (pull_up ? PORT_PINCFG_PULLEN : 0));
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* General Purpose Input Output (GPIO) pins
|
||||
****************************************************************/
|
||||
|
||||
#if CONFIG_MACH_SAMD21
|
||||
#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
|
||||
#define NUM_PORT 4
|
||||
DECL_ENUMERATION_RANGE("pin", "PA0", GPIO('A', 0), 32);
|
||||
DECL_ENUMERATION_RANGE("pin", "PB0", GPIO('B', 0), 32);
|
||||
DECL_ENUMERATION_RANGE("pin", "PC0", GPIO('C', 0), 32);
|
||||
DECL_ENUMERATION_RANGE("pin", "PD0", GPIO('D', 0), 32);
|
||||
#endif
|
||||
|
||||
struct gpio_out
|
||||
gpio_out_setup(uint8_t pin, uint8_t val)
|
||||
{
|
||||
if (GPIO2PORT(pin) >= NUM_PORT)
|
||||
goto fail;
|
||||
PortGroup *pg = &PORT->Group[GPIO2PORT(pin)];
|
||||
struct gpio_out g = { .regs=pg, .bit=GPIO2BIT(pin) };
|
||||
gpio_out_reset(g, val);
|
||||
return g;
|
||||
fail:
|
||||
shutdown("Not an output pin");
|
||||
}
|
||||
|
||||
static void
|
||||
set_pincfg(PortGroup *pg, uint32_t bit, uint8_t cfg)
|
||||
{
|
||||
pg->PINCFG[ffs(bit)-1].reg = cfg;
|
||||
}
|
||||
|
||||
void
|
||||
gpio_out_reset(struct gpio_out g, uint8_t val)
|
||||
{
|
||||
PortGroup *pg = g.regs;
|
||||
irqstatus_t flag = irq_save();
|
||||
if (val)
|
||||
pg->OUTSET.reg = g.bit;
|
||||
else
|
||||
pg->OUTCLR.reg = g.bit;
|
||||
pg->DIRSET.reg = g.bit;
|
||||
set_pincfg(pg, g.bit, 0);
|
||||
irq_restore(flag);
|
||||
}
|
||||
|
||||
void
|
||||
gpio_out_toggle_noirq(struct gpio_out g)
|
||||
{
|
||||
PortGroup *pg = g.regs;
|
||||
pg->OUTTGL.reg = g.bit;
|
||||
}
|
||||
|
||||
void
|
||||
gpio_out_toggle(struct gpio_out g)
|
||||
{
|
||||
gpio_out_toggle_noirq(g);
|
||||
}
|
||||
|
||||
void
|
||||
gpio_out_write(struct gpio_out g, uint8_t val)
|
||||
{
|
||||
PortGroup *pg = g.regs;
|
||||
if (val)
|
||||
pg->OUTSET.reg = g.bit;
|
||||
else
|
||||
pg->OUTCLR.reg = g.bit;
|
||||
}
|
||||
|
||||
|
||||
struct gpio_in
|
||||
gpio_in_setup(uint8_t pin, int8_t pull_up)
|
||||
{
|
||||
if (GPIO2PORT(pin) >= NUM_PORT)
|
||||
goto fail;
|
||||
PortGroup *pg = &PORT->Group[GPIO2PORT(pin)];
|
||||
struct gpio_in g = { .regs=pg, .bit=GPIO2BIT(pin) };
|
||||
gpio_in_reset(g, pull_up);
|
||||
return g;
|
||||
fail:
|
||||
shutdown("Not an input pin");
|
||||
}
|
||||
|
||||
void
|
||||
gpio_in_reset(struct gpio_in g, int8_t pull_up)
|
||||
{
|
||||
PortGroup *pg = g.regs;
|
||||
irqstatus_t flag = irq_save();
|
||||
uint32_t cfg = PORT_PINCFG_INEN;
|
||||
if (pull_up) {
|
||||
cfg |= PORT_PINCFG_PULLEN;
|
||||
if (pull_up > 0)
|
||||
pg->OUTSET.reg = g.bit;
|
||||
else
|
||||
pg->OUTCLR.reg = g.bit;
|
||||
}
|
||||
set_pincfg(pg, g.bit, cfg);
|
||||
pg->DIRCLR.reg = g.bit;
|
||||
irq_restore(flag);
|
||||
}
|
||||
|
||||
uint8_t
|
||||
gpio_in_read(struct gpio_in g)
|
||||
{
|
||||
PortGroup *pg = g.regs;
|
||||
return !!(pg->IN.reg & g.bit);
|
||||
}
|
||||
58
src/atsamd/gpio.h
Normal file
58
src/atsamd/gpio.h
Normal file
@@ -0,0 +1,58 @@
|
||||
#ifndef __ATSAMD_GPIO_H
|
||||
#define __ATSAMD_GPIO_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
struct gpio_out {
|
||||
void *regs;
|
||||
uint32_t bit;
|
||||
};
|
||||
struct gpio_out gpio_out_setup(uint8_t pin, uint8_t val);
|
||||
void gpio_out_reset(struct gpio_out g, uint8_t val);
|
||||
void gpio_out_toggle_noirq(struct gpio_out g);
|
||||
void gpio_out_toggle(struct gpio_out g);
|
||||
void gpio_out_write(struct gpio_out g, uint8_t val);
|
||||
|
||||
struct gpio_in {
|
||||
void *regs;
|
||||
uint32_t bit;
|
||||
};
|
||||
struct gpio_in gpio_in_setup(uint8_t pin, int8_t pull_up);
|
||||
void gpio_in_reset(struct gpio_in g, int8_t pull_up);
|
||||
uint8_t gpio_in_read(struct gpio_in g);
|
||||
|
||||
struct gpio_pwm {
|
||||
void *reg;
|
||||
};
|
||||
struct gpio_pwm gpio_pwm_setup(uint8_t pin, uint32_t cycle_time, uint8_t val);
|
||||
void gpio_pwm_write(struct gpio_pwm g, uint8_t val);
|
||||
|
||||
struct gpio_adc {
|
||||
void *regs;
|
||||
uint32_t chan;
|
||||
};
|
||||
struct gpio_adc gpio_adc_setup(uint8_t pin);
|
||||
uint32_t gpio_adc_sample(struct gpio_adc g);
|
||||
uint16_t gpio_adc_read(struct gpio_adc g);
|
||||
void gpio_adc_cancel_sample(struct gpio_adc g);
|
||||
|
||||
struct spi_config {
|
||||
void *ss;
|
||||
uint32_t ctrla, baud;
|
||||
};
|
||||
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 *si;
|
||||
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
|
||||
108
src/atsamd/hard_pwm.c
Normal file
108
src/atsamd/hard_pwm.c
Normal file
@@ -0,0 +1,108 @@
|
||||
// Hardware PWM support on samd21
|
||||
//
|
||||
// Copyright (C) 2018-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "command.h" // shutdown
|
||||
#include "gpio.h" // gpio_pwm_write
|
||||
#include "internal.h" // GPIO
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
// Available TCC devices
|
||||
struct tcc_info_s {
|
||||
Tcc *tcc;
|
||||
uint32_t pclk_id, pm_id;
|
||||
};
|
||||
static const struct tcc_info_s tcc_info[] = {
|
||||
{ TCC0, TCC0_GCLK_ID, ID_TCC0 },
|
||||
{ TCC1, TCC1_GCLK_ID, ID_TCC1 },
|
||||
{ TCC2, TCC2_GCLK_ID, ID_TCC2 },
|
||||
};
|
||||
|
||||
// PWM pins and their TCC device/channel
|
||||
struct gpio_pwm_info {
|
||||
uint8_t gpio, ptype, tcc, channel;
|
||||
};
|
||||
static const struct gpio_pwm_info pwm_regs[] = {
|
||||
{ GPIO('A', 4), 'E', 0, 0 },
|
||||
{ GPIO('A', 5), 'E', 0, 1 },
|
||||
{ GPIO('A', 6), 'E', 1, 0 },
|
||||
{ GPIO('A', 7), 'E', 1, 1 },
|
||||
{ GPIO('A', 8), 'E', 0, 0 },
|
||||
{ GPIO('A', 9), 'E', 0, 1 },
|
||||
{ GPIO('A', 10), 'E', 1, 0 },
|
||||
{ GPIO('A', 11), 'E', 1, 1 },
|
||||
{ GPIO('A', 12), 'E', 2, 0 },
|
||||
{ GPIO('A', 13), 'E', 2, 1 },
|
||||
{ GPIO('A', 16), 'E', 2, 0 },
|
||||
{ GPIO('A', 17), 'E', 2, 1 },
|
||||
{ GPIO('A', 18), 'F', 0, 2 },
|
||||
{ GPIO('A', 19), 'F', 0, 3 },
|
||||
{ GPIO('A', 24), 'F', 1, 2 },
|
||||
{ GPIO('A', 25), 'F', 1, 3 },
|
||||
{ GPIO('A', 30), 'E', 1, 0 },
|
||||
{ GPIO('A', 31), 'E', 1, 1 },
|
||||
{ GPIO('B', 30), 'E', 0, 0 },
|
||||
{ GPIO('B', 31), 'E', 0, 1 },
|
||||
};
|
||||
|
||||
#define MAX_PWM 255
|
||||
DECL_CONSTANT("PWM_MAX", MAX_PWM);
|
||||
|
||||
struct gpio_pwm
|
||||
gpio_pwm_setup(uint8_t pin, uint32_t cycle_time, uint8_t val)
|
||||
{
|
||||
// Find pin in pwm_regs table
|
||||
const struct gpio_pwm_info *p = pwm_regs;
|
||||
for (; ; p++) {
|
||||
if (p >= &pwm_regs[ARRAY_SIZE(pwm_regs)])
|
||||
shutdown("Not a valid PWM pin");
|
||||
if (p->gpio == pin)
|
||||
break;
|
||||
}
|
||||
|
||||
// Enable timer clock
|
||||
enable_pclock(tcc_info[p->tcc].pclk_id, tcc_info[p->tcc].pm_id);
|
||||
|
||||
// Map cycle_time to pwm clock divisor
|
||||
uint32_t cs;
|
||||
switch (cycle_time) {
|
||||
case 0 ... (1+2) * MAX_PWM / 2 - 1: cs = 0; break;
|
||||
case (1+2) * MAX_PWM / 2 ... (2+4) * MAX_PWM / 2 - 1: cs = 1; break;
|
||||
case (2+4) * MAX_PWM / 2 ... (4+8) * MAX_PWM / 2 - 1: cs = 2; break;
|
||||
case (4+8) * MAX_PWM / 2 ... (8+16) * MAX_PWM / 2 - 1: cs = 3; break;
|
||||
case (8+16) * MAX_PWM / 2 ... (16+64) * MAX_PWM / 2 - 1: cs = 4; break;
|
||||
case (16+64) * MAX_PWM / 2 ... (64+256) * MAX_PWM / 2 - 1: cs = 5; break;
|
||||
case (64+256) * MAX_PWM / 2 ... (256+1024) * MAX_PWM / 2 - 1: cs = 6; break;
|
||||
default: cs = 7; break;
|
||||
}
|
||||
uint32_t ctrla = TCC_CTRLA_ENABLE | TCC_CTRLA_PRESCALER(cs);
|
||||
|
||||
// Enable timer
|
||||
Tcc *tcc = tcc_info[p->tcc].tcc;
|
||||
uint32_t old_ctrla = tcc->CTRLA.reg;
|
||||
if (old_ctrla != ctrla) {
|
||||
if (old_ctrla & TCC_CTRLA_ENABLE)
|
||||
shutdown("PWM already programmed at different speed");
|
||||
tcc->CTRLA.reg = ctrla & ~TCC_CTRLA_ENABLE;
|
||||
tcc->WAVE.reg = TCC_WAVE_WAVEGEN_NPWM;
|
||||
tcc->PER.reg = MAX_PWM;
|
||||
tcc->CTRLA.reg = ctrla;
|
||||
}
|
||||
|
||||
// Set initial value
|
||||
struct gpio_pwm g = (struct gpio_pwm) { (void*)&tcc->CCB[p->channel].reg };
|
||||
gpio_pwm_write(g, val);
|
||||
|
||||
// Route output to pin
|
||||
gpio_peripheral(pin, p->ptype, 0);
|
||||
|
||||
return g;
|
||||
}
|
||||
|
||||
void
|
||||
gpio_pwm_write(struct gpio_pwm g, uint8_t val)
|
||||
{
|
||||
*(volatile uint32_t*)g.reg = val;
|
||||
}
|
||||
148
src/atsamd/i2c.c
Normal file
148
src/atsamd/i2c.c
Normal file
@@ -0,0 +1,148 @@
|
||||
// i2c support on samd
|
||||
//
|
||||
// Copyright (C) 2019 Florian Heilmann <Florian.Heilmann@gmx.net>
|
||||
// Copyright (C) 2018-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "internal.h" // enable_pclock
|
||||
#include "command.h" // shutdown
|
||||
#include "gpio.h" // i2c_setup
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
#define TIME_RISE 125ULL // 125 nanoseconds
|
||||
#define I2C_FREQ 100000
|
||||
|
||||
static void
|
||||
i2c_init(uint32_t bus, SercomI2cm *si)
|
||||
{
|
||||
static uint8_t have_run_init;
|
||||
if (have_run_init & (1<<bus))
|
||||
return;
|
||||
have_run_init |= 1<<bus;
|
||||
|
||||
// Configure i2c
|
||||
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);
|
||||
uint32_t baud = (freq/I2C_FREQ - 10 - freq*TIME_RISE/1000000000) / 2;
|
||||
si->BAUD.reg = baud;
|
||||
si->CTRLA.reg = areg | SERCOM_I2CM_CTRLA_ENABLE;
|
||||
while (si->SYNCBUSY.reg & SERCOM_I2CM_SYNCBUSY_ENABLE)
|
||||
;
|
||||
|
||||
// Go into idle mode
|
||||
si->STATUS.reg = SERCOM_I2CM_STATUS_BUSSTATE(1);
|
||||
while (si->SYNCBUSY.reg & SERCOM_I2CM_SYNCBUSY_SYSOP)
|
||||
;
|
||||
}
|
||||
|
||||
struct i2c_config
|
||||
i2c_setup(uint32_t bus, uint32_t rate, uint8_t addr)
|
||||
{
|
||||
Sercom *sercom = sercom_enable_pclock(bus);
|
||||
sercom_i2c_pins(bus);
|
||||
SercomI2cm *si = &sercom->I2CM;
|
||||
i2c_init(bus, si);
|
||||
return (struct i2c_config){ .si=si, .addr=addr<<1 };
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_wait(SercomI2cm *si)
|
||||
{
|
||||
for (;;) {
|
||||
uint32_t intflag = si->INTFLAG.reg;
|
||||
if (!(intflag & SERCOM_I2CM_INTFLAG_MB)) {
|
||||
if (si->STATUS.reg & SERCOM_I2CM_STATUS_BUSERR)
|
||||
shutdown("i2c buserror");
|
||||
continue;
|
||||
}
|
||||
if (intflag & SERCOM_I2CM_INTFLAG_ERROR)
|
||||
shutdown("i2c error");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_start(SercomI2cm *si, uint8_t addr)
|
||||
{
|
||||
si->ADDR.reg = addr;
|
||||
i2c_wait(si);
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_send_byte(SercomI2cm *si, uint8_t b)
|
||||
{
|
||||
si->DATA.reg = b;
|
||||
i2c_wait(si);
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_stop(SercomI2cm *si)
|
||||
{
|
||||
si->CTRLB.reg = SERCOM_I2CM_CTRLB_CMD(3);
|
||||
}
|
||||
|
||||
void
|
||||
i2c_write(struct i2c_config config, uint8_t write_len, uint8_t *write)
|
||||
{
|
||||
SercomI2cm *si = (SercomI2cm *)config.si;
|
||||
i2c_start(si, config.addr);
|
||||
while (write_len--)
|
||||
i2c_send_byte(si, *write++);
|
||||
i2c_stop(si);
|
||||
}
|
||||
|
||||
void
|
||||
i2c_read(struct i2c_config config, uint8_t reg_len, uint8_t *reg
|
||||
, uint8_t read_len, uint8_t *read)
|
||||
{
|
||||
SercomI2cm *si = (SercomI2cm *)config.si;
|
||||
|
||||
// start in write mode and write register if provided
|
||||
if(reg_len) {
|
||||
// start in write mode
|
||||
si->ADDR.reg = config.addr;
|
||||
while (!(si->INTFLAG.reg & SERCOM_I2CM_INTFLAG_MB));
|
||||
|
||||
// write registers
|
||||
while (reg_len--){
|
||||
si->DATA.reg = *reg++;
|
||||
while (!(si->INTFLAG.reg & SERCOM_I2CM_INTFLAG_MB));
|
||||
}
|
||||
}
|
||||
|
||||
// start with read bit enabled
|
||||
si->ADDR.reg = (config.addr | 0x1);
|
||||
|
||||
// read bytes from slave
|
||||
while (read_len--){
|
||||
while (!(si->INTFLAG.reg & SERCOM_I2CM_INTFLAG_SB));
|
||||
|
||||
if (read_len){
|
||||
// set ACK response
|
||||
si->CTRLB.reg &= ~SERCOM_I2CM_CTRLB_ACKACT;
|
||||
while (si->SYNCBUSY.bit.SYSOP);
|
||||
|
||||
// execute ACK succeded by byte read
|
||||
si->CTRLB.reg |= SERCOM_I2CM_CTRLB_CMD(2);
|
||||
while (si->SYNCBUSY.bit.SYSOP);
|
||||
} else {
|
||||
// set NACK response
|
||||
si->CTRLB.reg |= SERCOM_I2CM_CTRLB_ACKACT;
|
||||
while (si->SYNCBUSY.bit.SYSOP);
|
||||
|
||||
// execute NACK succeded by stop condition
|
||||
si->CTRLB.reg |= SERCOM_I2CM_CTRLB_CMD(3);
|
||||
while (si->SYNCBUSY.bit.SYSOP);
|
||||
}
|
||||
|
||||
// read received data byte
|
||||
*read++ = si->DATA.reg;
|
||||
}
|
||||
}
|
||||
30
src/atsamd/internal.h
Normal file
30
src/atsamd/internal.h
Normal file
@@ -0,0 +1,30 @@
|
||||
#ifndef __ATSAMD_INTERNAL_H
|
||||
#define __ATSAMD_INTERNAL_H
|
||||
// Local definitions for atsamd code
|
||||
|
||||
#include <stdint.h> // uint32_t
|
||||
#include "autoconf.h" // CONFIG_MACH_SAMD21A
|
||||
|
||||
#if CONFIG_MACH_SAMD21
|
||||
#include "samd21.h"
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
#include "samd51.h"
|
||||
#endif
|
||||
|
||||
#define GPIO(PORT, NUM) (((PORT)-'A') * 32 + (NUM))
|
||||
#define GPIO2PORT(PIN) ((PIN) / 32)
|
||||
#define GPIO2BIT(PIN) (1<<((PIN) % 32))
|
||||
|
||||
#define GET_FUSE(REG) \
|
||||
((*((uint32_t*)(REG##_ADDR)) & (REG##_Msk)) >> (REG##_Pos))
|
||||
|
||||
void enable_pclock(uint32_t pclk_id, uint32_t pm_id);
|
||||
uint32_t get_pclock_frequency(uint32_t pclk_id);
|
||||
void gpio_peripheral(uint32_t gpio, char ptype, int32_t pull_up);
|
||||
|
||||
Sercom * sercom_enable_pclock(uint32_t sercom_id);
|
||||
uint32_t sercom_get_pclock_frequency(uint32_t sercom_id);
|
||||
uint32_t sercom_spi_pins(uint32_t sercom_id);
|
||||
void sercom_i2c_pins(uint32_t sercom_id);
|
||||
|
||||
#endif // internal.h
|
||||
17
src/atsamd/main.c
Normal file
17
src/atsamd/main.c
Normal file
@@ -0,0 +1,17 @@
|
||||
// Main starting point for SAMD boards
|
||||
//
|
||||
// Copyright (C) 2018-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "board/armcm_boot.h" // armcm_main
|
||||
#include "internal.h" // SystemInit
|
||||
#include "sched.h" // sched_main
|
||||
|
||||
// Main entry point - called from armcm_boot.c:ResetHandler()
|
||||
void
|
||||
armcm_main(void)
|
||||
{
|
||||
SystemInit();
|
||||
sched_main();
|
||||
}
|
||||
206
src/atsamd/samd51_clock.c
Normal file
206
src/atsamd/samd51_clock.c
Normal file
@@ -0,0 +1,206 @@
|
||||
// Code to setup peripheral clocks on the SAMD51
|
||||
//
|
||||
// Copyright (C) 2018-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// 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 CLKGEN_48M 3
|
||||
#define CLKGEN_2M 4
|
||||
|
||||
#define FREQ_MAIN CONFIG_CLOCK_FREQ
|
||||
#define FREQ_32K 32768
|
||||
#define FREQ_48M 48000000
|
||||
#define FREQ_2M 2000000
|
||||
|
||||
// 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;
|
||||
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, uint32_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;
|
||||
}
|
||||
|
||||
// Return the frequency of the given peripheral clock
|
||||
uint32_t
|
||||
get_pclock_frequency(uint32_t pclk_id)
|
||||
{
|
||||
return FREQ_48M;
|
||||
}
|
||||
|
||||
// Configure a dpll to a given clock multiplier
|
||||
static void
|
||||
config_dpll(uint32_t pll, uint32_t mul, uint32_t ctrlb)
|
||||
{
|
||||
OSCCTRL->Dpll[pll].DPLLCTRLA.reg = 0;
|
||||
while (OSCCTRL->Dpll[pll].DPLLSYNCBUSY.reg & OSCCTRL_DPLLSYNCBUSY_ENABLE)
|
||||
;
|
||||
OSCCTRL->Dpll[pll].DPLLRATIO.reg = OSCCTRL_DPLLRATIO_LDR(mul - 1);
|
||||
while (OSCCTRL->Dpll[pll].DPLLSYNCBUSY.reg & OSCCTRL_DPLLSYNCBUSY_DPLLRATIO)
|
||||
;
|
||||
OSCCTRL->Dpll[pll].DPLLCTRLB.reg = ctrlb | OSCCTRL_DPLLCTRLB_LBYPASS;
|
||||
OSCCTRL->Dpll[pll].DPLLCTRLA.reg = OSCCTRL_DPLLCTRLA_ENABLE;
|
||||
uint32_t mask = OSCCTRL_DPLLSTATUS_CLKRDY | OSCCTRL_DPLLSTATUS_LOCK;
|
||||
while ((OSCCTRL->Dpll[pll].DPLLSTATUS.reg & mask) != mask)
|
||||
;
|
||||
}
|
||||
|
||||
// Configure the dfll
|
||||
static void
|
||||
config_dfll(uint32_t dfllmul, uint32_t ctrlb)
|
||||
{
|
||||
// Disable the dfllmul and reenable in this order due to chip errata
|
||||
OSCCTRL->DFLLCTRLA.reg = 0;
|
||||
while (OSCCTRL->DFLLSYNC.reg & OSCCTRL_DFLLSYNC_ENABLE)
|
||||
;
|
||||
OSCCTRL->DFLLMUL.reg = dfllmul;
|
||||
while (OSCCTRL->DFLLSYNC.reg & OSCCTRL_DFLLSYNC_DFLLMUL)
|
||||
;
|
||||
OSCCTRL->DFLLCTRLB.reg = 0;
|
||||
while (OSCCTRL->DFLLSYNC.reg & OSCCTRL_DFLLSYNC_DFLLCTRLB)
|
||||
;
|
||||
OSCCTRL->DFLLCTRLA.reg = OSCCTRL_DFLLCTRLA_ENABLE;
|
||||
while (OSCCTRL->DFLLSYNC.reg & OSCCTRL_DFLLSYNC_ENABLE)
|
||||
;
|
||||
OSCCTRL->DFLLVAL.reg = OSCCTRL->DFLLVAL.reg;
|
||||
while(OSCCTRL->DFLLSYNC.reg & OSCCTRL_DFLLSYNC_DFLLVAL)
|
||||
;
|
||||
OSCCTRL->DFLLCTRLB.reg = ctrlb;
|
||||
while (OSCCTRL->DFLLSYNC.reg & OSCCTRL_DFLLSYNC_DFLLCTRLB)
|
||||
;
|
||||
}
|
||||
|
||||
#if CONFIG_CLOCK_REF_X32K
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_crystal", "PA0,PA1");
|
||||
#elif CONFIG_CLOCK_REF_X25M
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_crystal", "PB22,PB23");
|
||||
#endif
|
||||
|
||||
// Initialize the clocks using an external 32K crystal
|
||||
static void
|
||||
clock_init_32k(void)
|
||||
{
|
||||
// Enable external 32Khz crystal
|
||||
uint32_t val = (OSC32KCTRL_XOSC32K_ENABLE | OSC32KCTRL_XOSC32K_EN32K
|
||||
| OSC32KCTRL_XOSC32K_CGM_XT | OSC32KCTRL_XOSC32K_XTALEN);
|
||||
OSC32KCTRL->XOSC32K.reg = val;
|
||||
while (!(OSC32KCTRL->STATUS.reg & OSC32KCTRL_STATUS_XOSC32KRDY))
|
||||
;
|
||||
|
||||
// Generate 120Mhz clock on PLL0 (with XOSC32 as reference)
|
||||
uint32_t mul = DIV_ROUND_CLOSEST(FREQ_MAIN, FREQ_32K);
|
||||
config_dpll(0, mul, OSCCTRL_DPLLCTRLB_REFCLK_XOSC32);
|
||||
|
||||
// Switch main clock to 120Mhz PLL0
|
||||
gen_clock(CLKGEN_MAIN, GCLK_GENCTRL_SRC_DPLL0);
|
||||
|
||||
// Generate 48Mhz clock on PLL1 (with XOSC32 as reference)
|
||||
mul = DIV_ROUND_CLOSEST(FREQ_48M, FREQ_32K);
|
||||
config_dpll(1, mul, OSCCTRL_DPLLCTRLB_REFCLK_XOSC32);
|
||||
gen_clock(CLKGEN_48M, GCLK_GENCTRL_SRC_DPLL1);
|
||||
}
|
||||
|
||||
// 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_IPTAT(3) | OSCCTRL_XOSCCTRL_IMULT(6));
|
||||
OSCCTRL->XOSCCTRL[1].reg = val;
|
||||
while (!(OSCCTRL->STATUS.reg & OSCCTRL_STATUS_XOSCRDY1))
|
||||
;
|
||||
|
||||
// Generate 120Mhz clock on PLL0 (with XOSC1 as reference)
|
||||
uint32_t p0div = 10, p0mul = DIV_ROUND_CLOSEST(FREQ_MAIN, freq_xosc/p0div);
|
||||
uint32_t p0ctrlb = OSCCTRL_DPLLCTRLB_DIV(p0div / 2 - 1);
|
||||
config_dpll(0, p0mul, p0ctrlb | OSCCTRL_DPLLCTRLB_REFCLK_XOSC1);
|
||||
|
||||
// Switch main clock to 120Mhz PLL0
|
||||
gen_clock(CLKGEN_MAIN, GCLK_GENCTRL_SRC_DPLL0);
|
||||
|
||||
// Generate 48Mhz clock on PLL1 (with XOSC1 as reference)
|
||||
uint32_t p1div = 50, p1mul = DIV_ROUND_CLOSEST(FREQ_48M, freq_xosc/p1div);
|
||||
uint32_t p1ctrlb = OSCCTRL_DPLLCTRLB_DIV(p1div / 2 - 1);
|
||||
config_dpll(1, p1mul, p1ctrlb | OSCCTRL_DPLLCTRLB_REFCLK_XOSC1);
|
||||
gen_clock(CLKGEN_48M, GCLK_GENCTRL_SRC_DPLL1);
|
||||
}
|
||||
|
||||
// Initialize clocks from factory calibrated internal clock
|
||||
static void
|
||||
clock_init_internal(void)
|
||||
{
|
||||
// Enable USB clock recovery mode if applicable
|
||||
if (CONFIG_USBSERIAL) {
|
||||
// Temporarily switch main clock to internal 32K clock
|
||||
gen_clock(CLKGEN_MAIN, GCLK_GENCTRL_SRC_OSCULP32K);
|
||||
|
||||
// Configure DFLL48M clock (with USB 1Khz SOF as reference)
|
||||
uint32_t mul = DIV_ROUND_CLOSEST(FREQ_48M, 1000);
|
||||
uint32_t dfllmul = OSCCTRL_DFLLMUL_FSTEP(10) | OSCCTRL_DFLLMUL_MUL(mul);
|
||||
uint32_t ctrlb = (OSCCTRL_DFLLCTRLB_MODE | OSCCTRL_DFLLCTRLB_USBCRM
|
||||
| OSCCTRL_DFLLCTRLB_CCDIS);
|
||||
config_dfll(dfllmul, ctrlb);
|
||||
}
|
||||
|
||||
// Route factory calibrated DFLL48M to CLKGEN_48M
|
||||
gen_clock(CLKGEN_48M, GCLK_GENCTRL_SRC_DFLL);
|
||||
|
||||
// Generate CLKGEN_2M (with CLKGEN_48M as reference)
|
||||
uint32_t div = DIV_ROUND_CLOSEST(FREQ_48M, FREQ_2M);
|
||||
gen_clock(CLKGEN_2M, GCLK_GENCTRL_SRC_DFLL | GCLK_GENCTRL_DIV(div));
|
||||
|
||||
// Generate 120Mhz clock on PLL0 (with CLKGEN_2M as reference)
|
||||
route_pclock(OSCCTRL_GCLK_ID_FDPLL0, CLKGEN_2M);
|
||||
uint32_t mul = DIV_ROUND_CLOSEST(FREQ_MAIN, FREQ_2M);
|
||||
config_dpll(0, mul, OSCCTRL_DPLLCTRLB_REFCLK_GCLK);
|
||||
|
||||
// Switch main clock to 120Mhz PLL0
|
||||
gen_clock(CLKGEN_MAIN, GCLK_GENCTRL_SRC_DPLL0);
|
||||
}
|
||||
|
||||
void
|
||||
SystemInit(void)
|
||||
{
|
||||
// Reset GCLK
|
||||
GCLK->CTRLA.reg = GCLK_CTRLA_SWRST;
|
||||
while (GCLK->SYNCBUSY.reg & GCLK_SYNCBUSY_SWRST)
|
||||
;
|
||||
|
||||
// Init clocks
|
||||
if (CONFIG_CLOCK_REF_X32K)
|
||||
clock_init_32k();
|
||||
else if (CONFIG_CLOCK_REF_X25M)
|
||||
clock_init_25m();
|
||||
else
|
||||
clock_init_internal();
|
||||
|
||||
// Enable SAMD51 cache
|
||||
CMCC->CTRL.reg = 1;
|
||||
}
|
||||
24
src/atsamd/samd51_watchdog.c
Normal file
24
src/atsamd/samd51_watchdog.c
Normal file
@@ -0,0 +1,24 @@
|
||||
// Watchdog handler on SAMD21 boards
|
||||
//
|
||||
// Copyright (C) 2018-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "internal.h" // WDT
|
||||
#include "sched.h" // DECL_TASK
|
||||
|
||||
void
|
||||
watchdog_reset(void)
|
||||
{
|
||||
if (!(WDT->SYNCBUSY.reg & WDT_SYNCBUSY_CLEAR))
|
||||
WDT->CLEAR.reg = 0xa5;
|
||||
}
|
||||
DECL_TASK(watchdog_reset);
|
||||
|
||||
void
|
||||
watchdog_init(void)
|
||||
{
|
||||
WDT->CONFIG.reg = WDT_CONFIG_PER(6); // 500ms timeout
|
||||
WDT->CTRLA.reg = WDT_CTRLA_ENABLE;
|
||||
}
|
||||
DECL_INIT(watchdog_init);
|
||||
387
src/atsamd/sercom.c
Normal file
387
src/atsamd/sercom.c
Normal file
@@ -0,0 +1,387 @@
|
||||
// Handling of sercom pins
|
||||
//
|
||||
// Copyright (C) 2019 Florian Heilmann <Florian.Heilmann@gmx.net>
|
||||
// Copyright (C) 2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "internal.h" // sercom_enable
|
||||
#include "command.h" // shutdown
|
||||
#include "compiler.h" // ARRAY_SIZE
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Available sercom blocks
|
||||
****************************************************************/
|
||||
|
||||
DECL_ENUMERATION_RANGE("bus", "sercom0", 0, 8);
|
||||
|
||||
struct sercom_bus {
|
||||
Sercom *sercom;
|
||||
uint32_t pclk_id, pm_id;
|
||||
};
|
||||
|
||||
static const struct sercom_bus sercoms[] = {
|
||||
{ SERCOM0, SERCOM0_GCLK_ID_CORE, ID_SERCOM0 },
|
||||
{ SERCOM1, SERCOM1_GCLK_ID_CORE, ID_SERCOM1 },
|
||||
{ SERCOM2, SERCOM2_GCLK_ID_CORE, ID_SERCOM2 },
|
||||
{ SERCOM3, SERCOM3_GCLK_ID_CORE, ID_SERCOM3 },
|
||||
#ifdef SERCOM4
|
||||
{ SERCOM4, SERCOM4_GCLK_ID_CORE, ID_SERCOM4 },
|
||||
{ SERCOM5, SERCOM5_GCLK_ID_CORE, ID_SERCOM5 },
|
||||
#endif
|
||||
#ifdef SERCOM6
|
||||
{ SERCOM6, SERCOM6_GCLK_ID_CORE, ID_SERCOM6 },
|
||||
{ SERCOM7, SERCOM7_GCLK_ID_CORE, ID_SERCOM7 },
|
||||
#endif
|
||||
};
|
||||
|
||||
Sercom *
|
||||
sercom_enable_pclock(uint32_t sercom_id)
|
||||
{
|
||||
if (sercom_id >= ARRAY_SIZE(sercoms))
|
||||
shutdown("Invalid SERCOM bus");
|
||||
const struct sercom_bus *sb = &sercoms[sercom_id];
|
||||
enable_pclock(sb->pclk_id, sb->pm_id);
|
||||
return sb->sercom;
|
||||
}
|
||||
|
||||
uint32_t
|
||||
sercom_get_pclock_frequency(uint32_t sercom_id)
|
||||
{
|
||||
const struct sercom_bus *sb = &sercoms[sercom_id];
|
||||
return get_pclock_frequency(sb->pclk_id);
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Pin configurations
|
||||
****************************************************************/
|
||||
|
||||
struct sercom_pad {
|
||||
uint8_t sercom_id, gpio, pad, ptype;
|
||||
};
|
||||
|
||||
static const struct sercom_pad sercom_pads[] = {
|
||||
#if CONFIG_MACH_SAMD21
|
||||
{ 0, GPIO('A', 8), 0, 'C'},
|
||||
{ 0, GPIO('A', 9), 1, 'C'},
|
||||
{ 0, GPIO('A', 10), 2, 'C'},
|
||||
{ 0, GPIO('A', 11), 3, 'C'},
|
||||
{ 0, GPIO('A', 4), 0, 'D'},
|
||||
{ 0, GPIO('A', 5), 1, 'D'},
|
||||
{ 0, GPIO('A', 6), 2, 'D'},
|
||||
{ 0, GPIO('A', 7), 3, 'D'},
|
||||
{ 1, GPIO('A', 16), 0, 'C'},
|
||||
{ 1, GPIO('A', 17), 1, 'C'},
|
||||
{ 1, GPIO('A', 18), 2, 'C'},
|
||||
{ 1, GPIO('A', 19), 3, 'C'},
|
||||
{ 1, GPIO('A', 0), 0, 'D'},
|
||||
{ 1, GPIO('A', 1), 1, 'D'},
|
||||
{ 1, GPIO('A', 30), 2, 'D'},
|
||||
{ 1, GPIO('A', 31), 3, 'D'},
|
||||
{ 2, GPIO('A', 12), 0, 'C'},
|
||||
{ 2, GPIO('A', 13), 1, 'C'},
|
||||
{ 2, GPIO('A', 14), 2, 'C'},
|
||||
{ 2, GPIO('A', 15), 3, 'C'},
|
||||
{ 2, GPIO('A', 8), 0, 'D'},
|
||||
{ 2, GPIO('A', 9), 1, 'D'},
|
||||
{ 2, GPIO('A', 10), 2, 'D'},
|
||||
{ 2, GPIO('A', 11), 3, 'D'},
|
||||
{ 3, GPIO('A', 22), 0, 'C'},
|
||||
{ 3, GPIO('A', 23), 1, 'C'},
|
||||
{ 3, GPIO('A', 24), 2, 'C'},
|
||||
{ 3, GPIO('A', 25), 3, 'C'},
|
||||
{ 3, GPIO('A', 16), 0, 'D'},
|
||||
{ 3, GPIO('A', 17), 1, 'D'},
|
||||
{ 3, GPIO('A', 18), 2, 'D'},
|
||||
{ 3, GPIO('A', 19), 3, 'D'},
|
||||
{ 3, GPIO('A', 20), 2, 'D'},
|
||||
{ 3, GPIO('A', 21), 3, 'D'},
|
||||
{ 4, GPIO('B', 12), 0, 'C'},
|
||||
{ 4, GPIO('B', 13), 1, 'C'},
|
||||
{ 4, GPIO('B', 14), 2, 'C'},
|
||||
{ 4, GPIO('B', 15), 3, 'C'},
|
||||
{ 4, GPIO('B', 8), 0, 'D'},
|
||||
{ 4, GPIO('B', 9), 1, 'D'},
|
||||
{ 4, GPIO('B', 10), 2, 'D'},
|
||||
{ 4, GPIO('B', 11), 3, 'D'},
|
||||
{ 4, GPIO('A', 12), 0, 'D'},
|
||||
{ 4, GPIO('A', 13), 1, 'D'},
|
||||
{ 4, GPIO('A', 14), 2, 'D'},
|
||||
{ 4, GPIO('A', 15), 3, 'D'},
|
||||
{ 5, GPIO('B', 16), 0, 'C'},
|
||||
{ 5, GPIO('B', 17), 1, 'C'},
|
||||
{ 5, GPIO('A', 20), 2, 'C'},
|
||||
{ 5, GPIO('A', 21), 3, 'C'},
|
||||
{ 5, GPIO('A', 22), 0, 'D'},
|
||||
{ 5, GPIO('A', 23), 1, 'D'},
|
||||
{ 5, GPIO('A', 24), 2, 'D'},
|
||||
{ 5, GPIO('A', 25), 3, 'D'},
|
||||
{ 5, GPIO('B', 30), 0, 'D'},
|
||||
{ 5, GPIO('B', 31), 1, 'D'},
|
||||
{ 5, GPIO('B', 22), 2, 'D'},
|
||||
{ 5, GPIO('B', 23), 3, 'D'},
|
||||
{ 5, GPIO('B', 2), 0, 'D'},
|
||||
{ 5, GPIO('B', 3), 1, 'D'},
|
||||
{ 5, GPIO('B', 0), 2, 'D'},
|
||||
{ 5, GPIO('B', 1), 3, 'D'},
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
{ 0, GPIO('A', 8), 0, 'C'},
|
||||
{ 0, GPIO('A', 9), 1, 'C'},
|
||||
{ 0, GPIO('A', 10), 2, 'C'},
|
||||
{ 0, GPIO('A', 11), 3, 'C'},
|
||||
{ 0, GPIO('B', 24), 0, 'C'},
|
||||
{ 0, GPIO('B', 25), 1, 'C'},
|
||||
{ 0, GPIO('C', 24), 2, 'C'},
|
||||
{ 0, GPIO('C', 25), 3, 'C'},
|
||||
{ 0, GPIO('A', 4), 0, 'D'},
|
||||
{ 0, GPIO('A', 5), 1, 'D'},
|
||||
{ 0, GPIO('A', 6), 2, 'D'},
|
||||
{ 0, GPIO('A', 7), 3, 'D'},
|
||||
{ 0, GPIO('C', 17), 0, 'D'},
|
||||
{ 0, GPIO('C', 16), 1, 'D'},
|
||||
{ 0, GPIO('C', 18), 2, 'D'},
|
||||
{ 0, GPIO('C', 19), 3, 'D'},
|
||||
|
||||
{ 1, GPIO('A', 16), 0, 'C'},
|
||||
{ 1, GPIO('A', 17), 1, 'C'},
|
||||
{ 1, GPIO('A', 18), 2, 'C'},
|
||||
{ 1, GPIO('A', 19), 3, 'C'},
|
||||
{ 1, GPIO('C', 22), 0, 'C'},
|
||||
{ 1, GPIO('C', 23), 1, 'C'},
|
||||
{ 1, GPIO('D', 20), 2, 'C'},
|
||||
{ 1, GPIO('D', 21), 3, 'C'},
|
||||
{ 1, GPIO('C', 27), 0, 'C'},
|
||||
{ 1, GPIO('C', 28), 1, 'C'},
|
||||
{ 1, GPIO('B', 22), 2, 'C'},
|
||||
{ 1, GPIO('B', 23), 3, 'C'},
|
||||
{ 1, GPIO('A', 0), 0, 'D'},
|
||||
{ 1, GPIO('A', 1), 1, 'D'},
|
||||
{ 1, GPIO('A', 30), 2, 'D'},
|
||||
{ 1, GPIO('A', 31), 3, 'D'},
|
||||
|
||||
{ 2, GPIO('A', 12), 0, 'C'},
|
||||
{ 2, GPIO('A', 13), 1, 'C'},
|
||||
{ 2, GPIO('A', 14), 2, 'C'},
|
||||
{ 2, GPIO('A', 15), 3, 'C'},
|
||||
{ 2, GPIO('B', 26), 0, 'C'},
|
||||
{ 2, GPIO('B', 27), 1, 'C'},
|
||||
{ 2, GPIO('B', 28), 2, 'C'},
|
||||
{ 2, GPIO('B', 29), 3, 'C'},
|
||||
{ 2, GPIO('A', 9), 0, 'D'},
|
||||
{ 2, GPIO('A', 8), 1, 'D'},
|
||||
{ 2, GPIO('A', 10), 2, 'D'},
|
||||
{ 2, GPIO('A', 11), 3, 'D'},
|
||||
{ 2, GPIO('B', 25), 0, 'D'},
|
||||
{ 2, GPIO('B', 24), 1, 'D'},
|
||||
{ 2, GPIO('C', 24), 2, 'D'},
|
||||
{ 2, GPIO('C', 25), 3, 'D'},
|
||||
|
||||
{ 3, GPIO('A', 22), 0, 'C'},
|
||||
{ 3, GPIO('A', 23), 1, 'C'},
|
||||
{ 3, GPIO('A', 24), 2, 'C'},
|
||||
{ 3, GPIO('A', 25), 3, 'C'},
|
||||
{ 3, GPIO('B', 20), 0, 'C'},
|
||||
{ 3, GPIO('B', 21), 1, 'C'},
|
||||
{ 3, GPIO('A', 20), 2, 'D'},
|
||||
{ 3, GPIO('A', 21), 3, 'D'},
|
||||
{ 3, GPIO('A', 17), 0, 'D'},
|
||||
{ 3, GPIO('A', 16), 1, 'D'},
|
||||
{ 3, GPIO('A', 18), 2, 'D'},
|
||||
{ 3, GPIO('A', 19), 3, 'D'},
|
||||
{ 3, GPIO('C', 23), 0, 'D'},
|
||||
{ 3, GPIO('C', 22), 1, 'D'},
|
||||
{ 3, GPIO('D', 20), 2, 'D'},
|
||||
{ 3, GPIO('D', 21), 3, 'D'},
|
||||
|
||||
{ 4, GPIO('B', 12), 0, 'C'},
|
||||
{ 4, GPIO('B', 13), 1, 'C'},
|
||||
{ 4, GPIO('B', 14), 2, 'C'},
|
||||
{ 4, GPIO('B', 15), 3, 'C'},
|
||||
{ 4, GPIO('B', 8), 0, 'D'},
|
||||
{ 4, GPIO('B', 9), 1, 'D'},
|
||||
{ 4, GPIO('B', 10), 2, 'D'},
|
||||
{ 4, GPIO('B', 11), 3, 'D'},
|
||||
{ 4, GPIO('A', 13), 0, 'D'},
|
||||
{ 4, GPIO('A', 12), 1, 'D'},
|
||||
{ 4, GPIO('A', 14), 2, 'D'},
|
||||
{ 4, GPIO('A', 15), 3, 'D'},
|
||||
{ 4, GPIO('B', 27), 0, 'D'},
|
||||
{ 4, GPIO('B', 26), 1, 'D'},
|
||||
{ 4, GPIO('B', 28), 2, 'D'},
|
||||
{ 4, GPIO('B', 29), 3, 'D'},
|
||||
|
||||
{ 5, GPIO('B', 16), 0, 'C'},
|
||||
{ 5, GPIO('B', 17), 1, 'C'},
|
||||
{ 5, GPIO('B', 18), 2, 'C'},
|
||||
{ 5, GPIO('B', 19), 3, 'C'},
|
||||
{ 5, GPIO('A', 23), 0, 'D'},
|
||||
{ 5, GPIO('A', 22), 1, 'D'},
|
||||
{ 5, GPIO('A', 20), 2, 'D'},
|
||||
{ 5, GPIO('A', 21), 3, 'D'},
|
||||
{ 5, GPIO('A', 24), 2, 'D'},
|
||||
{ 5, GPIO('A', 25), 3, 'D'},
|
||||
{ 5, GPIO('B', 22), 2, 'D'},
|
||||
{ 5, GPIO('B', 23), 3, 'D'},
|
||||
{ 5, GPIO('B', 31), 0, 'D'},
|
||||
{ 5, GPIO('B', 30), 1, 'D'},
|
||||
{ 5, GPIO('B', 0), 2, 'D'},
|
||||
{ 5, GPIO('B', 1), 3, 'D'},
|
||||
{ 5, GPIO('B', 2), 0, 'D'},
|
||||
{ 5, GPIO('B', 3), 1, 'D'},
|
||||
#ifdef SERCOM6
|
||||
{ 6, GPIO('C', 16), 0, 'C'},
|
||||
{ 6, GPIO('C', 17), 1, 'C'},
|
||||
{ 6, GPIO('C', 18), 2, 'C'},
|
||||
{ 6, GPIO('C', 19), 3, 'C'},
|
||||
{ 6, GPIO('C', 4), 0, 'C'},
|
||||
{ 6, GPIO('C', 5), 1, 'C'},
|
||||
{ 6, GPIO('C', 6), 2, 'C'},
|
||||
{ 6, GPIO('C', 7), 3, 'C'},
|
||||
{ 6, GPIO('D', 9), 0, 'D'},
|
||||
{ 6, GPIO('D', 8), 1, 'D'},
|
||||
{ 6, GPIO('D', 10), 2, 'D'},
|
||||
{ 6, GPIO('D', 11), 3, 'D'},
|
||||
{ 6, GPIO('C', 13), 0, 'D'},
|
||||
{ 6, GPIO('C', 12), 1, 'D'},
|
||||
{ 6, GPIO('C', 14), 2, 'D'},
|
||||
{ 6, GPIO('C', 15), 3, 'D'},
|
||||
{ 6, GPIO('C', 10), 2, 'C'},
|
||||
{ 6, GPIO('C', 11), 3, 'C'},
|
||||
|
||||
{ 7, GPIO('C', 12), 0, 'C'},
|
||||
{ 7, GPIO('C', 13), 1, 'C'},
|
||||
{ 7, GPIO('C', 14), 2, 'C'},
|
||||
{ 7, GPIO('C', 15), 3, 'C'},
|
||||
{ 7, GPIO('D', 8), 0, 'C'},
|
||||
{ 7, GPIO('D', 9), 1, 'C'},
|
||||
{ 7, GPIO('D', 10), 2, 'C'},
|
||||
{ 7, GPIO('D', 11), 3, 'C'},
|
||||
{ 7, GPIO('C', 10), 2, 'D'},
|
||||
{ 7, GPIO('C', 11), 3, 'D'},
|
||||
{ 7, GPIO('B', 21), 0, 'D'},
|
||||
{ 7, GPIO('B', 20), 1, 'D'},
|
||||
{ 7, GPIO('B', 18), 2, 'D'},
|
||||
{ 7, GPIO('B', 19), 3, 'D'},
|
||||
{ 7, GPIO('B', 30), 0, 'C'},
|
||||
{ 7, GPIO('B', 31), 1, 'C'},
|
||||
{ 7, GPIO('A', 30), 2, 'C'},
|
||||
{ 7, GPIO('A', 31), 3, 'C'},
|
||||
#endif
|
||||
#endif
|
||||
};
|
||||
|
||||
static const struct sercom_pad *
|
||||
sercom_lookup_pad(uint32_t sercom_id, uint8_t pin)
|
||||
{
|
||||
const struct sercom_pad *sp = sercom_pads;
|
||||
for (; ; sp++) {
|
||||
if (sp >= &sercom_pads[ARRAY_SIZE(sercom_pads)])
|
||||
shutdown("Invalid SERCOM configuration");
|
||||
if (sp->sercom_id == sercom_id && sp->gpio == pin)
|
||||
return sp;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Runtime configuration
|
||||
****************************************************************/
|
||||
|
||||
enum { TX_PIN, RX_PIN, CLK_PIN };
|
||||
DECL_ENUMERATION("sercom_pin_type", "tx", TX_PIN);
|
||||
DECL_ENUMERATION("sercom_pin_type", "rx", RX_PIN);
|
||||
DECL_ENUMERATION("sercom_pin_type", "clk", CLK_PIN);
|
||||
|
||||
// Runtime configuration
|
||||
struct sercom_pin {
|
||||
uint8_t pins[3];
|
||||
};
|
||||
|
||||
static struct sercom_pin sercom_pins[ARRAY_SIZE(sercoms)];
|
||||
|
||||
void
|
||||
command_set_sercom_pin(uint32_t *args)
|
||||
{
|
||||
uint8_t sercom_id = args[0], pin_type = args[1], pin = args[2];
|
||||
if (sercom_id >= ARRAY_SIZE(sercom_pins)
|
||||
|| pin_type >= ARRAY_SIZE(sercom_pins[0].pins))
|
||||
shutdown("Invalid SERCOM bus");
|
||||
sercom_pins[sercom_id].pins[pin_type] = pin;
|
||||
}
|
||||
DECL_COMMAND(command_set_sercom_pin,
|
||||
"set_sercom_pin bus=%u sercom_pin_type=%u pin=%u");
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* SPI dopo flag mapping
|
||||
****************************************************************/
|
||||
|
||||
struct sercom_spi_map {
|
||||
uint8_t tx_pad, clk_pad, dopo;
|
||||
};
|
||||
|
||||
static const struct sercom_spi_map sercom_spi[] = {
|
||||
{ 0, 1, 0 },
|
||||
{ 3, 1, 2 },
|
||||
#if CONFIG_MACH_SAMD21
|
||||
{ 2, 3, 1 },
|
||||
{ 0, 3, 3 },
|
||||
#endif
|
||||
};
|
||||
|
||||
static uint8_t
|
||||
sercom_lookup_spi_dopo(uint8_t tx_pad, uint8_t clk_pad)
|
||||
{
|
||||
const struct sercom_spi_map *sm = sercom_spi;
|
||||
for (; ; sm++) {
|
||||
if (sm >= &sercom_spi[ARRAY_SIZE(sercom_spi)])
|
||||
shutdown("Invalid combination of TX pin and CLK pin");
|
||||
if (sm->tx_pad == tx_pad && sm->clk_pad == clk_pad)
|
||||
return sm->dopo;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Pin setup
|
||||
****************************************************************/
|
||||
|
||||
uint32_t
|
||||
sercom_spi_pins(uint32_t sercom_id)
|
||||
{
|
||||
if (sercom_id >= ARRAY_SIZE(sercom_pins))
|
||||
shutdown("Invalid SERCOM bus");
|
||||
uint8_t tx_pin = sercom_pins[sercom_id].pins[TX_PIN];
|
||||
const struct sercom_pad *tx_sp = sercom_lookup_pad(sercom_id, tx_pin);
|
||||
uint8_t rx_pin = sercom_pins[sercom_id].pins[RX_PIN];
|
||||
const struct sercom_pad *rx_sp = sercom_lookup_pad(sercom_id, rx_pin);
|
||||
uint8_t clk_pin = sercom_pins[sercom_id].pins[CLK_PIN];
|
||||
const struct sercom_pad *clk_sp = sercom_lookup_pad(sercom_id, clk_pin);
|
||||
|
||||
uint8_t dopo = sercom_lookup_spi_dopo(tx_sp->pad, clk_sp->pad);
|
||||
if (rx_sp->pad == tx_sp->pad || rx_sp->pad == clk_sp->pad)
|
||||
shutdown("Sercom RX pad collides with TX or CLK pad");
|
||||
|
||||
gpio_peripheral(tx_pin, tx_sp->ptype, 0);
|
||||
gpio_peripheral(rx_pin, rx_sp->ptype, 0);
|
||||
gpio_peripheral(clk_pin, clk_sp->ptype, 0);
|
||||
return SERCOM_SPI_CTRLA_DIPO(rx_sp->pad) | SERCOM_SPI_CTRLA_DOPO(dopo);
|
||||
}
|
||||
|
||||
void
|
||||
sercom_i2c_pins(uint32_t sercom_id)
|
||||
{
|
||||
uint8_t tx_pin = sercom_pins[sercom_id].pins[TX_PIN];
|
||||
const struct sercom_pad *tx_sp = sercom_lookup_pad(sercom_id, tx_pin);
|
||||
uint8_t clk_pin = sercom_pins[sercom_id].pins[CLK_PIN];
|
||||
const struct sercom_pad *clk_sp = sercom_lookup_pad(sercom_id, clk_pin);
|
||||
|
||||
if (tx_sp->pad != 0 || clk_sp->pad != 1)
|
||||
shutdown("TX pin not on PAD0 or CLK pin not on PAD1");
|
||||
|
||||
gpio_peripheral(tx_pin, tx_sp->ptype, 0);
|
||||
gpio_peripheral(clk_pin, clk_sp->ptype, 0);
|
||||
}
|
||||
71
src/atsamd/serial.c
Normal file
71
src/atsamd/serial.c
Normal file
@@ -0,0 +1,71 @@
|
||||
// samd21 serial port
|
||||
//
|
||||
// Copyright (C) 2018-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "board/armcm_boot.h" // armcm_enable_irq
|
||||
#include "board/serial_irq.h" // serial_rx_data
|
||||
#include "command.h" // DECL_CONSTANT_STR
|
||||
#include "internal.h" // enable_pclock
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
void
|
||||
serial_enable_tx_irq(void)
|
||||
{
|
||||
SERCOM0->USART.INTENSET.reg = SERCOM_USART_INTENSET_DRE;
|
||||
}
|
||||
|
||||
void
|
||||
SERCOM0_Handler(void)
|
||||
{
|
||||
uint32_t status = SERCOM0->USART.INTFLAG.reg;
|
||||
if (status & SERCOM_USART_INTFLAG_RXC)
|
||||
serial_rx_byte(SERCOM0->USART.DATA.reg);
|
||||
if (status & SERCOM_USART_INTFLAG_DRE) {
|
||||
uint8_t data;
|
||||
int ret = serial_get_tx_byte(&data);
|
||||
if (ret)
|
||||
SERCOM0->USART.INTENCLR.reg = SERCOM_USART_INTENSET_DRE;
|
||||
else
|
||||
SERCOM0->USART.DATA.reg = data;
|
||||
}
|
||||
}
|
||||
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PA11,PA10");
|
||||
|
||||
void
|
||||
serial_init(void)
|
||||
{
|
||||
// Enable serial clock
|
||||
enable_pclock(SERCOM0_GCLK_ID_CORE, ID_SERCOM0);
|
||||
// Enable pins
|
||||
gpio_peripheral(GPIO('A', 11), 'C', 0);
|
||||
gpio_peripheral(GPIO('A', 10), 'C', 0);
|
||||
// Configure serial
|
||||
SercomUsart *su = &SERCOM0->USART;
|
||||
su->CTRLA.reg = 0;
|
||||
uint32_t areg = (SERCOM_USART_CTRLA_MODE(1)
|
||||
| SERCOM_USART_CTRLA_DORD
|
||||
| SERCOM_USART_CTRLA_SAMPR(1)
|
||||
| SERCOM_USART_CTRLA_RXPO(3)
|
||||
| SERCOM_USART_CTRLA_TXPO(1));
|
||||
su->CTRLA.reg = areg;
|
||||
su->CTRLB.reg = SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN;
|
||||
uint32_t freq = get_pclock_frequency(SERCOM0_GCLK_ID_CORE);
|
||||
uint32_t baud8 = freq / (2 * CONFIG_SERIAL_BAUD);
|
||||
su->BAUD.reg = (SERCOM_USART_BAUD_FRAC_BAUD(baud8 / 8)
|
||||
| SERCOM_USART_BAUD_FRAC_FP(baud8 % 8));
|
||||
// enable irqs
|
||||
su->INTENSET.reg = SERCOM_USART_INTENSET_RXC;
|
||||
su->CTRLA.reg = areg | SERCOM_USART_CTRLA_ENABLE;
|
||||
#if CONFIG_MACH_SAMD21
|
||||
armcm_enable_irq(SERCOM0_Handler, SERCOM0_IRQn, 0);
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
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);
|
||||
armcm_enable_irq(SERCOM0_Handler, SERCOM0_3_IRQn, 0);
|
||||
#endif
|
||||
}
|
||||
DECL_INIT(serial_init);
|
||||
78
src/atsamd/spi.c
Normal file
78
src/atsamd/spi.c
Normal file
@@ -0,0 +1,78 @@
|
||||
// spi support on samd
|
||||
//
|
||||
// Copyright (C) 2019 Florian Heilmann <Florian.Heilmann@gmx.net>
|
||||
// Copyright (C) 2018-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "internal.h" // enable_pclock
|
||||
#include "gpio.h" // spi_setup
|
||||
|
||||
void
|
||||
spi_init(uint32_t bus, SercomSpi *ss, uint32_t ctrla, uint32_t baud)
|
||||
{
|
||||
static uint8_t have_run_init;
|
||||
if (have_run_init & (1<<bus))
|
||||
return;
|
||||
have_run_init |= 1<<bus;
|
||||
|
||||
ss->CTRLA.reg = 0;
|
||||
ss->CTRLA.reg = ctrla & ~SERCOM_SPI_CTRLA_ENABLE;
|
||||
ss->CTRLB.reg = SERCOM_SPI_CTRLB_RXEN;
|
||||
ss->BAUD.reg = baud;
|
||||
ss->CTRLA.reg = ctrla;
|
||||
}
|
||||
|
||||
struct spi_config
|
||||
spi_setup(uint32_t bus, uint8_t mode, uint32_t rate)
|
||||
{
|
||||
uint32_t dipo_dopo = sercom_spi_pins(bus);
|
||||
uint32_t ctrla = (SERCOM_SPI_CTRLA_MODE(3)
|
||||
| (mode << SERCOM_SPI_CTRLA_CPHA_Pos)
|
||||
| dipo_dopo
|
||||
| SERCOM_SPI_CTRLA_ENABLE);
|
||||
Sercom *sercom = sercom_enable_pclock(bus);
|
||||
SercomSpi *ss = &sercom->SPI;
|
||||
uint32_t baud = sercom_get_pclock_frequency(bus) / (2 * rate) - 1;
|
||||
spi_init(bus, ss, ctrla, baud);
|
||||
return (struct spi_config){ .ss = ss, .ctrla = ctrla, .baud = baud };
|
||||
}
|
||||
|
||||
void
|
||||
spi_prepare(struct spi_config config)
|
||||
{
|
||||
uint32_t ctrla = config.ctrla, baud = config.baud;
|
||||
SercomSpi *ss = (SercomSpi *)config.ss;
|
||||
if (ctrla == ss->CTRLA.reg && baud == ss->BAUD.reg)
|
||||
return;
|
||||
ss->CTRLA.reg = ctrla & ~SERCOM_SPI_CTRLA_ENABLE;
|
||||
ss->CTRLA.reg = ctrla & ~SERCOM_SPI_CTRLA_ENABLE;
|
||||
ss->BAUD.reg = baud;
|
||||
ss->CTRLA.reg = ctrla;
|
||||
}
|
||||
|
||||
void
|
||||
spi_transfer(struct spi_config config, uint8_t receive_data
|
||||
, uint8_t len, uint8_t *data)
|
||||
{
|
||||
SercomSpi *ss = (SercomSpi *)config.ss;
|
||||
if (receive_data) {
|
||||
while (len--) {
|
||||
ss->DATA.reg = *data;
|
||||
// wait for receive register
|
||||
while (!(ss->INTFLAG.reg & SERCOM_SPI_INTFLAG_RXC))
|
||||
;
|
||||
// get data
|
||||
*data++ = ss->DATA.reg;
|
||||
}
|
||||
} else {
|
||||
while (len--) {
|
||||
ss->DATA.reg = *data++;
|
||||
// wait for receive register
|
||||
while (!(ss->INTFLAG.reg & SERCOM_SPI_INTFLAG_RXC))
|
||||
;
|
||||
// read data (to clear RXC)
|
||||
ss->DATA.reg;
|
||||
}
|
||||
}
|
||||
}
|
||||
65
src/atsamd/timer.c
Normal file
65
src/atsamd/timer.c
Normal file
@@ -0,0 +1,65 @@
|
||||
// SAMD21 timer interrupt scheduling
|
||||
//
|
||||
// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "board/armcm_boot.h" // armcm_enable_irq
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "board/misc.h" // timer_read_time
|
||||
#include "board/timer_irq.h" // timer_dispatch_many
|
||||
#include "internal.h" // enable_pclock
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
// Set the next irq time
|
||||
static void
|
||||
timer_set(uint32_t value)
|
||||
{
|
||||
TC4->COUNT32.CC[0].reg = value;
|
||||
TC4->COUNT32.INTFLAG.reg = TC_INTFLAG_MC0;
|
||||
}
|
||||
|
||||
// Return the current time (in absolute clock ticks).
|
||||
uint32_t
|
||||
timer_read_time(void)
|
||||
{
|
||||
return TC4->COUNT32.COUNT.reg;
|
||||
}
|
||||
|
||||
// Activate timer dispatch as soon as possible
|
||||
void
|
||||
timer_kick(void)
|
||||
{
|
||||
timer_set(timer_read_time() + 50);
|
||||
}
|
||||
|
||||
// IRQ handler
|
||||
void __aligned(16) // aligning helps stabilize perf benchmarks
|
||||
TC4_Handler(void)
|
||||
{
|
||||
irq_disable();
|
||||
uint32_t next = timer_dispatch_many();
|
||||
timer_set(next);
|
||||
irq_enable();
|
||||
}
|
||||
|
||||
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);
|
||||
|
||||
// Configure the timer
|
||||
TcCount32 *tc = &TC4->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);
|
||||
tc->INTENSET.reg = TC_INTENSET_MC0;
|
||||
tc->COUNT.reg = 0;
|
||||
timer_kick();
|
||||
tc->CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_ENABLE;
|
||||
irq_restore(flag);
|
||||
}
|
||||
DECL_INIT(timer_init);
|
||||
262
src/atsamd/usbserial.c
Normal file
262
src/atsamd/usbserial.c
Normal file
@@ -0,0 +1,262 @@
|
||||
// Hardware interface to USB on samd
|
||||
//
|
||||
// Copyright (C) 2018-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memcpy
|
||||
#include "autoconf.h" // CONFIG_FLASH_START
|
||||
#include "board/armcm_boot.h" // armcm_enable_irq
|
||||
#include "board/io.h" // readl
|
||||
#include "board/irq.h" // irq_disable
|
||||
#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
|
||||
#include "internal.h" // enable_pclock
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* USB transfer memory
|
||||
****************************************************************/
|
||||
|
||||
static uint8_t __aligned(4) ep0out[USB_CDC_EP0_SIZE];
|
||||
static uint8_t __aligned(4) ep0in[USB_CDC_EP0_SIZE];
|
||||
static uint8_t __aligned(4) acmin[USB_CDC_EP_ACM_SIZE];
|
||||
static uint8_t __aligned(4) bulkout[USB_CDC_EP_BULK_OUT_SIZE];
|
||||
static uint8_t __aligned(4) bulkin[USB_CDC_EP_BULK_IN_SIZE];
|
||||
|
||||
static UsbDeviceDescriptor usb_desc[] = {
|
||||
[0] = { {
|
||||
{
|
||||
.ADDR.reg = (uint32_t)ep0out,
|
||||
.PCKSIZE.reg = USB_DEVICE_PCKSIZE_SIZE(sizeof(ep0out) >> 4),
|
||||
}, {
|
||||
.ADDR.reg = (uint32_t)ep0in,
|
||||
.PCKSIZE.reg = USB_DEVICE_PCKSIZE_SIZE(sizeof(ep0in) >> 4),
|
||||
},
|
||||
} },
|
||||
[USB_CDC_EP_ACM] = { {
|
||||
{
|
||||
}, {
|
||||
.ADDR.reg = (uint32_t)acmin,
|
||||
.PCKSIZE.reg = USB_DEVICE_PCKSIZE_SIZE(sizeof(acmin) >> 4),
|
||||
},
|
||||
} },
|
||||
[USB_CDC_EP_BULK_OUT] = { {
|
||||
{
|
||||
.ADDR.reg = (uint32_t)bulkout,
|
||||
.PCKSIZE.reg = USB_DEVICE_PCKSIZE_SIZE(sizeof(bulkout) >> 4),
|
||||
}, {
|
||||
},
|
||||
} },
|
||||
[USB_CDC_EP_BULK_IN] = { {
|
||||
{
|
||||
}, {
|
||||
.ADDR.reg = (uint32_t)bulkin,
|
||||
.PCKSIZE.reg = USB_DEVICE_PCKSIZE_SIZE(sizeof(bulkin) >> 4),
|
||||
},
|
||||
} },
|
||||
};
|
||||
|
||||
#define EP0 USB->DEVICE.DeviceEndpoint[0]
|
||||
#define EP_ACM USB->DEVICE.DeviceEndpoint[USB_CDC_EP_ACM]
|
||||
#define EP_BULKOUT USB->DEVICE.DeviceEndpoint[USB_CDC_EP_BULK_OUT]
|
||||
#define EP_BULKIN USB->DEVICE.DeviceEndpoint[USB_CDC_EP_BULK_IN]
|
||||
|
||||
static int_fast8_t
|
||||
usb_write_packet(uint32_t ep, uint32_t bank, const void *data, uint_fast8_t len)
|
||||
{
|
||||
// Check if there is room for this packet
|
||||
UsbDeviceEndpoint *ude = &USB->DEVICE.DeviceEndpoint[ep];
|
||||
uint8_t sts = ude->EPSTATUS.reg;
|
||||
uint8_t bkrdy = (bank ? USB_DEVICE_EPSTATUS_BK1RDY
|
||||
: USB_DEVICE_EPSTATUS_BK0RDY);
|
||||
if (sts & bkrdy)
|
||||
return -1;
|
||||
// Copy the packet to the given buffer
|
||||
UsbDeviceDescBank *uddb = &usb_desc[ep].DeviceDescBank[bank];
|
||||
memcpy((void*)uddb->ADDR.reg, data, len);
|
||||
// Inform the USB hardware of the available packet
|
||||
uint32_t pcksize = uddb->PCKSIZE.reg;
|
||||
uint32_t c = pcksize & ~USB_DEVICE_PCKSIZE_BYTE_COUNT_Msk;
|
||||
uddb->PCKSIZE.reg = c | USB_DEVICE_PCKSIZE_BYTE_COUNT(len);
|
||||
ude->EPSTATUSSET.reg = bkrdy;
|
||||
return len;
|
||||
}
|
||||
|
||||
static int_fast8_t
|
||||
usb_read_packet(uint32_t ep, uint32_t bank, void *data, uint_fast8_t max_len)
|
||||
{
|
||||
// Check if there is a packet ready
|
||||
UsbDeviceEndpoint *ude = &USB->DEVICE.DeviceEndpoint[ep];
|
||||
uint8_t sts = ude->EPSTATUS.reg;
|
||||
uint8_t bkrdy = (bank ? USB_DEVICE_EPSTATUS_BK1RDY
|
||||
: USB_DEVICE_EPSTATUS_BK0RDY);
|
||||
if (!(sts & bkrdy))
|
||||
return -1;
|
||||
// Copy the packet to the given buffer
|
||||
UsbDeviceDescBank *uddb = &usb_desc[ep].DeviceDescBank[bank];
|
||||
uint32_t pcksize = uddb->PCKSIZE.reg;
|
||||
uint32_t c = pcksize & USB_DEVICE_PCKSIZE_BYTE_COUNT_Msk;
|
||||
if (c > max_len)
|
||||
c = max_len;
|
||||
memcpy(data, (void*)uddb->ADDR.reg, c);
|
||||
// Notify the USB hardware that the space is now available
|
||||
ude->EPSTATUSCLR.reg = bkrdy;
|
||||
return c;
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Interface
|
||||
****************************************************************/
|
||||
|
||||
int_fast8_t
|
||||
usb_read_bulk_out(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
return usb_read_packet(USB_CDC_EP_BULK_OUT, 0, data, max_len);
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_send_bulk_in(void *data, uint_fast8_t len)
|
||||
{
|
||||
return usb_write_packet(USB_CDC_EP_BULK_IN, 1, data, len);
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_read_ep0(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
return usb_read_packet(0, 0, data, max_len);
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_read_ep0_setup(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
return usb_read_ep0(data, max_len);
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_send_ep0(const void *data, uint_fast8_t len)
|
||||
{
|
||||
return usb_write_packet(0, 1, data, len);
|
||||
}
|
||||
|
||||
void
|
||||
usb_stall_ep0(void)
|
||||
{
|
||||
EP0.EPSTATUSSET.reg = USB_DEVICE_EPSTATUS_STALLRQ(3);
|
||||
}
|
||||
|
||||
static uint8_t set_address;
|
||||
|
||||
void
|
||||
usb_set_address(uint_fast8_t addr)
|
||||
{
|
||||
writeb(&set_address, addr | USB_DEVICE_DADD_ADDEN);
|
||||
usb_send_ep0(NULL, 0);
|
||||
}
|
||||
|
||||
void
|
||||
usb_set_configure(void)
|
||||
{
|
||||
EP_ACM.EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE1(4);
|
||||
|
||||
EP_BULKOUT.EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE0(3);
|
||||
EP_BULKOUT.EPINTENSET.reg = (
|
||||
USB_DEVICE_EPINTENSET_TRCPT0 | USB_DEVICE_EPINTENSET_TRCPT1);
|
||||
|
||||
EP_BULKIN.EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE1(3);
|
||||
EP_BULKIN.EPINTENSET.reg = (
|
||||
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
|
||||
****************************************************************/
|
||||
|
||||
void
|
||||
USB_Handler(void)
|
||||
{
|
||||
uint8_t s = USB->DEVICE.INTFLAG.reg;
|
||||
if (s & USB_DEVICE_INTFLAG_EORST) {
|
||||
USB->DEVICE.INTFLAG.reg = USB_DEVICE_INTFLAG_EORST;
|
||||
// Enable endpoint 0 irqs
|
||||
EP0.EPINTENSET.reg = (
|
||||
USB_DEVICE_EPINTENSET_TRCPT0 | USB_DEVICE_EPINTENSET_TRCPT1
|
||||
| USB_DEVICE_EPINTENSET_RXSTP);
|
||||
}
|
||||
|
||||
uint16_t ep = USB->DEVICE.EPINTSMRY.reg;
|
||||
if (ep & (1<<0)) {
|
||||
uint8_t sts = EP0.EPINTFLAG.reg;
|
||||
EP0.EPINTFLAG.reg = sts;
|
||||
if (set_address && sts & USB_DEVICE_EPINTFLAG_TRCPT1) {
|
||||
// Apply address after last "in" message transmitted
|
||||
USB->DEVICE.DADD.reg = set_address;
|
||||
set_address = 0;
|
||||
}
|
||||
usb_notify_ep0();
|
||||
}
|
||||
if (ep & (1<<USB_CDC_EP_BULK_OUT)) {
|
||||
uint8_t sts = EP_BULKOUT.EPINTFLAG.reg;
|
||||
EP_BULKOUT.EPINTFLAG.reg = sts;
|
||||
usb_notify_bulk_out();
|
||||
}
|
||||
if (ep & (1<<USB_CDC_EP_BULK_IN)) {
|
||||
uint8_t sts = EP_BULKIN.EPINTFLAG.reg;
|
||||
EP_BULKIN.EPINTFLAG.reg = sts;
|
||||
usb_notify_bulk_in();
|
||||
}
|
||||
}
|
||||
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_USB", "PA24,PA25");
|
||||
|
||||
void
|
||||
usbserial_init(void)
|
||||
{
|
||||
// configure usb clock
|
||||
enable_pclock(USB_GCLK_ID, ID_USB);
|
||||
// configure USBD+ and USBD- pins
|
||||
uint32_t ptype = CONFIG_MACH_SAMD21 ? 'G' : 'H';
|
||||
gpio_peripheral(GPIO('A', 24), ptype, 0);
|
||||
gpio_peripheral(GPIO('A', 25), ptype, 0);
|
||||
uint32_t trim = GET_FUSE(USB_FUSES_TRIM);
|
||||
uint32_t transp = GET_FUSE(USB_FUSES_TRANSP);
|
||||
uint32_t transn = GET_FUSE(USB_FUSES_TRANSN);
|
||||
USB->DEVICE.PADCAL.reg = (USB_PADCAL_TRIM(trim) | USB_PADCAL_TRANSP(transp)
|
||||
| USB_PADCAL_TRANSN(transn));
|
||||
// Enable USB in device mode
|
||||
USB->DEVICE.CTRLA.reg = USB_CTRLA_ENABLE;
|
||||
USB->DEVICE.DESCADD.reg = (uint32_t)usb_desc;
|
||||
EP0.EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE0(1) | USB_DEVICE_EPCFG_EPTYPE1(1);
|
||||
EP_ACM.EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE1(4);
|
||||
USB->DEVICE.CTRLB.reg = 0;
|
||||
// enable irqs
|
||||
USB->DEVICE.INTENSET.reg = USB_DEVICE_INTENSET_EORST;
|
||||
#if CONFIG_MACH_SAMD21
|
||||
armcm_enable_irq(USB_Handler, USB_IRQn, 1);
|
||||
#elif CONFIG_MACH_SAMD51
|
||||
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);
|
||||
armcm_enable_irq(USB_Handler, USB_3_IRQn, 1);
|
||||
#endif
|
||||
}
|
||||
DECL_INIT(usbserial_init);
|
||||
24
src/atsamd/watchdog.c
Normal file
24
src/atsamd/watchdog.c
Normal file
@@ -0,0 +1,24 @@
|
||||
// Watchdog handler on SAMD21 boards
|
||||
//
|
||||
// Copyright (C) 2018-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "internal.h" // WDT
|
||||
#include "sched.h" // DECL_TASK
|
||||
|
||||
void
|
||||
watchdog_reset(void)
|
||||
{
|
||||
if (!(WDT->STATUS.reg & WDT_STATUS_SYNCBUSY))
|
||||
WDT->CLEAR.reg = 0xa5;
|
||||
}
|
||||
DECL_TASK(watchdog_reset);
|
||||
|
||||
void
|
||||
watchdog_init(void)
|
||||
{
|
||||
WDT->CONFIG.reg = WDT_CONFIG_PER_16K; // 500ms timeout
|
||||
WDT->CTRL.reg = WDT_CTRL_ENABLE;
|
||||
}
|
||||
DECL_INIT(watchdog_init);
|
||||
152
src/avr/Kconfig
Normal file
152
src/avr/Kconfig
Normal file
@@ -0,0 +1,152 @@
|
||||
# Kconfig settings for AVR processors
|
||||
|
||||
if MACH_AVR
|
||||
|
||||
config AVR_SELECT
|
||||
bool
|
||||
default y
|
||||
select HAVE_GPIO
|
||||
select HAVE_GPIO_ADC
|
||||
select HAVE_GPIO_SPI
|
||||
select HAVE_GPIO_I2C
|
||||
select HAVE_GPIO_HARD_PWM
|
||||
select HAVE_GPIO_BITBANGING if !MACH_atmega168
|
||||
select HAVE_STRICT_TIMING
|
||||
|
||||
config BOARD_DIRECTORY
|
||||
string
|
||||
default "avr"
|
||||
|
||||
choice
|
||||
prompt "Processor model"
|
||||
config MACH_atmega2560
|
||||
bool "atmega2560"
|
||||
config MACH_atmega1280
|
||||
bool "atmega1280"
|
||||
config MACH_at90usb1286
|
||||
bool "at90usb1286"
|
||||
config MACH_at90usb646
|
||||
bool "at90usb646"
|
||||
config MACH_atmega32u4
|
||||
bool "atmega32u4"
|
||||
config MACH_atmega1284p
|
||||
bool "atmega1284p"
|
||||
config MACH_atmega644p
|
||||
bool "atmega644p"
|
||||
config MACH_atmega328p
|
||||
bool "atmega328p"
|
||||
config MACH_atmega328
|
||||
bool "atmega328"
|
||||
config MACH_atmega168
|
||||
bool "atmega168"
|
||||
endchoice
|
||||
|
||||
config MCU
|
||||
string
|
||||
default "atmega168" if MACH_atmega168
|
||||
default "atmega328" if MACH_atmega328
|
||||
default "atmega328p" if MACH_atmega328p
|
||||
default "atmega1284p" if MACH_atmega1284p
|
||||
default "atmega644p" if MACH_atmega644p
|
||||
default "at90usb1286" if MACH_at90usb1286
|
||||
default "at90usb646" if MACH_at90usb646
|
||||
default "atmega32u4" if MACH_atmega32u4
|
||||
default "atmega1280" if MACH_atmega1280
|
||||
default "atmega2560" if MACH_atmega2560
|
||||
|
||||
config AVRDUDE_PROTOCOL
|
||||
string
|
||||
default "wiring" if MACH_atmega2560
|
||||
default "avr109" if MACH_at90usb1286 || MACH_at90usb646 || MACH_atmega32u4
|
||||
default "arduino"
|
||||
|
||||
choice
|
||||
prompt "Processor speed" if LOW_LEVEL_OPTIONS
|
||||
config AVR_FREQ_16000000
|
||||
bool "16Mhz"
|
||||
config AVR_FREQ_20000000
|
||||
bool "20Mhz"
|
||||
depends on MACH_atmega168 || MACH_atmega328 || MACH_atmega328p || MACH_atmega644p || MACH_atmega1284p
|
||||
config AVR_FREQ_8000000
|
||||
bool "8Mhz"
|
||||
endchoice
|
||||
|
||||
config CLOCK_FREQ
|
||||
int
|
||||
default 8000000 if AVR_FREQ_8000000
|
||||
default 20000000 if AVR_FREQ_20000000
|
||||
default 16000000
|
||||
|
||||
config CLEAR_PRESCALER
|
||||
bool "Manually clear the CPU prescaler field at startup" if LOW_LEVEL_OPTIONS
|
||||
depends on MACH_at90usb1286 || MACH_at90usb646 || MACH_atmega32u4
|
||||
default y
|
||||
help
|
||||
Some AVR chips ship with a "clock prescaler" that causes the
|
||||
chip to run at 1/8th speed. Enable this setting to clear the
|
||||
prescaler field at startup which will cause the chip to run
|
||||
without a clock divisor.
|
||||
|
||||
config AVR_CLKPR
|
||||
int
|
||||
default 0 if CLEAR_PRESCALER
|
||||
default -1
|
||||
|
||||
config AVR_STACK_SIZE
|
||||
int
|
||||
default 256
|
||||
|
||||
config AVR_WATCHDOG
|
||||
bool
|
||||
default y
|
||||
|
||||
config USBSERIAL
|
||||
depends on (MACH_at90usb1286 || MACH_at90usb646 || MACH_atmega32u4) && !AVR_SERIAL_UART1
|
||||
bool
|
||||
default y
|
||||
config SERIAL
|
||||
depends on !USBSERIAL
|
||||
bool
|
||||
default y
|
||||
choice
|
||||
prompt "Communication interface" if LOW_LEVEL_OPTIONS && (MACH_atmega2560 || MACH_atmega1280 || MACH_atmega644p || MACH_atmega1284p || MACH_at90usb1286 || MACH_at90usb646 || MACH_atmega32u4)
|
||||
config AVR_USB
|
||||
bool "USB" if MACH_at90usb1286 || MACH_at90usb646 || MACH_atmega32u4
|
||||
select USBSERIAL
|
||||
config AVR_SERIAL_UART0
|
||||
bool "UART0" if !(MACH_at90usb1286 || MACH_at90usb646 || MACH_atmega32u4)
|
||||
select SERIAL
|
||||
config AVR_SERIAL_UART1
|
||||
bool "UART1"
|
||||
select SERIAL
|
||||
config AVR_SERIAL_UART2
|
||||
bool "UART2" if MACH_atmega2560 || MACH_atmega1280
|
||||
select SERIAL
|
||||
config AVR_SERIAL_UART3
|
||||
bool "UART3" if MACH_atmega2560 || MACH_atmega1280
|
||||
select SERIAL
|
||||
endchoice
|
||||
config SERIAL_BAUD_U2X
|
||||
depends on SERIAL && !SIMULAVR
|
||||
bool
|
||||
default y
|
||||
|
||||
config SERIAL_PORT
|
||||
int
|
||||
default 3 if AVR_SERIAL_UART3
|
||||
default 2 if AVR_SERIAL_UART2
|
||||
default 1 if AVR_SERIAL_UART1
|
||||
default 0
|
||||
|
||||
config SIMULAVR
|
||||
depends on MACH_atmega168 || MACH_atmega328 || MACH_atmega328p || MACH_atmega644p || MACH_atmega1284p
|
||||
bool "Compile for simulavr software emulation" if LOW_LEVEL_OPTIONS
|
||||
default n
|
||||
help
|
||||
Compile the code to run on simulavr software emulation
|
||||
instead of for real hardware. This disables support for "U2X
|
||||
baud" mode which is not supported on simulavr.
|
||||
|
||||
If unsure, select "N".
|
||||
|
||||
endif
|
||||
34
src/avr/Makefile
Normal file
34
src/avr/Makefile
Normal file
@@ -0,0 +1,34 @@
|
||||
# Additional avr build rules
|
||||
|
||||
# Use the avr toolchain
|
||||
CROSS_PREFIX=avr-
|
||||
|
||||
dirs-y += src/avr src/generic
|
||||
|
||||
CFLAGS += -mmcu=$(CONFIG_MCU)
|
||||
|
||||
# Add avr source files
|
||||
src-y += avr/main.c avr/timer.c
|
||||
src-$(CONFIG_HAVE_GPIO) += avr/gpio.c
|
||||
src-$(CONFIG_HAVE_GPIO_ADC) += avr/adc.c
|
||||
src-$(CONFIG_HAVE_GPIO_SPI) += avr/spi.c
|
||||
src-$(CONFIG_HAVE_GPIO_I2C) += avr/i2c.c
|
||||
src-$(CONFIG_HAVE_GPIO_HARD_PWM) += avr/hard_pwm.c
|
||||
src-$(CONFIG_AVR_WATCHDOG) += avr/watchdog.c
|
||||
src-$(CONFIG_USBSERIAL) += avr/usbserial.c generic/usb_cdc.c
|
||||
src-$(CONFIG_SERIAL) += avr/serial.c generic/serial_irq.c
|
||||
|
||||
# Suppress broken "misspelled signal handler" warnings on gcc 4.8.1
|
||||
CFLAGS_klipper.elf := $(CFLAGS_klipper.elf) $(if $(filter 4.8.1, $(shell $(CC) -dumpversion)), -w)
|
||||
|
||||
# Build the additional hex output file
|
||||
target-y += $(OUT)klipper.elf.hex
|
||||
|
||||
$(OUT)klipper.elf.hex: $(OUT)klipper.elf
|
||||
@echo " Creating hex file $@"
|
||||
$(Q)$(OBJCOPY) -j .text -j .data -O ihex $< $@
|
||||
|
||||
flash: $(OUT)klipper.elf.hex
|
||||
@echo " Flashing $< to $(FLASH_DEVICE) via avrdude"
|
||||
$(Q)if [ -z $(FLASH_DEVICE) ]; then echo "Please specify FLASH_DEVICE"; exit 1; fi
|
||||
$(Q)avrdude -p$(CONFIG_MCU) -c$(CONFIG_AVRDUDE_PROTOCOL) -P"$(FLASH_DEVICE)" -D -U"flash:w:$(<):i"
|
||||
122
src/avr/adc.c
Normal file
122
src/avr/adc.c
Normal file
@@ -0,0 +1,122 @@
|
||||
// Analog to Digital Converter support
|
||||
//
|
||||
// Copyright (C) 2016-2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_MACH_atmega644p
|
||||
#include "command.h" // shutdown
|
||||
#include "gpio.h" // gpio_adc_read
|
||||
#include "internal.h" // GPIO
|
||||
#include "pgm.h" // PROGMEM
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
static const uint8_t adc_pins[] PROGMEM = {
|
||||
#if CONFIG_MACH_atmega168 || CONFIG_MACH_atmega328 || CONFIG_MACH_atmega328p
|
||||
GPIO('C', 0), GPIO('C', 1), GPIO('C', 2), GPIO('C', 3),
|
||||
GPIO('C', 4), GPIO('C', 5), GPIO('E', 2), GPIO('E', 3),
|
||||
#elif CONFIG_MACH_atmega644p || CONFIG_MACH_atmega1284p
|
||||
GPIO('A', 0), GPIO('A', 1), GPIO('A', 2), GPIO('A', 3),
|
||||
GPIO('A', 4), GPIO('A', 5), GPIO('A', 6), GPIO('A', 7),
|
||||
#elif CONFIG_MACH_at90usb1286 || CONFIG_MACH_at90usb646
|
||||
GPIO('F', 0), GPIO('F', 1), GPIO('F', 2), GPIO('F', 3),
|
||||
GPIO('F', 4), GPIO('F', 5), GPIO('F', 6), GPIO('F', 7),
|
||||
#elif CONFIG_MACH_atmega32u4
|
||||
GPIO('F', 0), GPIO('F', 1), GPIO('F', 2), GPIO('F', 3),
|
||||
GPIO('F', 4), GPIO('F', 5), GPIO('F', 6), GPIO('F', 7),
|
||||
GPIO('D', 4), GPIO('D', 6), GPIO('D', 7), GPIO('B', 4),
|
||||
#elif CONFIG_MACH_atmega1280 || CONFIG_MACH_atmega2560
|
||||
GPIO('F', 0), GPIO('F', 1), GPIO('F', 2), GPIO('F', 3),
|
||||
GPIO('F', 4), GPIO('F', 5), GPIO('F', 6), GPIO('F', 7),
|
||||
GPIO('K', 0), GPIO('K', 1), GPIO('K', 2), GPIO('K', 3),
|
||||
GPIO('K', 4), GPIO('K', 5), GPIO('K', 6), GPIO('K', 7),
|
||||
#endif
|
||||
};
|
||||
|
||||
// The atmega168/328 have two analog only pins
|
||||
#if CONFIG_MACH_atmega168 || CONFIG_MACH_atmega328
|
||||
DECL_ENUMERATION_RANGE("pin", "PE2", GPIO('E', 2), 2);
|
||||
#endif
|
||||
|
||||
enum { ADMUX_DEFAULT = 0x40 };
|
||||
enum { ADC_ENABLE = (1<<ADPS0)|(1<<ADPS1)|(1<<ADPS2)|(1<<ADEN)|(1<<ADIF) };
|
||||
|
||||
DECL_CONSTANT("ADC_MAX", 1023);
|
||||
|
||||
struct gpio_adc
|
||||
gpio_adc_setup(uint8_t pin)
|
||||
{
|
||||
// Find pin in adc_pins table
|
||||
uint8_t chan;
|
||||
for (chan=0; ; chan++) {
|
||||
if (chan >= ARRAY_SIZE(adc_pins))
|
||||
shutdown("Not a valid ADC pin");
|
||||
if (READP(adc_pins[chan]) == pin)
|
||||
break;
|
||||
}
|
||||
|
||||
// Enable ADC
|
||||
ADCSRA = ADC_ENABLE;
|
||||
|
||||
// Disable digital input for this pin
|
||||
#ifdef DIDR2
|
||||
if (chan >= 8)
|
||||
DIDR2 |= 1 << (chan & 0x07);
|
||||
else
|
||||
#endif
|
||||
DIDR0 |= 1 << chan;
|
||||
|
||||
return (struct gpio_adc){ chan };
|
||||
}
|
||||
|
||||
enum { ADC_DUMMY=0xff };
|
||||
static uint8_t last_analog_read = ADC_DUMMY;
|
||||
|
||||
// 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)
|
||||
{
|
||||
if (ADCSRA & (1<<ADSC))
|
||||
// Busy
|
||||
goto need_delay;
|
||||
if (last_analog_read == g.chan)
|
||||
// Sample now ready
|
||||
return 0;
|
||||
if (last_analog_read != ADC_DUMMY)
|
||||
// Sample on another channel in progress
|
||||
goto need_delay;
|
||||
last_analog_read = g.chan;
|
||||
|
||||
// Set the channel to sample
|
||||
#if defined(ADCSRB) && defined(MUX5)
|
||||
// The MUX5 bit of ADCSRB selects whether we're reading from
|
||||
// channels 0 to 7 (MUX5 low) or 8 to 15 (MUX5 high).
|
||||
ADCSRB = ((g.chan >> 3) & 0x01) << MUX5;
|
||||
#endif
|
||||
ADMUX = ADMUX_DEFAULT | (g.chan & 0x07);
|
||||
|
||||
// Start the sample
|
||||
ADCSRA = ADC_ENABLE | (1<<ADSC);
|
||||
|
||||
// Schedule next attempt after sample is likely to be complete
|
||||
need_delay:
|
||||
return (13 + 1) * 128 + 200;
|
||||
}
|
||||
|
||||
// Read a value; use only after gpio_adc_sample() returns zero
|
||||
uint16_t
|
||||
gpio_adc_read(struct gpio_adc g)
|
||||
{
|
||||
last_analog_read = ADC_DUMMY;
|
||||
return ADC;
|
||||
}
|
||||
|
||||
// Cancel a sample that may have been started with gpio_adc_sample()
|
||||
void
|
||||
gpio_adc_cancel_sample(struct gpio_adc g)
|
||||
{
|
||||
if (last_analog_read == g.chan)
|
||||
last_analog_read = ADC_DUMMY;
|
||||
}
|
||||
126
src/avr/gpio.c
Normal file
126
src/avr/gpio.c
Normal file
@@ -0,0 +1,126 @@
|
||||
// GPIO functions on AVR.
|
||||
//
|
||||
// Copyright (C) 2016-2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_MACH_atmega644p
|
||||
#include "command.h" // shutdown
|
||||
#include "gpio.h" // gpio_out_write
|
||||
#include "internal.h" // GPIO2REGS
|
||||
#include "irq.h" // irq_save
|
||||
#include "pgm.h" // PROGMEM
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
#ifdef PINA
|
||||
DECL_ENUMERATION_RANGE("pin", "PA0", GPIO('A', 0), 8);
|
||||
#endif
|
||||
DECL_ENUMERATION_RANGE("pin", "PB0", GPIO('B', 0), 8);
|
||||
DECL_ENUMERATION_RANGE("pin", "PC0", GPIO('C', 0), 8);
|
||||
DECL_ENUMERATION_RANGE("pin", "PD0", GPIO('D', 0), 8);
|
||||
#if CONFIG_MACH_atmega328p
|
||||
DECL_ENUMERATION_RANGE("pin", "PE0", GPIO('E', 0), 8);
|
||||
#endif
|
||||
#ifdef PINE
|
||||
DECL_ENUMERATION_RANGE("pin", "PE0", GPIO('E', 0), 8);
|
||||
DECL_ENUMERATION_RANGE("pin", "PF0", GPIO('F', 0), 8);
|
||||
#endif
|
||||
#ifdef PING
|
||||
DECL_ENUMERATION_RANGE("pin", "PG0", GPIO('G', 0), 8);
|
||||
DECL_ENUMERATION_RANGE("pin", "PH0", GPIO('H', 0), 8);
|
||||
DECL_ENUMERATION_RANGE("pin", "PJ0", GPIO('J', 0), 8);
|
||||
DECL_ENUMERATION_RANGE("pin", "PK0", GPIO('K', 0), 8);
|
||||
DECL_ENUMERATION_RANGE("pin", "PL0", GPIO('L', 0), 8);
|
||||
#endif
|
||||
|
||||
volatile uint8_t * const digital_regs[] PROGMEM = {
|
||||
#ifdef PINA
|
||||
&PINA,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
&PINB, &PINC, &PIND,
|
||||
#if CONFIG_MACH_atmega328p
|
||||
&_SFR_IO8(0x0C), // PINE on atmega328pb
|
||||
#endif
|
||||
#ifdef PINE
|
||||
&PINE, &PINF,
|
||||
#endif
|
||||
#ifdef PING
|
||||
&PING, &PINH, NULL, &PINJ, &PINK, &PINL
|
||||
#endif
|
||||
};
|
||||
|
||||
struct gpio_out
|
||||
gpio_out_setup(uint8_t pin, uint8_t val)
|
||||
{
|
||||
if (GPIO2PORT(pin) >= ARRAY_SIZE(digital_regs))
|
||||
goto fail;
|
||||
struct gpio_digital_regs *regs = GPIO2REGS(pin);
|
||||
if (! regs)
|
||||
goto fail;
|
||||
struct gpio_out g = { .regs=regs, .bit=GPIO2BIT(pin) };
|
||||
gpio_out_reset(g, val);
|
||||
return g;
|
||||
fail:
|
||||
shutdown("Not an output pin");
|
||||
}
|
||||
|
||||
void
|
||||
gpio_out_reset(struct gpio_out g, uint8_t val)
|
||||
{
|
||||
irqstatus_t flag = irq_save();
|
||||
g.regs->out = val ? (g.regs->out | g.bit) : (g.regs->out & ~g.bit);
|
||||
g.regs->mode |= g.bit;
|
||||
irq_restore(flag);
|
||||
}
|
||||
|
||||
void
|
||||
gpio_out_toggle_noirq(struct gpio_out g)
|
||||
{
|
||||
g.regs->in = g.bit;
|
||||
}
|
||||
|
||||
void
|
||||
gpio_out_toggle(struct gpio_out g)
|
||||
{
|
||||
gpio_out_toggle_noirq(g);
|
||||
}
|
||||
|
||||
void
|
||||
gpio_out_write(struct gpio_out g, uint8_t val)
|
||||
{
|
||||
irqstatus_t flag = irq_save();
|
||||
g.regs->out = val ? (g.regs->out | g.bit) : (g.regs->out & ~g.bit);
|
||||
irq_restore(flag);
|
||||
}
|
||||
|
||||
struct gpio_in
|
||||
gpio_in_setup(uint8_t pin, int8_t pull_up)
|
||||
{
|
||||
if (GPIO2PORT(pin) >= ARRAY_SIZE(digital_regs) || pull_up < 0)
|
||||
goto fail;
|
||||
struct gpio_digital_regs *regs = GPIO2REGS(pin);
|
||||
if (! regs)
|
||||
goto fail;
|
||||
struct gpio_in g = { .regs=regs, .bit=GPIO2BIT(pin) };
|
||||
gpio_in_reset(g, pull_up);
|
||||
return g;
|
||||
fail:
|
||||
shutdown("Not a valid input pin");
|
||||
}
|
||||
|
||||
void
|
||||
gpio_in_reset(struct gpio_in g, int8_t pull_up)
|
||||
{
|
||||
irqstatus_t flag = irq_save();
|
||||
g.regs->out = pull_up > 0 ? (g.regs->out | g.bit) : (g.regs->out & ~g.bit);
|
||||
g.regs->mode &= ~g.bit;
|
||||
irq_restore(flag);
|
||||
}
|
||||
|
||||
uint8_t
|
||||
gpio_in_read(struct gpio_in g)
|
||||
{
|
||||
return !!(g.regs->in & g.bit);
|
||||
}
|
||||
57
src/avr/gpio.h
Normal file
57
src/avr/gpio.h
Normal file
@@ -0,0 +1,57 @@
|
||||
#ifndef __AVR_GPIO_H
|
||||
#define __AVR_GPIO_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
struct gpio_out {
|
||||
struct gpio_digital_regs *regs;
|
||||
// gcc (pre v6) does better optimization when uint8_t are bitfields
|
||||
uint8_t bit : 8;
|
||||
};
|
||||
struct gpio_out gpio_out_setup(uint8_t pin, uint8_t val);
|
||||
void gpio_out_reset(struct gpio_out g, uint8_t val);
|
||||
void gpio_out_toggle_noirq(struct gpio_out g);
|
||||
void gpio_out_toggle(struct gpio_out g);
|
||||
void gpio_out_write(struct gpio_out g, uint8_t val);
|
||||
|
||||
struct gpio_in {
|
||||
struct gpio_digital_regs *regs;
|
||||
uint8_t bit;
|
||||
};
|
||||
struct gpio_in gpio_in_setup(uint8_t pin, int8_t pull_up);
|
||||
void gpio_in_reset(struct gpio_in g, int8_t pull_up);
|
||||
uint8_t gpio_in_read(struct gpio_in g);
|
||||
|
||||
struct gpio_pwm {
|
||||
void *reg;
|
||||
uint8_t size8;
|
||||
};
|
||||
struct gpio_pwm gpio_pwm_setup(uint8_t pin, uint32_t cycle_time, uint8_t val);
|
||||
void gpio_pwm_write(struct gpio_pwm g, uint8_t val);
|
||||
|
||||
struct gpio_adc {
|
||||
uint8_t chan;
|
||||
};
|
||||
struct gpio_adc gpio_adc_setup(uint8_t pin);
|
||||
uint32_t gpio_adc_sample(struct gpio_adc g);
|
||||
uint16_t gpio_adc_read(struct gpio_adc g);
|
||||
void gpio_adc_cancel_sample(struct gpio_adc g);
|
||||
|
||||
struct spi_config {
|
||||
uint8_t spcr, spsr;
|
||||
};
|
||||
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 {
|
||||
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
|
||||
147
src/avr/hard_pwm.c
Normal file
147
src/avr/hard_pwm.c
Normal file
@@ -0,0 +1,147 @@
|
||||
// Hardware PWM pin support
|
||||
//
|
||||
// Copyright (C) 2016-2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_MACH_atmega644p
|
||||
#include "command.h" // shutdown
|
||||
#include "gpio.h" // gpio_pwm_write
|
||||
#include "internal.h" // GPIO2REGS
|
||||
#include "irq.h" // irq_save
|
||||
#include "pgm.h" // PROGMEM
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
struct gpio_pwm_info {
|
||||
uint8_t pin;
|
||||
volatile void *ocr;
|
||||
volatile uint8_t *rega, *regb;
|
||||
uint8_t en_bit, flags;
|
||||
};
|
||||
|
||||
enum { GP_8BIT=1, GP_AFMT=2 };
|
||||
|
||||
static const struct gpio_pwm_info pwm_regs[] PROGMEM = {
|
||||
#if CONFIG_MACH_atmega168 || CONFIG_MACH_atmega328 || CONFIG_MACH_atmega328p
|
||||
{ GPIO('D', 6), &OCR0A, &TCCR0A, &TCCR0B, 1<<COM0A1, GP_8BIT },
|
||||
{ GPIO('D', 5), &OCR0B, &TCCR0A, &TCCR0B, 1<<COM0B1, GP_8BIT },
|
||||
{ GPIO('B', 1), &OCR1A, &TCCR1A, &TCCR1B, 1<<COM1A1, 0 },
|
||||
{ GPIO('B', 2), &OCR1B, &TCCR1A, &TCCR1B, 1<<COM1B1, 0 },
|
||||
{ GPIO('B', 3), &OCR2A, &TCCR2A, &TCCR2B, 1<<COM2A1, GP_8BIT|GP_AFMT },
|
||||
{ GPIO('D', 3), &OCR2B, &TCCR2A, &TCCR2B, 1<<COM2B1, GP_8BIT|GP_AFMT },
|
||||
#elif CONFIG_MACH_atmega644p || CONFIG_MACH_atmega1284p
|
||||
{ GPIO('B', 3), &OCR0A, &TCCR0A, &TCCR0B, 1<<COM0A1, GP_8BIT },
|
||||
{ GPIO('B', 4), &OCR0B, &TCCR0A, &TCCR0B, 1<<COM0B1, GP_8BIT },
|
||||
{ GPIO('D', 5), &OCR1A, &TCCR1A, &TCCR1B, 1<<COM1A1, 0 },
|
||||
{ GPIO('D', 4), &OCR1B, &TCCR1A, &TCCR1B, 1<<COM1B1, 0 },
|
||||
{ GPIO('D', 7), &OCR2A, &TCCR2A, &TCCR2B, 1<<COM2A1, GP_8BIT|GP_AFMT },
|
||||
{ GPIO('D', 6), &OCR2B, &TCCR2A, &TCCR2B, 1<<COM2B1, GP_8BIT|GP_AFMT },
|
||||
# ifdef OCR3A
|
||||
{ GPIO('B', 6), &OCR3A, &TCCR3A, &TCCR3B, 1<<COM3A1, 0 },
|
||||
{ GPIO('B', 7), &OCR3B, &TCCR3A, &TCCR3B, 1<<COM3B1, 0 },
|
||||
# endif
|
||||
#elif CONFIG_MACH_at90usb1286 || CONFIG_MACH_at90usb646 \
|
||||
|| CONFIG_MACH_atmega32u4
|
||||
{ GPIO('B', 7), &OCR0A, &TCCR0A, &TCCR0B, 1<<COM0A1, GP_8BIT },
|
||||
{ GPIO('D', 0), &OCR0B, &TCCR0A, &TCCR0B, 1<<COM0B1, GP_8BIT },
|
||||
{ GPIO('B', 5), &OCR1A, &TCCR1A, &TCCR1B, 1<<COM1A1, 0 },
|
||||
{ GPIO('B', 6), &OCR1B, &TCCR1A, &TCCR1B, 1<<COM1B1, 0 },
|
||||
{ GPIO('B', 7), &OCR1C, &TCCR1A, &TCCR1B, 1<<COM1C1, 0 },
|
||||
# ifdef OCR2A
|
||||
{ GPIO('B', 4), &OCR2A, &TCCR2A, &TCCR2B, 1<<COM2A1, GP_8BIT|GP_AFMT },
|
||||
{ GPIO('D', 1), &OCR2B, &TCCR2A, &TCCR2B, 1<<COM2B1, GP_8BIT|GP_AFMT },
|
||||
# endif
|
||||
{ GPIO('C', 6), &OCR3A, &TCCR3A, &TCCR3B, 1<<COM3A1, 0 },
|
||||
{ GPIO('C', 5), &OCR3B, &TCCR3A, &TCCR3B, 1<<COM3B1, 0 },
|
||||
{ GPIO('C', 4), &OCR3C, &TCCR3A, &TCCR3B, 1<<COM3C1, 0 },
|
||||
#elif CONFIG_MACH_atmega1280 || CONFIG_MACH_atmega2560
|
||||
{ GPIO('B', 7), &OCR0A, &TCCR0A, &TCCR0B, 1<<COM0A1, GP_8BIT },
|
||||
{ GPIO('G', 5), &OCR0B, &TCCR0A, &TCCR0B, 1<<COM0B1, GP_8BIT },
|
||||
{ GPIO('B', 5), &OCR1A, &TCCR1A, &TCCR1B, 1<<COM1A1, 0 },
|
||||
{ GPIO('B', 6), &OCR1B, &TCCR1A, &TCCR1B, 1<<COM1B1, 0 },
|
||||
{ GPIO('B', 7), &OCR1C, &TCCR1A, &TCCR1B, 1<<COM1C1, 0 },
|
||||
{ GPIO('B', 4), &OCR2A, &TCCR2A, &TCCR2B, 1<<COM2A1, GP_8BIT|GP_AFMT },
|
||||
{ GPIO('H', 6), &OCR2B, &TCCR2A, &TCCR2B, 1<<COM2B1, GP_8BIT|GP_AFMT },
|
||||
{ GPIO('E', 3), &OCR3A, &TCCR3A, &TCCR3B, 1<<COM3A1, 0 },
|
||||
{ GPIO('E', 4), &OCR3B, &TCCR3A, &TCCR3B, 1<<COM3B1, 0 },
|
||||
{ GPIO('E', 5), &OCR3C, &TCCR3A, &TCCR3B, 1<<COM3C1, 0 },
|
||||
{ GPIO('H', 3), &OCR4A, &TCCR4A, &TCCR4B, 1<<COM4A1, 0 },
|
||||
{ GPIO('H', 4), &OCR4B, &TCCR4A, &TCCR4B, 1<<COM4B1, 0 },
|
||||
{ GPIO('H', 5), &OCR4C, &TCCR4A, &TCCR4B, 1<<COM4C1, 0 },
|
||||
{ GPIO('L', 3), &OCR5A, &TCCR5A, &TCCR5B, 1<<COM5A1, 0 },
|
||||
{ GPIO('L', 4), &OCR5B, &TCCR5A, &TCCR5B, 1<<COM5B1, 0 },
|
||||
{ GPIO('L', 5), &OCR5C, &TCCR5A, &TCCR5B, 1<<COM5C1, 0 },
|
||||
#endif
|
||||
};
|
||||
|
||||
DECL_CONSTANT("PWM_MAX", 255);
|
||||
|
||||
struct gpio_pwm
|
||||
gpio_pwm_setup(uint8_t pin, uint32_t cycle_time, uint8_t val)
|
||||
{
|
||||
// Find pin in pwm_regs table
|
||||
const struct gpio_pwm_info *p = pwm_regs;
|
||||
for (; ; p++) {
|
||||
if (p >= &pwm_regs[ARRAY_SIZE(pwm_regs)])
|
||||
shutdown("Not a valid PWM pin");
|
||||
if (READP(p->pin) == pin)
|
||||
break;
|
||||
}
|
||||
|
||||
// Map cycle_time to pwm clock divisor
|
||||
uint8_t flags = READP(p->flags), cs;
|
||||
if (flags & GP_AFMT) {
|
||||
switch (cycle_time) {
|
||||
case 0 ... (1+8) * 510L / 2 - 1: cs = 1; break;
|
||||
case (1+8) * 510L / 2 ... (8+32) * 510L / 2 - 1: cs = 2; break;
|
||||
case (8+32) * 510L / 2 ... (32+64) * 510L / 2 - 1: cs = 3; break;
|
||||
case (32+64) * 510L / 2 ... (64+128) * 510L / 2 - 1: cs = 4; break;
|
||||
case (64+128) * 510L / 2 ... (128+256) * 510L / 2 - 1: cs = 5; break;
|
||||
case (128+256) * 510L / 2 ... (256+1024) * 510L / 2 - 1: cs = 6; break;
|
||||
default: cs = 7; break;
|
||||
}
|
||||
} else {
|
||||
switch (cycle_time) {
|
||||
case 0 ... (1+8) * 510L / 2 - 1: cs = 1; break;
|
||||
case (1+8) * 510L / 2 ... (8+64) * 510L / 2 - 1: cs = 2; break;
|
||||
case (8+64) * 510L / 2 ... (64+256) * 510L / 2 - 1: cs = 3; break;
|
||||
case (64+256) * 510L / 2 ... (256+1024) * 510L / 2 - 1: cs = 4; break;
|
||||
default: cs = 5; break;
|
||||
}
|
||||
}
|
||||
volatile uint8_t *rega = READP(p->rega), *regb = READP(p->regb);
|
||||
uint8_t en_bit = READP(p->en_bit);
|
||||
struct gpio_digital_regs *gpio_regs = GPIO2REGS(pin);
|
||||
uint8_t gpio_bit = GPIO2BIT(pin);
|
||||
struct gpio_pwm g = (struct gpio_pwm) {
|
||||
(void*)READP(p->ocr), flags & GP_8BIT };
|
||||
if (rega == &TCCR1A)
|
||||
shutdown("Can not use timer1 for PWM; timer1 is used for timers");
|
||||
|
||||
// Setup PWM timer
|
||||
irqstatus_t flag = irq_save();
|
||||
uint8_t old_cs = *regb & 0x07;
|
||||
if (old_cs && old_cs != cs)
|
||||
shutdown("PWM already programmed at different speed");
|
||||
*regb = cs;
|
||||
|
||||
// Set default value and enable output
|
||||
gpio_pwm_write(g, val);
|
||||
*rega |= (1<<WGM00) | en_bit;
|
||||
gpio_regs->mode |= gpio_bit;
|
||||
irq_restore(flag);
|
||||
|
||||
return g;
|
||||
}
|
||||
|
||||
void
|
||||
gpio_pwm_write(struct gpio_pwm g, uint8_t val)
|
||||
{
|
||||
if (g.size8) {
|
||||
*(volatile uint8_t*)g.reg = val;
|
||||
} else {
|
||||
irqstatus_t flag = irq_save();
|
||||
*(volatile uint16_t*)g.reg = val;
|
||||
irq_restore(flag);
|
||||
}
|
||||
}
|
||||
127
src/avr/i2c.c
Normal file
127
src/avr/i2c.c
Normal file
@@ -0,0 +1,127 @@
|
||||
// I2C functions on AVR
|
||||
//
|
||||
// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <avr/io.h> // TWCR
|
||||
#include "autoconf.h" // CONFIG_CLOCK_FREQ
|
||||
#include "board/misc.h" // timer_is_before
|
||||
#include "command.h" // shutdown
|
||||
#include "gpio.h" // i2c_setup
|
||||
#include "internal.h" // GPIO
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
DECL_ENUMERATION("i2c_bus", "twi", 0);
|
||||
|
||||
#if CONFIG_MACH_atmega168 || CONFIG_MACH_atmega328 || CONFIG_MACH_atmega328p
|
||||
static const uint8_t SCL = GPIO('C', 5), SDA = GPIO('C', 4);
|
||||
DECL_CONSTANT_STR("BUS_PINS_twi", "PC5,PC4");
|
||||
#elif CONFIG_MACH_atmega644p || CONFIG_MACH_atmega1284p
|
||||
static const uint8_t SCL = GPIO('C', 0), SDA = GPIO('C', 1);
|
||||
DECL_CONSTANT_STR("BUS_PINS_twi", "PC0,PC1");
|
||||
#elif CONFIG_MACH_at90usb1286 || CONFIG_MACH_at90usb646 \
|
||||
|| CONFIG_MACH_atmega32u4 || CONFIG_MACH_atmega1280 \
|
||||
|| CONFIG_MACH_atmega2560
|
||||
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();
|
||||
return (struct i2c_config){ .addr=addr<<1 };
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_wait(uint32_t timeout)
|
||||
{
|
||||
for (;;) {
|
||||
if (TWCR & (1<<TWINT))
|
||||
break;
|
||||
if (!timer_is_before(timer_read_time(), timeout))
|
||||
shutdown("i2c timeout");
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_start(uint32_t timeout)
|
||||
{
|
||||
TWCR = (1<<TWEN) | (1<<TWINT) | (1<<TWSTA);
|
||||
i2c_wait(timeout);
|
||||
uint32_t status = TWSR;
|
||||
if (status != 0x10 && status != 0x08)
|
||||
shutdown("Failed to send i2c start");
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_send_byte(uint8_t b, uint32_t timeout)
|
||||
{
|
||||
TWDR = b;
|
||||
TWCR = (1<<TWEN) | (1<<TWINT);
|
||||
i2c_wait(timeout);
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_receive_byte(uint8_t *read, uint32_t timeout, uint8_t send_ack)
|
||||
{
|
||||
TWCR = (1<<TWEN) | (1<<TWINT) | ((send_ack?1:0)<<TWEA);
|
||||
i2c_wait(timeout);
|
||||
*read = TWDR;
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_stop(uint32_t timeout)
|
||||
{
|
||||
TWCR = (1<<TWEN) | (1<<TWINT) | (1<<TWSTO);
|
||||
}
|
||||
|
||||
void
|
||||
i2c_write(struct i2c_config config, uint8_t write_len, uint8_t *write)
|
||||
{
|
||||
uint32_t timeout = timer_read_time() + timer_from_us(5000);
|
||||
|
||||
i2c_start(timeout);
|
||||
i2c_send_byte(config.addr, timeout);
|
||||
while (write_len--)
|
||||
i2c_send_byte(*write++, timeout);
|
||||
i2c_stop(timeout);
|
||||
}
|
||||
|
||||
void
|
||||
i2c_read(struct i2c_config config, uint8_t reg_len, uint8_t *reg
|
||||
, uint8_t read_len, uint8_t *read)
|
||||
{
|
||||
uint32_t timeout = timer_read_time() + timer_from_us(5000);
|
||||
i2c_start(timeout);
|
||||
i2c_send_byte(config.addr, timeout);
|
||||
while (reg_len--)
|
||||
i2c_send_byte(*reg++, timeout);
|
||||
i2c_start(timeout);
|
||||
i2c_send_byte(config.addr | 0x1, timeout);
|
||||
while (read_len--)
|
||||
i2c_receive_byte(read++, timeout, read_len);
|
||||
i2c_stop(timeout);
|
||||
}
|
||||
18
src/avr/internal.h
Normal file
18
src/avr/internal.h
Normal file
@@ -0,0 +1,18 @@
|
||||
#ifndef __AVR_INTERNAL_H
|
||||
#define __AVR_INTERNAL_H
|
||||
// Local definitions for avr code
|
||||
|
||||
#define GPIO(PORT, NUM) (((PORT)-'A') * 8 + (NUM))
|
||||
#define GPIO2PORT(PIN) ((PIN) / 8)
|
||||
#define GPIO2BIT(PIN) (1<<((PIN) % 8))
|
||||
|
||||
struct gpio_digital_regs {
|
||||
// gcc (pre v6) does better optimization when uint8_t are bitfields
|
||||
volatile uint8_t in : 8, mode : 8, out : 8;
|
||||
};
|
||||
extern volatile uint8_t * const digital_regs[];
|
||||
|
||||
#define GPIO2REGS(pin) \
|
||||
((struct gpio_digital_regs*)READP(digital_regs[GPIO2PORT(pin)]))
|
||||
|
||||
#endif // internal.h
|
||||
38
src/avr/irq.h
Normal file
38
src/avr/irq.h
Normal file
@@ -0,0 +1,38 @@
|
||||
#ifndef __AVR_IRQ_H
|
||||
#define __AVR_IRQ_H
|
||||
// Definitions for irq enable/disable on AVR
|
||||
|
||||
#include <avr/interrupt.h> // cli
|
||||
#include "compiler.h" // barrier
|
||||
|
||||
static inline void irq_disable(void) {
|
||||
cli();
|
||||
barrier();
|
||||
}
|
||||
|
||||
static inline void irq_enable(void) {
|
||||
barrier();
|
||||
sei();
|
||||
}
|
||||
|
||||
typedef uint8_t irqstatus_t;
|
||||
|
||||
static inline irqstatus_t irq_save(void) {
|
||||
uint8_t flag = SREG;
|
||||
irq_disable();
|
||||
return flag;
|
||||
}
|
||||
|
||||
static inline void irq_restore(irqstatus_t flag) {
|
||||
barrier();
|
||||
SREG = flag;
|
||||
}
|
||||
|
||||
static inline void irq_wait(void) {
|
||||
asm("sei\n nop\n cli" : : : "memory");
|
||||
}
|
||||
|
||||
static inline void irq_poll(void) {
|
||||
}
|
||||
|
||||
#endif // irq.h
|
||||
72
src/avr/main.c
Normal file
72
src/avr/main.c
Normal file
@@ -0,0 +1,72 @@
|
||||
// Main starting point for AVR boards.
|
||||
//
|
||||
// Copyright (C) 2016,2017 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <avr/io.h> // AVR_STACK_POINTER_REG
|
||||
#include <util/crc16.h> // _crc_ccitt_update
|
||||
#include "autoconf.h" // CONFIG_MCU
|
||||
#include "board/misc.h" // dynmem_start
|
||||
#include "command.h" // DECL_CONSTANT
|
||||
#include "irq.h" // irq_enable
|
||||
#include "sched.h" // sched_main
|
||||
|
||||
DECL_CONSTANT_STR("MCU", CONFIG_MCU);
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Dynamic memory
|
||||
****************************************************************/
|
||||
|
||||
// Return the start of memory available for dynamic allocations
|
||||
void *
|
||||
dynmem_start(void)
|
||||
{
|
||||
extern char _end;
|
||||
return &_end;
|
||||
}
|
||||
|
||||
// Return the end of memory available for dynamic allocations
|
||||
void *
|
||||
dynmem_end(void)
|
||||
{
|
||||
return (void*)ALIGN(AVR_STACK_POINTER_REG, 256) - CONFIG_AVR_STACK_SIZE;
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Misc functions
|
||||
****************************************************************/
|
||||
|
||||
// Initialize the clock prescaler (if necessary)
|
||||
void
|
||||
prescaler_init(void)
|
||||
{
|
||||
if (CONFIG_AVR_CLKPR != -1 && (uint8_t)CONFIG_AVR_CLKPR != CLKPR) {
|
||||
irqstatus_t flag = irq_save();
|
||||
CLKPR = 0x80;
|
||||
CLKPR = CONFIG_AVR_CLKPR;
|
||||
irq_restore(flag);
|
||||
}
|
||||
}
|
||||
DECL_INIT(prescaler_init);
|
||||
|
||||
// Optimized crc16_ccitt for the avr processor
|
||||
uint16_t
|
||||
crc16_ccitt(uint8_t *buf, uint_fast8_t len)
|
||||
{
|
||||
uint16_t crc = 0xFFFF;
|
||||
while (len--)
|
||||
crc = _crc_ccitt_update(crc, *buf++);
|
||||
return crc;
|
||||
}
|
||||
|
||||
// Main entry point for avr code.
|
||||
int
|
||||
main(void)
|
||||
{
|
||||
irq_enable();
|
||||
sched_main();
|
||||
return 0;
|
||||
}
|
||||
27
src/avr/pgm.h
Normal file
27
src/avr/pgm.h
Normal file
@@ -0,0 +1,27 @@
|
||||
#ifndef __AVR_PGM_H
|
||||
#define __AVR_PGM_H
|
||||
// This header provides the avr/pgmspace.h definitions for "PROGMEM"
|
||||
// on AVR platforms.
|
||||
|
||||
#include <avr/pgmspace.h>
|
||||
|
||||
#define NEED_PROGMEM 1
|
||||
|
||||
#define READP(VAR) ({ \
|
||||
_Pragma("GCC diagnostic push"); \
|
||||
_Pragma("GCC diagnostic ignored \"-Wint-to-pointer-cast\""); \
|
||||
typeof(VAR) __val = \
|
||||
__builtin_choose_expr(sizeof(VAR) == 1, \
|
||||
(typeof(VAR))pgm_read_byte(&(VAR)), \
|
||||
__builtin_choose_expr(sizeof(VAR) == 2, \
|
||||
(typeof(VAR))pgm_read_word(&(VAR)), \
|
||||
__builtin_choose_expr(sizeof(VAR) == 4, \
|
||||
(typeof(VAR))pgm_read_dword(&(VAR)), \
|
||||
__force_link_error__unknown_type))); \
|
||||
_Pragma("GCC diagnostic pop"); \
|
||||
__val; \
|
||||
})
|
||||
|
||||
extern void __force_link_error__unknown_type(void);
|
||||
|
||||
#endif // pgm.h
|
||||
88
src/avr/serial.c
Normal file
88
src/avr/serial.c
Normal file
@@ -0,0 +1,88 @@
|
||||
// AVR serial port code.
|
||||
//
|
||||
// Copyright (C) 2016-2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <avr/interrupt.h> // USART_RX_vect
|
||||
#include "autoconf.h" // CONFIG_SERIAL_BAUD
|
||||
#include "board/serial_irq.h" // serial_rx_byte
|
||||
#include "command.h" // DECL_CONSTANT_STR
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
// Reserve serial pins
|
||||
#if CONFIG_SERIAL_PORT == 0
|
||||
#if CONFIG_MACH_atmega1280 || CONFIG_MACH_atmega2560
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PE0,PE1");
|
||||
#else
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PD0,PD1");
|
||||
#endif
|
||||
#elif CONFIG_SERIAL_PORT == 1
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PD2,PD3");
|
||||
#elif CONFIG_SERIAL_PORT == 2
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PH0,PH1");
|
||||
#else
|
||||
DECL_CONSTANT_STR("RESERVE_PINS_serial", "PJ0,PJ1");
|
||||
#endif
|
||||
|
||||
// Helper macros for defining serial port aliases
|
||||
#define AVR_SERIAL_REG1(prefix, id, suffix) prefix ## id ## suffix
|
||||
#define AVR_SERIAL_REG(prefix, id, suffix) AVR_SERIAL_REG1(prefix, id, suffix)
|
||||
|
||||
// Serial port register aliases
|
||||
#define UCSRxA AVR_SERIAL_REG(UCSR, CONFIG_SERIAL_PORT, A)
|
||||
#define UCSRxB AVR_SERIAL_REG(UCSR, CONFIG_SERIAL_PORT, B)
|
||||
#define UCSRxC AVR_SERIAL_REG(UCSR, CONFIG_SERIAL_PORT, C)
|
||||
#define UBRRx AVR_SERIAL_REG(UBRR, CONFIG_SERIAL_PORT,)
|
||||
#define UDRx AVR_SERIAL_REG(UDR, CONFIG_SERIAL_PORT,)
|
||||
#define UCSZx1 AVR_SERIAL_REG(UCSZ, CONFIG_SERIAL_PORT, 1)
|
||||
#define UCSZx0 AVR_SERIAL_REG(UCSZ, CONFIG_SERIAL_PORT, 0)
|
||||
#define U2Xx AVR_SERIAL_REG(U2X, CONFIG_SERIAL_PORT,)
|
||||
#define RXENx AVR_SERIAL_REG(RXEN, CONFIG_SERIAL_PORT,)
|
||||
#define TXENx AVR_SERIAL_REG(TXEN, CONFIG_SERIAL_PORT,)
|
||||
#define RXCIEx AVR_SERIAL_REG(RXCIE, CONFIG_SERIAL_PORT,)
|
||||
#define UDRIEx AVR_SERIAL_REG(UDRIE, CONFIG_SERIAL_PORT,)
|
||||
|
||||
#if defined(USART_RX_vect)
|
||||
// The atmega168 / atmega328 doesn't have an ID in the irq names
|
||||
#define USARTx_RX_vect USART_RX_vect
|
||||
#define USARTx_UDRE_vect USART_UDRE_vect
|
||||
#else
|
||||
#define USARTx_RX_vect AVR_SERIAL_REG(USART, CONFIG_SERIAL_PORT, _RX_vect)
|
||||
#define USARTx_UDRE_vect AVR_SERIAL_REG(USART, CONFIG_SERIAL_PORT, _UDRE_vect)
|
||||
#endif
|
||||
|
||||
void
|
||||
serial_init(void)
|
||||
{
|
||||
UCSRxA = CONFIG_SERIAL_BAUD_U2X ? (1<<U2Xx) : 0;
|
||||
uint32_t cm = CONFIG_SERIAL_BAUD_U2X ? 8 : 16;
|
||||
UBRRx = DIV_ROUND_CLOSEST(CONFIG_CLOCK_FREQ, cm * CONFIG_SERIAL_BAUD) - 1UL;
|
||||
UCSRxC = (1<<UCSZx1) | (1<<UCSZx0);
|
||||
UCSRxB = (1<<RXENx) | (1<<TXENx) | (1<<RXCIEx) | (1<<UDRIEx);
|
||||
}
|
||||
DECL_INIT(serial_init);
|
||||
|
||||
// Rx interrupt - data available to be read.
|
||||
ISR(USARTx_RX_vect)
|
||||
{
|
||||
serial_rx_byte(UDRx);
|
||||
}
|
||||
|
||||
// Tx interrupt - data can be written to serial.
|
||||
ISR(USARTx_UDRE_vect)
|
||||
{
|
||||
uint8_t data;
|
||||
int ret = serial_get_tx_byte(&data);
|
||||
if (ret)
|
||||
UCSRxB &= ~(1<<UDRIEx);
|
||||
else
|
||||
UDRx = data;
|
||||
}
|
||||
|
||||
// Enable tx interrupts
|
||||
void
|
||||
serial_enable_tx_irq(void)
|
||||
{
|
||||
UCSRxB |= 1<<UDRIEx;
|
||||
}
|
||||
106
src/avr/spi.c
Normal file
106
src/avr/spi.c
Normal file
@@ -0,0 +1,106 @@
|
||||
// Serial Peripheral Interface (SPI) support
|
||||
//
|
||||
// Copyright (C) 2016-2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_MACH_atmega644p
|
||||
#include "command.h" // shutdown
|
||||
#include "gpio.h" // spi_setup
|
||||
#include "internal.h" // GPIO
|
||||
#include "pgm.h" // READP
|
||||
#include "sched.h" // sched_shutdown
|
||||
|
||||
DECL_ENUMERATION("spi_bus", "spi", 0);
|
||||
|
||||
#if CONFIG_MACH_atmega168 || CONFIG_MACH_atmega328 || CONFIG_MACH_atmega328p
|
||||
static const uint8_t MISO = GPIO('B', 4), MOSI = GPIO('B', 3);
|
||||
static const uint8_t SCK = GPIO('B', 5), SS = GPIO('B', 2);
|
||||
DECL_CONSTANT_STR("BUS_PINS_spi", "PB4,PB3,PB5");
|
||||
#elif CONFIG_MACH_atmega644p || CONFIG_MACH_atmega1284p
|
||||
static const uint8_t MISO = GPIO('B', 6), MOSI = GPIO('B', 5);
|
||||
static const uint8_t SCK = GPIO('B', 7), SS = GPIO('B', 4);
|
||||
DECL_CONSTANT_STR("BUS_PINS_spi", "PB6,PB5,PB7");
|
||||
#elif CONFIG_MACH_at90usb1286 || CONFIG_MACH_at90usb646 \
|
||||
|| CONFIG_MACH_atmega32u4 || CONFIG_MACH_atmega1280 \
|
||||
|| CONFIG_MACH_atmega2560
|
||||
static const uint8_t MISO = GPIO('B', 3), MOSI = GPIO('B', 2);
|
||||
static const uint8_t SCK = GPIO('B', 1), SS = GPIO('B', 0);
|
||||
DECL_CONSTANT_STR("BUS_PINS_spi", "PB3,PB2,PB1");
|
||||
#endif
|
||||
|
||||
static void
|
||||
spi_init(void)
|
||||
{
|
||||
if (!(GPIO2REGS(SS)->mode & GPIO2BIT(SS)))
|
||||
// The SS pin must be an output pin (but is otherwise unused)
|
||||
gpio_out_setup(SS, 0);
|
||||
gpio_out_setup(SCK, 0);
|
||||
gpio_out_setup(MOSI, 0);
|
||||
gpio_in_setup(MISO, 0);
|
||||
|
||||
SPCR = (1<<MSTR) | (1<<SPE);
|
||||
SPSR = 0;
|
||||
}
|
||||
|
||||
struct spi_config
|
||||
spi_setup(uint32_t bus, uint8_t mode, uint32_t rate)
|
||||
{
|
||||
if (bus)
|
||||
shutdown("Invalid spi_setup parameters");
|
||||
|
||||
// Make sure the SPI interface is enabled
|
||||
spi_init();
|
||||
|
||||
// Setup rate
|
||||
struct spi_config config = {0, 0};
|
||||
if (rate >= (CONFIG_CLOCK_FREQ / 2)) {
|
||||
config.spsr = (1<<SPI2X);
|
||||
} else if (rate >= (CONFIG_CLOCK_FREQ / 4)) {
|
||||
config.spcr = 0;
|
||||
} else if (rate >= (CONFIG_CLOCK_FREQ / 8)) {
|
||||
config.spcr = 1;
|
||||
config.spsr = (1<<SPI2X);
|
||||
} else if (rate >= (CONFIG_CLOCK_FREQ / 16)) {
|
||||
config.spcr = 1;
|
||||
} else if (rate >= (CONFIG_CLOCK_FREQ / 32)) {
|
||||
config.spcr = 2;
|
||||
config.spsr = (1<<SPI2X);
|
||||
} else if (rate >= (CONFIG_CLOCK_FREQ / 64)) {
|
||||
config.spcr = 2;
|
||||
} else {
|
||||
config.spcr = 3;
|
||||
}
|
||||
|
||||
// Setup mode
|
||||
config.spcr |= (1<<SPE) | (1<<MSTR) | (mode << CPHA);
|
||||
|
||||
return config;
|
||||
}
|
||||
|
||||
void
|
||||
spi_prepare(struct spi_config config)
|
||||
{
|
||||
SPCR = config.spcr;
|
||||
SPSR = config.spsr;
|
||||
}
|
||||
|
||||
void
|
||||
spi_transfer(struct spi_config config, uint8_t receive_data
|
||||
, uint8_t len, uint8_t *data)
|
||||
{
|
||||
if (receive_data) {
|
||||
while (len--) {
|
||||
SPDR = *data;
|
||||
while (!(SPSR & (1<<SPIF)))
|
||||
;
|
||||
*data++ = SPDR;
|
||||
}
|
||||
} else {
|
||||
while (len--) {
|
||||
SPDR = *data++;
|
||||
while (!(SPSR & (1<<SPIF)))
|
||||
;
|
||||
}
|
||||
}
|
||||
}
|
||||
212
src/avr/timer.c
Normal file
212
src/avr/timer.c
Normal file
@@ -0,0 +1,212 @@
|
||||
// AVR timer interrupt scheduling code.
|
||||
//
|
||||
// Copyright (C) 2016,2017 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <avr/interrupt.h> // TCNT1
|
||||
#include "autoconf.h" // CONFIG_AVR_CLKPR
|
||||
#include "board/misc.h" // timer_from_us
|
||||
#include "command.h" // shutdown
|
||||
#include "irq.h" // irq_save
|
||||
#include "sched.h" // sched_timer_dispatch
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Low level timer code
|
||||
****************************************************************/
|
||||
|
||||
DECL_CONSTANT("CLOCK_FREQ", CONFIG_CLOCK_FREQ);
|
||||
|
||||
// Return the number of clock ticks for a given number of microseconds
|
||||
uint32_t
|
||||
timer_from_us(uint32_t us)
|
||||
{
|
||||
return us * (CONFIG_CLOCK_FREQ / 1000000);
|
||||
}
|
||||
|
||||
union u32_u {
|
||||
struct { uint8_t b0, b1, b2, b3; };
|
||||
struct { uint16_t lo, hi; };
|
||||
uint32_t val;
|
||||
};
|
||||
|
||||
// Return true if time1 is before time2. Always use this function to
|
||||
// compare times as regular C comparisons can fail if the counter
|
||||
// rolls over.
|
||||
uint8_t __always_inline
|
||||
timer_is_before(uint32_t time1, uint32_t time2)
|
||||
{
|
||||
// This asm is equivalent to:
|
||||
// return (int32_t)(time1 - time2) < 0;
|
||||
// But gcc doesn't do a good job with the above, so it's hand coded.
|
||||
union u32_u utime1 = { .val = time1 };
|
||||
uint8_t f = utime1.b3;
|
||||
asm(" cp %A1, %A2\n"
|
||||
" cpc %B1, %B2\n"
|
||||
" cpc %C1, %C2\n"
|
||||
" sbc %0, %D2"
|
||||
: "+r"(f) : "r"(time1), "r"(time2));
|
||||
return (int8_t)f < 0;
|
||||
}
|
||||
|
||||
static inline uint16_t
|
||||
timer_get(void)
|
||||
{
|
||||
return TCNT1;
|
||||
}
|
||||
|
||||
static inline void
|
||||
timer_set(uint16_t next)
|
||||
{
|
||||
OCR1A = next;
|
||||
}
|
||||
|
||||
static inline void
|
||||
timer_repeat_set(uint16_t next)
|
||||
{
|
||||
// Timer1B is used to limit the number of timers run from a timer1A irq
|
||||
OCR1B = next;
|
||||
// This is "TIFR1 = 1<<OCF1B" - gcc handles that poorly, so it's hand coded
|
||||
uint8_t dummy;
|
||||
asm volatile("ldi %0, %2\n out %1, %0"
|
||||
: "=d"(dummy) : "i"(&TIFR1 - 0x20), "i"(1<<OCF1B));
|
||||
}
|
||||
|
||||
// Activate timer dispatch as soon as possible
|
||||
void
|
||||
timer_kick(void)
|
||||
{
|
||||
timer_set(timer_get() + 50);
|
||||
TIFR1 = 1<<OCF1A;
|
||||
}
|
||||
|
||||
static struct timer wrap_timer;
|
||||
|
||||
void
|
||||
timer_reset(void)
|
||||
{
|
||||
sched_add_timer(&wrap_timer);
|
||||
}
|
||||
DECL_SHUTDOWN(timer_reset);
|
||||
|
||||
void
|
||||
timer_init(void)
|
||||
{
|
||||
irqstatus_t flag = irq_save();
|
||||
// no outputs
|
||||
TCCR1A = 0;
|
||||
// Normal Mode
|
||||
TCCR1B = 1<<CS10;
|
||||
// Setup for first irq
|
||||
TCNT1 = 0;
|
||||
timer_kick();
|
||||
timer_repeat_set(timer_get() + 50);
|
||||
timer_reset();
|
||||
TIFR1 = 1<<TOV1;
|
||||
// enable interrupt
|
||||
TIMSK1 = 1<<OCIE1A;
|
||||
irq_restore(flag);
|
||||
}
|
||||
DECL_INIT(timer_init);
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* 32bit timer wrappers
|
||||
****************************************************************/
|
||||
|
||||
static uint16_t timer_high;
|
||||
|
||||
// Return the current time (in absolute clock ticks).
|
||||
uint32_t
|
||||
timer_read_time(void)
|
||||
{
|
||||
irqstatus_t flag = irq_save();
|
||||
union u32_u calc = { .val = timer_get() };
|
||||
calc.hi = timer_high;
|
||||
if (unlikely(TIFR1 & (1<<TOV1))) {
|
||||
irq_restore(flag);
|
||||
if (calc.b1 < 0xff)
|
||||
calc.hi++;
|
||||
return calc.val;
|
||||
}
|
||||
irq_restore(flag);
|
||||
return calc.val;
|
||||
}
|
||||
|
||||
// Timer that runs every ~2ms - allows 16bit comparison optimizations
|
||||
static uint_fast8_t
|
||||
timer_event(struct timer *t)
|
||||
{
|
||||
union u32_u *nextwake = (void*)&wrap_timer.waketime;
|
||||
if (TIFR1 & (1<<TOV1)) {
|
||||
// Hardware timer has overflowed - update overflow counter
|
||||
TIFR1 = 1<<TOV1;
|
||||
timer_high++;
|
||||
*nextwake = (union u32_u){ .hi = timer_high, .lo = 0x8000 };
|
||||
} else {
|
||||
*nextwake = (union u32_u){ .hi = timer_high + 1, .lo = 0x0000 };
|
||||
}
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
static struct timer wrap_timer = {
|
||||
.func = timer_event,
|
||||
.waketime = 0x8000,
|
||||
};
|
||||
|
||||
#define TIMER_IDLE_REPEAT_TICKS 8000
|
||||
#define TIMER_REPEAT_TICKS 3000
|
||||
|
||||
#define TIMER_MIN_ENTRY_TICKS 44
|
||||
#define TIMER_MIN_EXIT_TICKS 47
|
||||
#define TIMER_MIN_TRY_TICKS (TIMER_MIN_ENTRY_TICKS + TIMER_MIN_EXIT_TICKS)
|
||||
#define TIMER_DEFER_REPEAT_TICKS 256
|
||||
|
||||
// Hardware timer IRQ handler - dispatch software timers
|
||||
ISR(TIMER1_COMPA_vect)
|
||||
{
|
||||
uint16_t next;
|
||||
for (;;) {
|
||||
// Run the next software timer
|
||||
next = sched_timer_dispatch();
|
||||
|
||||
for (;;) {
|
||||
int16_t diff = timer_get() - next;
|
||||
if (likely(diff >= 0)) {
|
||||
// Another timer is pending - briefly allow irqs and then run it
|
||||
irq_enable();
|
||||
if (unlikely(TIFR1 & (1<<OCF1B)))
|
||||
goto check_defer;
|
||||
irq_disable();
|
||||
break;
|
||||
}
|
||||
|
||||
if (likely(diff <= -TIMER_MIN_TRY_TICKS))
|
||||
// Schedule next timer normally
|
||||
goto done;
|
||||
|
||||
irq_enable();
|
||||
if (unlikely(TIFR1 & (1<<OCF1B)))
|
||||
goto check_defer;
|
||||
irq_disable();
|
||||
continue;
|
||||
|
||||
check_defer:
|
||||
// Check if there are too many repeat timers
|
||||
irq_disable();
|
||||
uint16_t now = timer_get();
|
||||
if ((int16_t)(next - now) < (int16_t)(-timer_from_us(1000)))
|
||||
try_shutdown("Rescheduled timer in the past");
|
||||
if (sched_tasks_busy()) {
|
||||
timer_repeat_set(now + TIMER_REPEAT_TICKS);
|
||||
next = now + TIMER_DEFER_REPEAT_TICKS;
|
||||
goto done;
|
||||
}
|
||||
timer_repeat_set(now + TIMER_IDLE_REPEAT_TICKS);
|
||||
timer_set(now);
|
||||
}
|
||||
}
|
||||
|
||||
done:
|
||||
timer_set(next);
|
||||
}
|
||||
260
src/avr/usbserial.c
Normal file
260
src/avr/usbserial.c
Normal file
@@ -0,0 +1,260 @@
|
||||
// Hardware interface to USB on AVR at90usb
|
||||
//
|
||||
// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <avr/interrupt.h> // USB_COM_vect
|
||||
#include <string.h> // NULL
|
||||
#include "autoconf.h" // CONFIG_MACH_at90usb1286
|
||||
#include "board/usb_cdc.h" // usb_notify_ep0
|
||||
#include "board/usb_cdc_ep.h" // USB_CDC_EP_BULK_IN
|
||||
#include "pgm.h" // READP
|
||||
#include "sched.h" // DECL_INIT
|
||||
|
||||
// EPCFG0X definitions
|
||||
#define EP_TYPE_CONTROL 0x00
|
||||
#define EP_TYPE_BULK_IN 0x81
|
||||
#define EP_TYPE_BULK_OUT 0x80
|
||||
#define EP_TYPE_INTERRUPT_IN 0xC1
|
||||
|
||||
// EPCFG1X definitions
|
||||
#define EP_SINGLE_BUFFER 0x02
|
||||
#define EP_DOUBLE_BUFFER 0x06
|
||||
#define EP_SIZE(s) ((s)==64 ? 0x30 : ((s)==32 ? 0x20 : ((s)==16 ? 0x10 : 0x00)))
|
||||
|
||||
static void
|
||||
usb_write_packet(const uint8_t *data, uint8_t len)
|
||||
{
|
||||
while (len--)
|
||||
UEDATX = *data++;
|
||||
}
|
||||
|
||||
static void
|
||||
usb_write_packet_progmem(const uint8_t *data, uint8_t len)
|
||||
{
|
||||
while (len--)
|
||||
UEDATX = READP(*data++);
|
||||
}
|
||||
|
||||
static void
|
||||
usb_read_packet(uint8_t *data, uint8_t len)
|
||||
{
|
||||
while (len--)
|
||||
*data++ = UEDATX;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_read_bulk_out(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
UENUM = USB_CDC_EP_BULK_OUT;
|
||||
if (!(UEINTX & (1<<RXOUTI))) {
|
||||
// No data ready
|
||||
UEIENX = 1<<RXOUTE;
|
||||
return -1;
|
||||
}
|
||||
uint8_t len = UEBCLX;
|
||||
usb_read_packet(data, len);
|
||||
UEINTX = (uint8_t)~((1<<FIFOCON) | (1<<RXOUTI));
|
||||
return len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_send_bulk_in(void *data, uint_fast8_t len)
|
||||
{
|
||||
UENUM = USB_CDC_EP_BULK_IN;
|
||||
if (!(UEINTX & (1<<TXINI))) {
|
||||
// Buffer full
|
||||
UEIENX = 1<<TXINE;
|
||||
return -1;
|
||||
}
|
||||
usb_write_packet(data, len);
|
||||
UEINTX = (uint8_t)~((1<<FIFOCON) | (1<<TXINI) | (1<<RXOUTI));
|
||||
return len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_read_ep0(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
UENUM = 0;
|
||||
uint8_t ueintx = UEINTX;
|
||||
if (ueintx & (1<<RXSTPI))
|
||||
return -2;
|
||||
if (!(ueintx & (1<<RXOUTI))) {
|
||||
// Not ready to receive data
|
||||
UEIENX = (1<<RXSTPE) | (1<<RXOUTE);
|
||||
return -1;
|
||||
}
|
||||
usb_read_packet(data, max_len);
|
||||
if (UEINTX & (1<<RXSTPI))
|
||||
return -2;
|
||||
UEINTX = ~(1<<RXOUTI);
|
||||
return max_len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_read_ep0_setup(void *data, uint_fast8_t max_len)
|
||||
{
|
||||
UENUM = 0;
|
||||
uint8_t ueintx = UEINTX;
|
||||
if (!(ueintx & ((1<<RXSTPI)))) {
|
||||
// No data ready to read
|
||||
UEIENX = 1<<RXSTPE;
|
||||
return -1;
|
||||
}
|
||||
usb_read_packet(data, max_len);
|
||||
UEINTX = ~((1<<RXSTPI) | (1<<RXOUTI));
|
||||
return max_len;
|
||||
}
|
||||
|
||||
static int8_t
|
||||
_usb_send_ep0(const void *data, uint8_t len, uint8_t progmem)
|
||||
{
|
||||
UENUM = 0;
|
||||
uint8_t ueintx = UEINTX;
|
||||
if (ueintx & ((1<<RXSTPI) | (1<<RXOUTI)))
|
||||
return -2;
|
||||
if (!(ueintx & (1<<TXINI))) {
|
||||
// Not ready to send
|
||||
UEIENX = (1<<RXSTPE) | (1<<RXOUTE) | (1<<TXINE);
|
||||
return -1;
|
||||
}
|
||||
if (progmem)
|
||||
usb_write_packet_progmem(data, len);
|
||||
else
|
||||
usb_write_packet(data, len);
|
||||
UEINTX = ~(1<<TXINI);
|
||||
return len;
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_send_ep0(const void *data, uint_fast8_t len)
|
||||
{
|
||||
return _usb_send_ep0(data, len, 0);
|
||||
}
|
||||
|
||||
int_fast8_t
|
||||
usb_send_ep0_progmem(const void *data, uint_fast8_t len)
|
||||
{
|
||||
return _usb_send_ep0(data, len, 1);
|
||||
}
|
||||
|
||||
void
|
||||
usb_stall_ep0(void)
|
||||
{
|
||||
UENUM = 0;
|
||||
UECONX = (1<<STALLRQ) | (1<<EPEN);
|
||||
UEIENX = 1<<RXSTPE;
|
||||
}
|
||||
|
||||
static uint8_t set_address;
|
||||
|
||||
void
|
||||
usb_set_address(uint_fast8_t addr)
|
||||
{
|
||||
set_address = addr | (1<<ADDEN);
|
||||
_usb_send_ep0(NULL, 0, 0);
|
||||
UEIENX = (1<<RXSTPE) | (1<<TXINE);
|
||||
}
|
||||
|
||||
void
|
||||
usb_set_configure(void)
|
||||
{
|
||||
UENUM = USB_CDC_EP_ACM;
|
||||
UECONX = 1<<EPEN;
|
||||
UECFG0X = EP_TYPE_INTERRUPT_IN;
|
||||
UECFG1X = EP_SIZE(USB_CDC_EP_ACM_SIZE) | EP_SINGLE_BUFFER;
|
||||
|
||||
UENUM = USB_CDC_EP_BULK_OUT;
|
||||
UECONX = 1<<EPEN;
|
||||
UECFG0X = EP_TYPE_BULK_OUT;
|
||||
UECFG1X = EP_SIZE(USB_CDC_EP_BULK_OUT_SIZE) | EP_DOUBLE_BUFFER;
|
||||
UEIENX = 1<<RXOUTE;
|
||||
|
||||
UENUM = USB_CDC_EP_BULK_IN;
|
||||
UECONX = 1<<EPEN;
|
||||
UECFG0X = EP_TYPE_BULK_IN;
|
||||
UECFG1X = EP_SIZE(USB_CDC_EP_BULK_IN_SIZE) | EP_DOUBLE_BUFFER;
|
||||
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))
|
||||
#elif CONFIG_MACH_at90usb646
|
||||
#define UHWCON_Init ((1<<UIMOD) | (1<<UVREGE))
|
||||
#define PLLCSR_Init ((1<<PLLP2) | (1<<PLLP1) | (1<<PLLE))
|
||||
#elif CONFIG_MACH_atmega32u4
|
||||
#define UHWCON_Init (1<<UVREGE)
|
||||
#define PLLCSR_Init ((1<<PINDIV) | (1<<PLLE))
|
||||
#endif
|
||||
|
||||
void
|
||||
usbserial_init(void)
|
||||
{
|
||||
// Set USB controller to device mode
|
||||
UHWCON = UHWCON_Init;
|
||||
|
||||
// Enable USB clock
|
||||
USBCON = (1<<USBE) | (1<<FRZCLK);
|
||||
PLLCSR = PLLCSR_Init;
|
||||
while (!(PLLCSR & (1<<PLOCK)))
|
||||
;
|
||||
USBCON = (1<<USBE) | (1<<OTGPADE);
|
||||
|
||||
// Enable USB pullup
|
||||
UDCON = 0;
|
||||
|
||||
// Enable interrupts
|
||||
UDIEN = 1<<EORSTE;
|
||||
}
|
||||
DECL_INIT(usbserial_init);
|
||||
|
||||
ISR(USB_GEN_vect)
|
||||
{
|
||||
uint8_t udint = UDINT;
|
||||
UDINT = 0;
|
||||
if (udint & (1<<EORSTI)) {
|
||||
// Configure endpoint 0 after usb reset completes
|
||||
uint8_t old_uenum = UENUM;
|
||||
UENUM = 0;
|
||||
UECONX = 1<<EPEN;
|
||||
UECFG0X = EP_TYPE_CONTROL;
|
||||
UECFG1X = EP_SIZE(USB_CDC_EP0_SIZE) | EP_SINGLE_BUFFER;
|
||||
UEIENX = 1<<RXSTPE;
|
||||
UENUM = old_uenum;
|
||||
}
|
||||
}
|
||||
|
||||
ISR(USB_COM_vect)
|
||||
{
|
||||
uint8_t ueint = UEINT, old_uenum = UENUM;
|
||||
if (ueint & (1<<0)) {
|
||||
UENUM = 0;
|
||||
UEIENX = 0;
|
||||
usb_notify_ep0();
|
||||
|
||||
uint8_t ueintx = UEINTX;
|
||||
if (!(ueintx & (1<<RXSTPI)) && (ueintx & (1<<TXINI)) && set_address) {
|
||||
// Ack from set_address command sent - now update address
|
||||
UDADDR = set_address;
|
||||
set_address = 0;
|
||||
}
|
||||
}
|
||||
if (ueint & (1<<USB_CDC_EP_BULK_OUT)) {
|
||||
UENUM = USB_CDC_EP_BULK_OUT;
|
||||
UEIENX = 0;
|
||||
usb_notify_bulk_out();
|
||||
}
|
||||
if (ueint & (1<<USB_CDC_EP_BULK_IN)) {
|
||||
UENUM = USB_CDC_EP_BULK_IN;
|
||||
UEIENX = 0;
|
||||
usb_notify_bulk_in();
|
||||
}
|
||||
UENUM = old_uenum;
|
||||
}
|
||||
58
src/avr/watchdog.c
Normal file
58
src/avr/watchdog.c
Normal file
@@ -0,0 +1,58 @@
|
||||
// Initialization of AVR watchdog timer.
|
||||
//
|
||||
// Copyright (C) 2016 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <avr/interrupt.h> // WDT_vect
|
||||
#include <avr/wdt.h> // wdt_enable
|
||||
#include "command.h" // shutdown
|
||||
#include "irq.h" // irq_disable
|
||||
#include "sched.h" // DECL_TASK
|
||||
|
||||
static uint8_t watchdog_shutdown;
|
||||
|
||||
ISR(WDT_vect)
|
||||
{
|
||||
watchdog_shutdown = 1;
|
||||
shutdown("Watchdog timer!");
|
||||
}
|
||||
|
||||
void
|
||||
watchdog_reset(void)
|
||||
{
|
||||
wdt_reset();
|
||||
if (watchdog_shutdown) {
|
||||
WDTCSR = 1<<WDIE;
|
||||
watchdog_shutdown = 0;
|
||||
}
|
||||
}
|
||||
DECL_TASK(watchdog_reset);
|
||||
|
||||
void
|
||||
watchdog_init(void)
|
||||
{
|
||||
// 0.5s timeout, interrupt and system reset
|
||||
wdt_enable(WDTO_500MS);
|
||||
WDTCSR = 1<<WDIE;
|
||||
}
|
||||
DECL_INIT(watchdog_init);
|
||||
|
||||
// Very early reset of the watchdog
|
||||
void __attribute__((naked)) __visible __section(".init3")
|
||||
watchdog_early_init(void)
|
||||
{
|
||||
MCUSR = 0;
|
||||
wdt_disable();
|
||||
}
|
||||
|
||||
// Support reset on AVR via the watchdog timer
|
||||
void
|
||||
command_reset(uint32_t *args)
|
||||
{
|
||||
irq_disable();
|
||||
wdt_enable(WDTO_15MS);
|
||||
for (;;)
|
||||
;
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_reset, HF_IN_SHUTDOWN, "reset");
|
||||
367
src/basecmd.c
Normal file
367
src/basecmd.c
Normal file
@@ -0,0 +1,367 @@
|
||||
// Basic infrastructure commands.
|
||||
//
|
||||
// Copyright (C) 2016-2020 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memset
|
||||
#include "basecmd.h" // oid_lookup
|
||||
#include "board/irq.h" // irq_save
|
||||
#include "board/misc.h" // alloc_maxsize
|
||||
#include "board/pgm.h" // READP
|
||||
#include "command.h" // DECL_COMMAND
|
||||
#include "sched.h" // sched_clear_shutdown
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Low level allocation
|
||||
****************************************************************/
|
||||
|
||||
static void *alloc_end;
|
||||
|
||||
void
|
||||
alloc_init(void)
|
||||
{
|
||||
alloc_end = (void*)ALIGN((size_t)dynmem_start(), __alignof__(void*));
|
||||
}
|
||||
DECL_INIT(alloc_init);
|
||||
|
||||
// Allocate an area of memory
|
||||
void *
|
||||
alloc_chunk(size_t size)
|
||||
{
|
||||
if (alloc_end + size > dynmem_end())
|
||||
shutdown("alloc_chunk failed");
|
||||
void *data = alloc_end;
|
||||
alloc_end += ALIGN(size, __alignof__(void*));
|
||||
memset(data, 0, size);
|
||||
return data;
|
||||
}
|
||||
|
||||
// Allocate an array of chunks
|
||||
static void *
|
||||
alloc_chunks(size_t size, size_t count, uint16_t *avail)
|
||||
{
|
||||
size_t can_alloc = 0;
|
||||
void *p = alloc_end, *end = dynmem_end();
|
||||
while (can_alloc < count && p + size <= end)
|
||||
can_alloc++, p += size;
|
||||
if (!can_alloc)
|
||||
shutdown("alloc_chunks failed");
|
||||
void *data = alloc_chunk(p - alloc_end);
|
||||
*avail = can_alloc;
|
||||
return data;
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Move queue
|
||||
****************************************************************/
|
||||
|
||||
static struct move_node *move_free_list;
|
||||
static void *move_list;
|
||||
static uint16_t move_count;
|
||||
static uint8_t move_item_size;
|
||||
|
||||
// Is the config and move queue finalized?
|
||||
static int
|
||||
is_finalized(void)
|
||||
{
|
||||
return !!move_count;
|
||||
}
|
||||
|
||||
// Free previously allocated storage from move_alloc(). Caller must
|
||||
// disable irqs.
|
||||
void
|
||||
move_free(void *m)
|
||||
{
|
||||
struct move_node *mf = m;
|
||||
mf->next = move_free_list;
|
||||
move_free_list = mf;
|
||||
}
|
||||
|
||||
// Allocate runtime storage
|
||||
void *
|
||||
move_alloc(void)
|
||||
{
|
||||
irqstatus_t flag = irq_save();
|
||||
struct move_node *mf = move_free_list;
|
||||
if (!mf)
|
||||
shutdown("Move queue overflow");
|
||||
move_free_list = mf->next;
|
||||
irq_restore(flag);
|
||||
return mf;
|
||||
}
|
||||
|
||||
// Check if a move_queue is empty
|
||||
int
|
||||
move_queue_empty(struct move_queue_head *mh)
|
||||
{
|
||||
return mh->first == NULL;
|
||||
}
|
||||
|
||||
// Return first node in a move queue
|
||||
struct move_node *
|
||||
move_queue_first(struct move_queue_head *mh)
|
||||
{
|
||||
return mh->first;
|
||||
}
|
||||
|
||||
// Add move to queue
|
||||
int
|
||||
move_queue_push(struct move_node *m, struct move_queue_head *mh)
|
||||
{
|
||||
m->next = NULL;
|
||||
if (mh->first) {
|
||||
mh->last->next = m;
|
||||
mh->last = m;
|
||||
return 0;
|
||||
}
|
||||
mh->first = mh->last = m;
|
||||
return 1;
|
||||
}
|
||||
|
||||
// Remove first item from queue (caller must ensure queue not empty)
|
||||
struct move_node *
|
||||
move_queue_pop(struct move_queue_head *mh)
|
||||
{
|
||||
struct move_node *mn = mh->first;
|
||||
mh->first = mn->next;
|
||||
return mn;
|
||||
}
|
||||
|
||||
// Completely clear move queue (used in shutdown handlers)
|
||||
void
|
||||
move_queue_clear(struct move_queue_head *mh)
|
||||
{
|
||||
mh->first = NULL;
|
||||
}
|
||||
|
||||
// Initialize a move_queue with nodes of the give size
|
||||
void
|
||||
move_queue_setup(struct move_queue_head *mh, int size)
|
||||
{
|
||||
mh->first = mh->last = NULL;
|
||||
|
||||
if (size > UINT8_MAX || is_finalized())
|
||||
shutdown("Invalid move request size");
|
||||
if (size > move_item_size)
|
||||
move_item_size = size;
|
||||
}
|
||||
|
||||
void
|
||||
move_reset(void)
|
||||
{
|
||||
if (!move_count)
|
||||
return;
|
||||
// Add everything in move_list to the free list.
|
||||
uint32_t i;
|
||||
for (i=0; i<move_count-1; i++) {
|
||||
struct move_node *mf = move_list + i*move_item_size;
|
||||
mf->next = move_list + (i + 1)*move_item_size;
|
||||
}
|
||||
struct move_node *mf = move_list + (move_count - 1)*move_item_size;
|
||||
mf->next = NULL;
|
||||
move_free_list = move_list;
|
||||
}
|
||||
DECL_SHUTDOWN(move_reset);
|
||||
|
||||
static void
|
||||
move_finalize(void)
|
||||
{
|
||||
if (is_finalized())
|
||||
shutdown("Already finalized");
|
||||
struct move_queue_head dummy;
|
||||
move_queue_setup(&dummy, sizeof(*move_free_list));
|
||||
move_list = alloc_chunks(move_item_size, 1024, &move_count);
|
||||
move_reset();
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Generic object ids (oid)
|
||||
****************************************************************/
|
||||
|
||||
struct oid_s {
|
||||
void *type, *data;
|
||||
};
|
||||
|
||||
static struct oid_s *oids;
|
||||
static uint8_t oid_count;
|
||||
|
||||
void *
|
||||
oid_lookup(uint8_t oid, void *type)
|
||||
{
|
||||
if (oid >= oid_count || type != oids[oid].type)
|
||||
shutdown("Invalid oid type");
|
||||
return oids[oid].data;
|
||||
}
|
||||
|
||||
void *
|
||||
oid_alloc(uint8_t oid, void *type, uint16_t size)
|
||||
{
|
||||
if (oid >= oid_count || oids[oid].type || is_finalized())
|
||||
shutdown("Can't assign oid");
|
||||
oids[oid].type = type;
|
||||
void *data = alloc_chunk(size);
|
||||
oids[oid].data = data;
|
||||
return data;
|
||||
}
|
||||
|
||||
void *
|
||||
oid_next(uint8_t *i, void *type)
|
||||
{
|
||||
uint8_t oid = *i;
|
||||
for (;;) {
|
||||
oid++;
|
||||
if (oid >= oid_count)
|
||||
return NULL;
|
||||
if (oids[oid].type == type) {
|
||||
*i = oid;
|
||||
return oids[oid].data;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
command_allocate_oids(uint32_t *args)
|
||||
{
|
||||
if (oids)
|
||||
shutdown("oids already allocated");
|
||||
uint8_t count = args[0];
|
||||
oids = alloc_chunk(sizeof(oids[0]) * count);
|
||||
oid_count = count;
|
||||
}
|
||||
DECL_COMMAND(command_allocate_oids, "allocate_oids count=%c");
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Config CRC
|
||||
****************************************************************/
|
||||
|
||||
static uint32_t config_crc;
|
||||
|
||||
void
|
||||
command_get_config(uint32_t *args)
|
||||
{
|
||||
sendf("config is_config=%c crc=%u is_shutdown=%c move_count=%hu"
|
||||
, is_finalized(), config_crc, sched_is_shutdown(), move_count);
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_get_config, HF_IN_SHUTDOWN, "get_config");
|
||||
|
||||
void
|
||||
command_finalize_config(uint32_t *args)
|
||||
{
|
||||
move_finalize();
|
||||
config_crc = args[0];
|
||||
}
|
||||
DECL_COMMAND(command_finalize_config, "finalize_config crc=%u");
|
||||
|
||||
// Attempt a full manual reset of the config
|
||||
void
|
||||
config_reset(uint32_t *args)
|
||||
{
|
||||
if (! sched_is_shutdown())
|
||||
shutdown("config_reset only available when shutdown");
|
||||
irq_disable();
|
||||
config_crc = 0;
|
||||
oid_count = 0;
|
||||
oids = NULL;
|
||||
move_free_list = NULL;
|
||||
move_list = NULL;
|
||||
move_count = move_item_size = 0;
|
||||
alloc_init();
|
||||
sched_timer_reset();
|
||||
sched_clear_shutdown();
|
||||
irq_enable();
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Timing and load stats
|
||||
****************************************************************/
|
||||
|
||||
void
|
||||
command_get_clock(uint32_t *args)
|
||||
{
|
||||
sendf("clock clock=%u", timer_read_time());
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_get_clock, HF_IN_SHUTDOWN, "get_clock");
|
||||
|
||||
static uint32_t stats_send_time, stats_send_time_high;
|
||||
|
||||
void
|
||||
command_get_uptime(uint32_t *args)
|
||||
{
|
||||
uint32_t cur = timer_read_time();
|
||||
uint32_t high = stats_send_time_high + (cur < stats_send_time);
|
||||
sendf("uptime high=%u clock=%u", high, cur);
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_get_uptime, HF_IN_SHUTDOWN, "get_uptime");
|
||||
|
||||
#define SUMSQ_BASE 256
|
||||
DECL_CONSTANT("STATS_SUMSQ_BASE", SUMSQ_BASE);
|
||||
|
||||
void
|
||||
stats_update(uint32_t start, uint32_t cur)
|
||||
{
|
||||
static uint32_t count, sum, sumsq;
|
||||
uint32_t diff = cur - start;
|
||||
count++;
|
||||
sum += diff;
|
||||
// Calculate sum of diff^2 - be careful of integer overflow
|
||||
uint32_t nextsumsq;
|
||||
if (diff <= 0xffff) {
|
||||
nextsumsq = sumsq + DIV_ROUND_UP(diff * diff, SUMSQ_BASE);
|
||||
} else if (diff <= 0xfffff) {
|
||||
nextsumsq = sumsq + DIV_ROUND_UP(diff, SUMSQ_BASE) * diff;
|
||||
} else {
|
||||
nextsumsq = 0xffffffff;
|
||||
}
|
||||
if (nextsumsq < sumsq)
|
||||
nextsumsq = 0xffffffff;
|
||||
sumsq = nextsumsq;
|
||||
|
||||
if (timer_is_before(cur, stats_send_time + timer_from_us(5000000)))
|
||||
return;
|
||||
sendf("stats count=%u sum=%u sumsq=%u", count, sum, sumsq);
|
||||
if (cur < stats_send_time)
|
||||
stats_send_time_high++;
|
||||
stats_send_time = cur;
|
||||
count = sum = sumsq = 0;
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Misc commands
|
||||
****************************************************************/
|
||||
|
||||
void
|
||||
command_emergency_stop(uint32_t *args)
|
||||
{
|
||||
shutdown("Command request");
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_emergency_stop, HF_IN_SHUTDOWN, "emergency_stop");
|
||||
|
||||
void
|
||||
command_clear_shutdown(uint32_t *args)
|
||||
{
|
||||
sched_clear_shutdown();
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_clear_shutdown, HF_IN_SHUTDOWN, "clear_shutdown");
|
||||
|
||||
void
|
||||
command_identify(uint32_t *args)
|
||||
{
|
||||
uint32_t offset = args[0];
|
||||
uint8_t count = args[1];
|
||||
uint32_t isize = READP(command_identify_size);
|
||||
if (offset >= isize)
|
||||
count = 0;
|
||||
else if (offset + count > isize)
|
||||
count = isize - offset;
|
||||
sendf("identify_response offset=%u data=%.*s"
|
||||
, offset, count, &command_identify_data[offset]);
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_identify, HF_IN_SHUTDOWN,
|
||||
"identify offset=%u count=%c");
|
||||
32
src/basecmd.h
Normal file
32
src/basecmd.h
Normal file
@@ -0,0 +1,32 @@
|
||||
#ifndef __BASECMD_H
|
||||
#define __BASECMD_H
|
||||
|
||||
#include <stddef.h> // size_t
|
||||
#include <stdint.h> // uint8_t
|
||||
|
||||
struct move_node {
|
||||
struct move_node *next;
|
||||
};
|
||||
struct move_queue_head {
|
||||
struct move_node *first, *last;
|
||||
};
|
||||
|
||||
void *alloc_chunk(size_t size);
|
||||
void move_free(void *m);
|
||||
void *move_alloc(void);
|
||||
int move_queue_empty(struct move_queue_head *mh);
|
||||
struct move_node *move_queue_first(struct move_queue_head *mh);
|
||||
int move_queue_push(struct move_node *m, struct move_queue_head *mh);
|
||||
struct move_node *move_queue_pop(struct move_queue_head *mh);
|
||||
void move_queue_clear(struct move_queue_head *mh);
|
||||
void move_queue_setup(struct move_queue_head *mh, int size);
|
||||
void *oid_lookup(uint8_t oid, void *type);
|
||||
void *oid_alloc(uint8_t oid, void *type, uint16_t size);
|
||||
void *oid_next(uint8_t *i, void *type);
|
||||
void stats_update(uint32_t start, uint32_t cur);
|
||||
void config_reset(uint32_t *args);
|
||||
|
||||
#define foreach_oid(pos,data,oidtype) \
|
||||
for (pos=-1; (data=oid_next(&pos, oidtype)); )
|
||||
|
||||
#endif // basecmd.h
|
||||
163
src/buttons.c
Normal file
163
src/buttons.c
Normal file
@@ -0,0 +1,163 @@
|
||||
// Report on user interface buttons
|
||||
//
|
||||
// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "basecmd.h" // oid_alloc
|
||||
#include "board/gpio.h" // struct gpio_in
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "command.h" // DECL_COMMAND
|
||||
#include "sched.h" // struct timer
|
||||
|
||||
struct buttons {
|
||||
struct timer time;
|
||||
uint32_t rest_ticks;
|
||||
uint8_t pressed, last_pressed;
|
||||
uint8_t report_count, reports[8];
|
||||
uint8_t ack_count, retransmit_state, retransmit_count;
|
||||
uint8_t button_count;
|
||||
struct gpio_in pins[0];
|
||||
};
|
||||
|
||||
enum { BF_NO_RETRANSMIT = 0x80, BF_PENDING = 0xff, BF_ACKED = 0xfe };
|
||||
|
||||
static struct task_wake buttons_wake;
|
||||
|
||||
static uint_fast8_t
|
||||
buttons_event(struct timer *t)
|
||||
{
|
||||
struct buttons *b = container_of(t, struct buttons, time);
|
||||
|
||||
// Read pins
|
||||
uint8_t i, bit, status = 0;
|
||||
for (i = 0, bit = 1; i < b->button_count; i++, bit <<= 1) {
|
||||
uint8_t val = gpio_in_read(b->pins[i]);
|
||||
if (val)
|
||||
status |= bit;
|
||||
}
|
||||
|
||||
// Check if any pins have changed since last time
|
||||
uint8_t diff = status ^ b->pressed;
|
||||
if (diff) {
|
||||
// At least one pin has changed - do button debouncing
|
||||
uint8_t debounced = ~(status ^ b->last_pressed);
|
||||
if (diff & debounced) {
|
||||
// Pin has been consistently different - report it
|
||||
b->pressed = (b->pressed & ~debounced) | (status & debounced);
|
||||
if (b->report_count < sizeof(b->reports)) {
|
||||
b->reports[b->report_count++] = b->pressed;
|
||||
sched_wake_task(&buttons_wake);
|
||||
b->retransmit_state = BF_PENDING;
|
||||
}
|
||||
}
|
||||
}
|
||||
b->last_pressed = status;
|
||||
|
||||
// Check if a retransmit is needed
|
||||
uint8_t retransmit_state = b->retransmit_state;
|
||||
if (!(retransmit_state & BF_NO_RETRANSMIT)) {
|
||||
retransmit_state--;
|
||||
if (retransmit_state & BF_NO_RETRANSMIT)
|
||||
// timeout - do retransmit
|
||||
sched_wake_task(&buttons_wake);
|
||||
b->retransmit_state = retransmit_state;
|
||||
}
|
||||
|
||||
// Reschedule timer
|
||||
b->time.waketime += b->rest_ticks;
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
|
||||
void
|
||||
command_config_buttons(uint32_t *args)
|
||||
{
|
||||
uint8_t button_count = args[1];
|
||||
if (button_count > 8)
|
||||
shutdown("Max of 8 buttons");
|
||||
struct buttons *b = oid_alloc(
|
||||
args[0], command_config_buttons
|
||||
, sizeof(*b) + sizeof(b->pins[0]) * button_count);
|
||||
b->button_count = button_count;
|
||||
b->time.func = buttons_event;
|
||||
}
|
||||
DECL_COMMAND(command_config_buttons, "config_buttons oid=%c button_count=%c");
|
||||
|
||||
void
|
||||
command_buttons_add(uint32_t *args)
|
||||
{
|
||||
struct buttons *b = oid_lookup(args[0], command_config_buttons);
|
||||
uint8_t pos = args[1];
|
||||
if (pos >= b->button_count)
|
||||
shutdown("Set button past maximum button count");
|
||||
b->pins[pos] = gpio_in_setup(args[2], args[3]);
|
||||
}
|
||||
DECL_COMMAND(command_buttons_add,
|
||||
"buttons_add oid=%c pos=%c pin=%u pull_up=%c");
|
||||
|
||||
void
|
||||
command_buttons_query(uint32_t *args)
|
||||
{
|
||||
struct buttons *b = oid_lookup(args[0], command_config_buttons);
|
||||
sched_del_timer(&b->time);
|
||||
b->time.waketime = args[1];
|
||||
b->rest_ticks = args[2];
|
||||
b->pressed = b->last_pressed = args[4];
|
||||
b->ack_count = b->report_count = 0;
|
||||
b->retransmit_state = BF_ACKED;
|
||||
b->retransmit_count = args[3];
|
||||
if (b->retransmit_count >= BF_NO_RETRANSMIT)
|
||||
shutdown("Invalid buttons retransmit count");
|
||||
if (! b->rest_ticks)
|
||||
return;
|
||||
sched_add_timer(&b->time);
|
||||
}
|
||||
DECL_COMMAND(command_buttons_query,
|
||||
"buttons_query oid=%c clock=%u rest_ticks=%u retransmit_count=%c"
|
||||
" invert=%c");
|
||||
|
||||
void
|
||||
command_buttons_ack(uint32_t *args)
|
||||
{
|
||||
struct buttons *b = oid_lookup(args[0], command_config_buttons);
|
||||
uint8_t count = args[1];
|
||||
b->ack_count += count;
|
||||
irq_disable();
|
||||
if (count >= b->report_count) {
|
||||
b->report_count = 0;
|
||||
b->retransmit_state = BF_ACKED;
|
||||
} else {
|
||||
uint8_t pending = b->report_count - count, i;
|
||||
for (i=0; i<pending; i++)
|
||||
b->reports[i] = b->reports[i+count];
|
||||
b->report_count = pending;
|
||||
}
|
||||
irq_enable();
|
||||
}
|
||||
DECL_COMMAND(command_buttons_ack, "buttons_ack oid=%c count=%c");
|
||||
|
||||
void
|
||||
buttons_task(void)
|
||||
{
|
||||
if (!sched_check_wake(&buttons_wake))
|
||||
return;
|
||||
uint8_t oid;
|
||||
struct buttons *b;
|
||||
foreach_oid(oid, b, command_config_buttons) {
|
||||
// See if need to transmit buttons_state
|
||||
if (b->retransmit_state != BF_PENDING)
|
||||
continue;
|
||||
// Generate message
|
||||
irq_disable();
|
||||
uint8_t report_count = b->report_count;
|
||||
if (!report_count) {
|
||||
irq_enable();
|
||||
continue;
|
||||
}
|
||||
b->retransmit_state = b->retransmit_count;
|
||||
irq_enable();
|
||||
sendf("buttons_state oid=%c ack_count=%c state=%*s"
|
||||
, oid, b->ack_count, report_count, b->reports);
|
||||
}
|
||||
}
|
||||
DECL_TASK(buttons_task);
|
||||
40
src/byteorder.h
Normal file
40
src/byteorder.h
Normal file
@@ -0,0 +1,40 @@
|
||||
#ifndef __BYTEORDER_H
|
||||
#define __BYTEORDER_H
|
||||
|
||||
#include <stdint.h> // uint32_t
|
||||
|
||||
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
|
||||
|
||||
#define cpu_to_le16(x) ((uint16_t)(x))
|
||||
#define cpu_to_le32(x) ((uint32_t)(x))
|
||||
#define cpu_to_le64(x) ((uint64_t)(x))
|
||||
#define le16_to_cpu(x) ((uint16_t)(x))
|
||||
#define le32_to_cpu(x) ((uint32_t)(x))
|
||||
#define le64_to_cpu(x) ((uint64_t)(x))
|
||||
|
||||
#define cpu_to_be16(x) __builtin_bswap16(x)
|
||||
#define cpu_to_be32(x) __builtin_bswap32(x)
|
||||
#define cpu_to_be64(x) __builtin_bswap64(x)
|
||||
#define be16_to_cpu(x) __builtin_bswap16(x)
|
||||
#define be32_to_cpu(x) __builtin_bswap32(x)
|
||||
#define be64_to_cpu(x) __builtin_bswap64(x)
|
||||
|
||||
#else // big endian
|
||||
|
||||
#define cpu_to_le16(x) __builtin_bswap16(x)
|
||||
#define cpu_to_le32(x) __builtin_bswap32(x)
|
||||
#define cpu_to_le64(x) __builtin_bswap64(x)
|
||||
#define le16_to_cpu(x) __builtin_bswap16(x)
|
||||
#define le32_to_cpu(x) __builtin_bswap32(x)
|
||||
#define le64_to_cpu(x) __builtin_bswap64(x)
|
||||
|
||||
#define cpu_to_be16(x) ((uint16_t)(x))
|
||||
#define cpu_to_be32(x) ((uint32_t)(x))
|
||||
#define cpu_to_be64(x) ((uint64_t)(x))
|
||||
#define be16_to_cpu(x) ((uint16_t)(x))
|
||||
#define be32_to_cpu(x) ((uint32_t)(x))
|
||||
#define be64_to_cpu(x) ((uint64_t)(x))
|
||||
|
||||
#endif
|
||||
|
||||
#endif // byteorder.h
|
||||
344
src/command.c
Normal file
344
src/command.c
Normal file
@@ -0,0 +1,344 @@
|
||||
// Code for parsing incoming commands and encoding outgoing messages
|
||||
//
|
||||
// Copyright (C) 2016,2017 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <stdarg.h> // va_start
|
||||
#include <string.h> // memcpy
|
||||
#include "board/io.h" // readb
|
||||
#include "board/irq.h" // irq_poll
|
||||
#include "board/misc.h" // crc16_ccitt
|
||||
#include "board/pgm.h" // READP
|
||||
#include "command.h" // output_P
|
||||
#include "sched.h" // sched_is_shutdown
|
||||
|
||||
static uint8_t next_sequence = MESSAGE_DEST;
|
||||
|
||||
static uint32_t
|
||||
command_encode_ptr(void *p)
|
||||
{
|
||||
if (sizeof(size_t) > sizeof(uint32_t))
|
||||
return p - console_receive_buffer();
|
||||
return (size_t)p;
|
||||
}
|
||||
|
||||
void *
|
||||
command_decode_ptr(uint32_t v)
|
||||
{
|
||||
if (sizeof(size_t) > sizeof(uint32_t))
|
||||
return console_receive_buffer() + v;
|
||||
return (void*)(size_t)v;
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Binary message parsing
|
||||
****************************************************************/
|
||||
|
||||
// Encode an integer as a variable length quantity (vlq)
|
||||
static uint8_t *
|
||||
encode_int(uint8_t *p, uint32_t v)
|
||||
{
|
||||
int32_t sv = v;
|
||||
if (sv < (3L<<5) && sv >= -(1L<<5)) goto f4;
|
||||
if (sv < (3L<<12) && sv >= -(1L<<12)) goto f3;
|
||||
if (sv < (3L<<19) && sv >= -(1L<<19)) goto f2;
|
||||
if (sv < (3L<<26) && sv >= -(1L<<26)) goto f1;
|
||||
*p++ = (v>>28) | 0x80;
|
||||
f1: *p++ = ((v>>21) & 0x7f) | 0x80;
|
||||
f2: *p++ = ((v>>14) & 0x7f) | 0x80;
|
||||
f3: *p++ = ((v>>7) & 0x7f) | 0x80;
|
||||
f4: *p++ = v & 0x7f;
|
||||
return p;
|
||||
}
|
||||
|
||||
// Parse an integer that was encoded as a "variable length quantity"
|
||||
static uint32_t
|
||||
parse_int(uint8_t **pp)
|
||||
{
|
||||
uint8_t *p = *pp, c = *p++;
|
||||
uint32_t v = c & 0x7f;
|
||||
if ((c & 0x60) == 0x60)
|
||||
v |= -0x20;
|
||||
while (c & 0x80) {
|
||||
c = *p++;
|
||||
v = (v<<7) | (c & 0x7f);
|
||||
}
|
||||
*pp = p;
|
||||
return v;
|
||||
}
|
||||
|
||||
// Parse an incoming command into 'args'
|
||||
uint8_t *
|
||||
command_parsef(uint8_t *p, uint8_t *maxend
|
||||
, const struct command_parser *cp, uint32_t *args)
|
||||
{
|
||||
uint_fast8_t num_params = READP(cp->num_params);
|
||||
const uint8_t *param_types = READP(cp->param_types);
|
||||
while (num_params--) {
|
||||
if (p > maxend)
|
||||
goto error;
|
||||
uint_fast8_t t = READP(*param_types);
|
||||
param_types++;
|
||||
switch (t) {
|
||||
case PT_uint32:
|
||||
case PT_int32:
|
||||
case PT_uint16:
|
||||
case PT_int16:
|
||||
case PT_byte:
|
||||
*args++ = parse_int(&p);
|
||||
break;
|
||||
case PT_buffer: {
|
||||
uint_fast8_t len = *p++;
|
||||
if (p + len > maxend)
|
||||
goto error;
|
||||
*args++ = len;
|
||||
*args++ = command_encode_ptr(p);
|
||||
p += len;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
goto error;
|
||||
}
|
||||
}
|
||||
return p;
|
||||
error:
|
||||
shutdown("Command parser error");
|
||||
}
|
||||
|
||||
// Encode a message
|
||||
static uint_fast8_t
|
||||
command_encodef(uint8_t *buf, const struct command_encoder *ce, va_list args)
|
||||
{
|
||||
uint_fast8_t max_size = READP(ce->max_size);
|
||||
if (max_size <= MESSAGE_MIN)
|
||||
// Ack/Nak message
|
||||
return max_size;
|
||||
uint8_t *p = &buf[MESSAGE_HEADER_SIZE];
|
||||
uint8_t *maxend = &p[max_size - MESSAGE_MIN];
|
||||
uint_fast8_t num_params = READP(ce->num_params);
|
||||
const uint8_t *param_types = READP(ce->param_types);
|
||||
*p++ = READP(ce->msg_id);
|
||||
while (num_params--) {
|
||||
if (p > maxend)
|
||||
goto error;
|
||||
uint_fast8_t t = READP(*param_types);
|
||||
param_types++;
|
||||
uint32_t v;
|
||||
switch (t) {
|
||||
case PT_uint32:
|
||||
case PT_int32:
|
||||
case PT_uint16:
|
||||
case PT_int16:
|
||||
case PT_byte:
|
||||
if (sizeof(v) > sizeof(int) && t >= PT_uint16)
|
||||
if (t == PT_int16)
|
||||
v = (int32_t)va_arg(args, int);
|
||||
else
|
||||
v = va_arg(args, unsigned int);
|
||||
else
|
||||
v = va_arg(args, uint32_t);
|
||||
p = encode_int(p, v);
|
||||
break;
|
||||
case PT_string: {
|
||||
uint8_t *s = va_arg(args, uint8_t*), *lenp = p++;
|
||||
while (*s && p<maxend)
|
||||
*p++ = *s++;
|
||||
*lenp = p-lenp-1;
|
||||
break;
|
||||
}
|
||||
case PT_progmem_buffer:
|
||||
case PT_buffer: {
|
||||
v = va_arg(args, int);
|
||||
if (v > maxend-p)
|
||||
v = maxend-p;
|
||||
*p++ = v;
|
||||
uint8_t *s = va_arg(args, uint8_t*);
|
||||
if (t == PT_progmem_buffer)
|
||||
memcpy_P(p, s, v);
|
||||
else
|
||||
memcpy(p, s, v);
|
||||
p += v;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
goto error;
|
||||
}
|
||||
}
|
||||
return p - buf + MESSAGE_TRAILER_SIZE;
|
||||
error:
|
||||
shutdown("Message encode error");
|
||||
}
|
||||
|
||||
// Add header and trailer bytes to a message block
|
||||
static void
|
||||
command_add_frame(uint8_t *buf, uint_fast8_t msglen)
|
||||
{
|
||||
buf[MESSAGE_POS_LEN] = msglen;
|
||||
buf[MESSAGE_POS_SEQ] = next_sequence;
|
||||
uint16_t crc = crc16_ccitt(buf, msglen - MESSAGE_TRAILER_SIZE);
|
||||
buf[msglen - MESSAGE_TRAILER_CRC + 0] = crc >> 8;
|
||||
buf[msglen - MESSAGE_TRAILER_CRC + 1] = crc;
|
||||
buf[msglen - MESSAGE_TRAILER_SYNC] = MESSAGE_SYNC;
|
||||
}
|
||||
|
||||
// Encode a message and then add a message block frame around it
|
||||
uint_fast8_t
|
||||
command_encode_and_frame(uint8_t *buf, const struct command_encoder *ce
|
||||
, va_list args)
|
||||
{
|
||||
uint_fast8_t msglen = command_encodef(buf, ce, args);
|
||||
command_add_frame(buf, msglen);
|
||||
return msglen;
|
||||
}
|
||||
|
||||
static uint8_t in_sendf;
|
||||
|
||||
// Encode and transmit a "response" message
|
||||
void
|
||||
command_sendf(const struct command_encoder *ce, ...)
|
||||
{
|
||||
if (readb(&in_sendf))
|
||||
// This sendf call was made from an irq handler while the main
|
||||
// code was already in sendf - just drop this sendf request.
|
||||
return;
|
||||
writeb(&in_sendf, 1);
|
||||
|
||||
va_list args;
|
||||
va_start(args, ce);
|
||||
console_sendf(ce, args);
|
||||
va_end(args);
|
||||
|
||||
writeb(&in_sendf, 0);
|
||||
}
|
||||
|
||||
void
|
||||
sendf_shutdown(void)
|
||||
{
|
||||
writeb(&in_sendf, 0);
|
||||
}
|
||||
DECL_SHUTDOWN(sendf_shutdown);
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Command routing
|
||||
****************************************************************/
|
||||
|
||||
// Find the command handler associated with a command
|
||||
static const struct command_parser *
|
||||
command_lookup_parser(uint_fast8_t cmdid)
|
||||
{
|
||||
if (!cmdid || cmdid >= READP(command_index_size))
|
||||
shutdown("Invalid command");
|
||||
return &command_index[cmdid];
|
||||
}
|
||||
|
||||
// Empty message (for ack/nak transmission)
|
||||
const struct command_encoder encode_acknak PROGMEM = {
|
||||
.max_size = MESSAGE_MIN,
|
||||
};
|
||||
|
||||
enum { CF_NEED_SYNC=1<<0, CF_NEED_VALID=1<<1 };
|
||||
|
||||
// Find the next complete message block
|
||||
int_fast8_t
|
||||
command_find_block(uint8_t *buf, uint_fast8_t buf_len, uint_fast8_t *pop_count)
|
||||
{
|
||||
static uint8_t sync_state;
|
||||
if (buf_len && sync_state & CF_NEED_SYNC)
|
||||
goto need_sync;
|
||||
if (buf_len < MESSAGE_MIN)
|
||||
goto need_more_data;
|
||||
uint_fast8_t msglen = buf[MESSAGE_POS_LEN];
|
||||
if (msglen < MESSAGE_MIN || msglen > MESSAGE_MAX)
|
||||
goto error;
|
||||
uint_fast8_t msgseq = buf[MESSAGE_POS_SEQ];
|
||||
if ((msgseq & ~MESSAGE_SEQ_MASK) != MESSAGE_DEST)
|
||||
goto error;
|
||||
if (buf_len < msglen)
|
||||
goto need_more_data;
|
||||
if (buf[msglen-MESSAGE_TRAILER_SYNC] != MESSAGE_SYNC)
|
||||
goto error;
|
||||
uint16_t msgcrc = ((buf[msglen-MESSAGE_TRAILER_CRC] << 8)
|
||||
| buf[msglen-MESSAGE_TRAILER_CRC+1]);
|
||||
uint16_t crc = crc16_ccitt(buf, msglen-MESSAGE_TRAILER_SIZE);
|
||||
if (crc != msgcrc)
|
||||
goto error;
|
||||
sync_state &= ~CF_NEED_VALID;
|
||||
*pop_count = msglen;
|
||||
// Check sequence number
|
||||
if (msgseq != next_sequence) {
|
||||
// Lost message - discard messages until it is retransmitted
|
||||
goto nak;
|
||||
}
|
||||
next_sequence = ((msgseq + 1) & MESSAGE_SEQ_MASK) | MESSAGE_DEST;
|
||||
return 1;
|
||||
|
||||
need_more_data:
|
||||
*pop_count = 0;
|
||||
return 0;
|
||||
error:
|
||||
if (buf[0] == MESSAGE_SYNC) {
|
||||
// Ignore (do not nak) leading SYNC bytes
|
||||
*pop_count = 1;
|
||||
return -1;
|
||||
}
|
||||
sync_state |= CF_NEED_SYNC;
|
||||
need_sync: ;
|
||||
// Discard bytes until next SYNC found
|
||||
uint8_t *next_sync = memchr(buf, MESSAGE_SYNC, buf_len);
|
||||
if (next_sync) {
|
||||
sync_state &= ~CF_NEED_SYNC;
|
||||
*pop_count = next_sync - buf + 1;
|
||||
} else {
|
||||
*pop_count = buf_len;
|
||||
}
|
||||
if (sync_state & CF_NEED_VALID)
|
||||
return -1;
|
||||
sync_state |= CF_NEED_VALID;
|
||||
nak:
|
||||
command_sendf(&encode_acknak);
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Dispatch all the commands found in a message block
|
||||
void
|
||||
command_dispatch(uint8_t *buf, uint_fast8_t msglen)
|
||||
{
|
||||
uint8_t *p = &buf[MESSAGE_HEADER_SIZE];
|
||||
uint8_t *msgend = &buf[msglen-MESSAGE_TRAILER_SIZE];
|
||||
while (p < msgend) {
|
||||
uint_fast8_t cmdid = *p++;
|
||||
const struct command_parser *cp = command_lookup_parser(cmdid);
|
||||
uint32_t args[READP(cp->num_args)];
|
||||
p = command_parsef(p, msgend, cp, args);
|
||||
if (sched_is_shutdown() && !(READP(cp->flags) & HF_IN_SHUTDOWN)) {
|
||||
sched_report_shutdown();
|
||||
continue;
|
||||
}
|
||||
irq_poll();
|
||||
void (*func)(uint32_t*) = READP(cp->func);
|
||||
func(args);
|
||||
}
|
||||
}
|
||||
|
||||
// Send an ack message to the host (notifying that it can send more data)
|
||||
void
|
||||
command_send_ack(void)
|
||||
{
|
||||
command_sendf(&encode_acknak);
|
||||
}
|
||||
|
||||
// Find a message block and then dispatch all the commands in it
|
||||
int_fast8_t
|
||||
command_find_and_dispatch(uint8_t *buf, uint_fast8_t buf_len
|
||||
, uint_fast8_t *pop_count)
|
||||
{
|
||||
int_fast8_t ret = command_find_block(buf, buf_len, pop_count);
|
||||
if (ret > 0) {
|
||||
command_dispatch(buf, *pop_count);
|
||||
command_send_ack();
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
108
src/command.h
Normal file
108
src/command.h
Normal file
@@ -0,0 +1,108 @@
|
||||
#ifndef __COMMAND_H
|
||||
#define __COMMAND_H
|
||||
|
||||
#include <stdarg.h> // va_list
|
||||
#include <stddef.h>
|
||||
#include <stdint.h> // uint8_t
|
||||
#include "ctr.h" // DECL_CTR
|
||||
|
||||
// Declare a function to run when the specified command is received
|
||||
#define DECL_COMMAND_FLAGS(FUNC, FLAGS, MSG) \
|
||||
DECL_CTR("DECL_COMMAND_FLAGS " __stringify(FUNC) " " \
|
||||
__stringify(FLAGS) " " MSG)
|
||||
#define DECL_COMMAND(FUNC, MSG) \
|
||||
DECL_COMMAND_FLAGS(FUNC, 0, MSG)
|
||||
|
||||
// Flags for command handler declarations.
|
||||
#define HF_IN_SHUTDOWN 0x01 // Handler can run even when in emergency stop
|
||||
|
||||
// Declare a constant exported to the host
|
||||
#define DECL_CONSTANT(NAME, VALUE) \
|
||||
DECL_CTR_INT("DECL_CONSTANT " NAME, 1, CTR_INT(VALUE))
|
||||
#define DECL_CONSTANT_STR(NAME, VALUE) \
|
||||
DECL_CTR("DECL_CONSTANT_STR " NAME " " VALUE)
|
||||
|
||||
// Declare an enumeration
|
||||
#define DECL_ENUMERATION(ENUM, NAME, VALUE) \
|
||||
DECL_CTR_INT("DECL_ENUMERATION " ENUM " " NAME, 1, CTR_INT(VALUE))
|
||||
#define DECL_ENUMERATION_RANGE(ENUM, NAME, VALUE, COUNT) \
|
||||
DECL_CTR_INT("DECL_ENUMERATION_RANGE " ENUM " " NAME, \
|
||||
2, CTR_INT(VALUE), CTR_INT(COUNT))
|
||||
|
||||
// Send an output message (and declare a static message type for it)
|
||||
#define output(FMT, args...) \
|
||||
command_sendf(_DECL_OUTPUT(FMT) , ##args )
|
||||
|
||||
// Declare a message type and transmit it.
|
||||
#define sendf(FMT, args...) \
|
||||
command_sendf(_DECL_ENCODER(FMT) , ##args )
|
||||
|
||||
// Shut down the machine (also declares a static string to transmit)
|
||||
#define shutdown(msg) \
|
||||
sched_shutdown(_DECL_STATIC_STR(msg))
|
||||
#define try_shutdown(msg) \
|
||||
sched_try_shutdown(_DECL_STATIC_STR(msg))
|
||||
|
||||
#define MESSAGE_MIN 5
|
||||
#define MESSAGE_MAX 64
|
||||
#define MESSAGE_HEADER_SIZE 2
|
||||
#define MESSAGE_TRAILER_SIZE 3
|
||||
#define MESSAGE_POS_LEN 0
|
||||
#define MESSAGE_POS_SEQ 1
|
||||
#define MESSAGE_TRAILER_CRC 3
|
||||
#define MESSAGE_TRAILER_SYNC 1
|
||||
#define MESSAGE_PAYLOAD_MAX (MESSAGE_MAX - MESSAGE_MIN)
|
||||
#define MESSAGE_SEQ_MASK 0x0f
|
||||
#define MESSAGE_DEST 0x10
|
||||
#define MESSAGE_SYNC 0x7E
|
||||
|
||||
struct command_encoder {
|
||||
uint8_t msg_id, max_size, num_params;
|
||||
const uint8_t *param_types;
|
||||
};
|
||||
struct command_parser {
|
||||
uint8_t msg_id, num_args, flags, num_params;
|
||||
const uint8_t *param_types;
|
||||
void (*func)(uint32_t *args);
|
||||
};
|
||||
enum {
|
||||
PT_uint32, PT_int32, PT_uint16, PT_int16, PT_byte,
|
||||
PT_string, PT_progmem_buffer, PT_buffer,
|
||||
};
|
||||
|
||||
// command.c
|
||||
void *command_decode_ptr(uint32_t v);
|
||||
uint8_t *command_parsef(uint8_t *p, uint8_t *maxend
|
||||
, const struct command_parser *cp, uint32_t *args);
|
||||
uint_fast8_t command_encode_and_frame(
|
||||
uint8_t *buf, const struct command_encoder *ce, va_list args);
|
||||
void command_sendf(const struct command_encoder *ce, ...);
|
||||
int_fast8_t command_find_block(uint8_t *buf, uint_fast8_t buf_len
|
||||
, uint_fast8_t *pop_count);
|
||||
void command_dispatch(uint8_t *buf, uint_fast8_t msglen);
|
||||
void command_send_ack(void);
|
||||
int_fast8_t command_find_and_dispatch(uint8_t *buf, uint_fast8_t buf_len
|
||||
, uint_fast8_t *pop_count);
|
||||
|
||||
// out/compile_time_request.c (auto generated file)
|
||||
extern const struct command_parser command_index[];
|
||||
extern const uint8_t command_index_size;
|
||||
extern const uint8_t command_identify_data[];
|
||||
extern const uint32_t command_identify_size;
|
||||
const struct command_encoder *ctr_lookup_encoder(const char *str);
|
||||
const struct command_encoder *ctr_lookup_output(const char *str);
|
||||
uint8_t ctr_lookup_static_string(const char *str);
|
||||
|
||||
#define _DECL_ENCODER(FMT) ({ \
|
||||
DECL_CTR("_DECL_ENCODER " FMT); \
|
||||
ctr_lookup_encoder(FMT); })
|
||||
|
||||
#define _DECL_OUTPUT(FMT) ({ \
|
||||
DECL_CTR("_DECL_OUTPUT " FMT); \
|
||||
ctr_lookup_output(FMT); })
|
||||
|
||||
#define _DECL_STATIC_STR(MSG) ({ \
|
||||
DECL_CTR("_DECL_STATIC_STR " MSG); \
|
||||
ctr_lookup_static_string(MSG); })
|
||||
|
||||
#endif // command.h
|
||||
46
src/compiler.h
Normal file
46
src/compiler.h
Normal file
@@ -0,0 +1,46 @@
|
||||
#ifndef __COMPILER_H
|
||||
#define __COMPILER_H
|
||||
// Low level definitions for C languange and gcc compiler.
|
||||
|
||||
#define barrier() __asm__ __volatile__("": : :"memory")
|
||||
|
||||
#define likely(x) __builtin_expect(!!(x), 1)
|
||||
#define unlikely(x) __builtin_expect(!!(x), 0)
|
||||
|
||||
#define noinline __attribute__((noinline))
|
||||
#ifndef __always_inline
|
||||
#define __always_inline inline __attribute__((always_inline))
|
||||
#endif
|
||||
#define __visible __attribute__((externally_visible))
|
||||
#define __noreturn __attribute__((noreturn))
|
||||
|
||||
#define PACKED __attribute__((packed))
|
||||
#ifndef __aligned
|
||||
#define __aligned(x) __attribute__((aligned(x)))
|
||||
#endif
|
||||
#ifndef __section
|
||||
#define __section(S) __attribute__((section(S)))
|
||||
#endif
|
||||
|
||||
#define ARRAY_SIZE(a) (sizeof(a) / sizeof(a[0]))
|
||||
#define ALIGN(x,a) __ALIGN_MASK(x,(typeof(x))(a)-1)
|
||||
#define __ALIGN_MASK(x,mask) (((x)+(mask))&~(mask))
|
||||
#define ALIGN_DOWN(x,a) ((x) & ~((typeof(x))(a)-1))
|
||||
|
||||
#define container_of(ptr, type, member) ({ \
|
||||
const typeof( ((type *)0)->member ) *__mptr = (ptr); \
|
||||
(type *)( (char *)__mptr - offsetof(type,member) );})
|
||||
|
||||
#define __stringify_1(x) #x
|
||||
#define __stringify(x) __stringify_1(x)
|
||||
|
||||
#define ___PASTE(a,b) a##b
|
||||
#define __PASTE(a,b) ___PASTE(a,b)
|
||||
|
||||
#define DIV_ROUND_UP(n,d) (((n) + (d) - 1) / (d))
|
||||
#define DIV_ROUND_CLOSEST(x, divisor)({ \
|
||||
typeof(divisor) __divisor = divisor; \
|
||||
(((x) + ((__divisor) / 2)) / (__divisor)); \
|
||||
})
|
||||
|
||||
#endif // compiler.h
|
||||
38
src/ctr.h
Normal file
38
src/ctr.h
Normal file
@@ -0,0 +1,38 @@
|
||||
#ifndef __CTR_H
|
||||
#define __CTR_H
|
||||
// Definitions for creating compile time requests. The DECL_CTR macro
|
||||
// produces requests (text strings) that are placed in a special
|
||||
// section of the intermediate object files (*.o). The build extracts
|
||||
// these strings and places them in out/compile_time_requests.txt.
|
||||
// The scripts/buildcommand.py code then generates
|
||||
// out/compile_time_request.c from these requests.
|
||||
|
||||
#include "compiler.h" // __section
|
||||
|
||||
// Declare a compile time request
|
||||
#define DECL_CTR(REQUEST) \
|
||||
static char __PASTE(_DECLS_, __LINE__)[] __attribute__((used)) \
|
||||
__section(".compile_time_request") = (REQUEST)
|
||||
|
||||
// Macro to encode an integer for use with DECL_CTR_INT()
|
||||
#define _CTR_HEX(H) ((H) > 9 ? (H) - 10 + 'A' : (H) + '0')
|
||||
#define _CTR_SHIFT(V, S) _CTR_HEX(((uint32_t)(V) >> (S)) & 0x0f)
|
||||
#define _CTR_INT(V, S) ((V) < 0 ? _CTR_SHIFT(-(V), (S)) : _CTR_SHIFT((V), (S)))
|
||||
#define CTR_INT(VALUE) { \
|
||||
' ', (VALUE) < 0 ? '-' : '+', '0', 'x', \
|
||||
_CTR_INT((VALUE),28), _CTR_INT((VALUE),24), \
|
||||
_CTR_INT((VALUE),20), _CTR_INT((VALUE),16), \
|
||||
_CTR_INT((VALUE),12), _CTR_INT((VALUE),8), \
|
||||
_CTR_INT((VALUE),4), _CTR_INT((VALUE),0) }
|
||||
|
||||
// Declare a compile time request with an integer expression
|
||||
#define DECL_CTR_INT(REQUEST, PARAM_COUNT, args...) \
|
||||
static struct { \
|
||||
char _request[sizeof(REQUEST)-1]; \
|
||||
char _values[(PARAM_COUNT)][12]; \
|
||||
char _end_of_line; \
|
||||
} __PASTE(_DECLI_, __LINE__) __attribute__((used)) \
|
||||
__section(".compile_time_request") = { \
|
||||
(REQUEST), { args }, 0 }
|
||||
|
||||
#endif // ctr.h
|
||||
59
src/debugcmds.c
Normal file
59
src/debugcmds.c
Normal file
@@ -0,0 +1,59 @@
|
||||
// Debugging commands.
|
||||
//
|
||||
// Copyright (C) 2016-2021 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "board/io.h" // readl
|
||||
#include "board/irq.h" // irq_save
|
||||
#include "command.h" // DECL_COMMAND
|
||||
|
||||
void
|
||||
command_debug_read(uint32_t *args)
|
||||
{
|
||||
uint8_t order = args[0];
|
||||
void *ptr = command_decode_ptr(args[1]);
|
||||
uint32_t v;
|
||||
irqstatus_t flag = irq_save();
|
||||
switch (order) {
|
||||
default: case 0: v = readb(ptr); break;
|
||||
case 1: v = readw(ptr); break;
|
||||
case 2: v = readl(ptr); break;
|
||||
}
|
||||
irq_restore(flag);
|
||||
sendf("debug_result val=%u", v);
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_debug_read, HF_IN_SHUTDOWN,
|
||||
"debug_read order=%c addr=%u");
|
||||
|
||||
void
|
||||
command_debug_write(uint32_t *args)
|
||||
{
|
||||
uint8_t order = args[0];
|
||||
void *ptr = command_decode_ptr(args[1]);
|
||||
uint32_t v = args[2];
|
||||
irqstatus_t flag = irq_save();
|
||||
switch (order) {
|
||||
default: case 0: writeb(ptr, v); break;
|
||||
case 1: writew(ptr, v); break;
|
||||
case 2: writel(ptr, v); break;
|
||||
}
|
||||
irq_restore(flag);
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_debug_write, HF_IN_SHUTDOWN,
|
||||
"debug_write order=%c addr=%u val=%u");
|
||||
|
||||
void
|
||||
command_debug_ping(uint32_t *args)
|
||||
{
|
||||
uint8_t len = args[0];
|
||||
char *data = command_decode_ptr(args[1]);
|
||||
sendf("pong data=%*s", len, data);
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_debug_ping, HF_IN_SHUTDOWN, "debug_ping data=%*s");
|
||||
|
||||
void
|
||||
command_debug_nop(uint32_t *args)
|
||||
{
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_debug_nop, HF_IN_SHUTDOWN, "debug_nop");
|
||||
115
src/endstop.c
Normal file
115
src/endstop.c
Normal file
@@ -0,0 +1,115 @@
|
||||
// Handling of end stops.
|
||||
//
|
||||
// Copyright (C) 2016-2021 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "basecmd.h" // oid_alloc
|
||||
#include "board/gpio.h" // struct gpio
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "command.h" // DECL_COMMAND
|
||||
#include "sched.h" // struct timer
|
||||
#include "trsync.h" // trsync_do_trigger
|
||||
|
||||
struct endstop {
|
||||
struct timer time;
|
||||
struct gpio_in pin;
|
||||
uint32_t rest_time, sample_time, nextwake;
|
||||
struct trsync *ts;
|
||||
uint8_t flags, sample_count, trigger_count, trigger_reason;
|
||||
};
|
||||
|
||||
enum { ESF_PIN_HIGH=1<<0, ESF_HOMING=1<<1 };
|
||||
|
||||
static uint_fast8_t endstop_oversample_event(struct timer *t);
|
||||
|
||||
// Timer callback for an end stop
|
||||
static uint_fast8_t
|
||||
endstop_event(struct timer *t)
|
||||
{
|
||||
struct endstop *e = container_of(t, struct endstop, time);
|
||||
uint8_t val = gpio_in_read(e->pin);
|
||||
uint32_t nextwake = e->time.waketime + e->rest_time;
|
||||
if ((val ? ~e->flags : e->flags) & ESF_PIN_HIGH) {
|
||||
// No match - reschedule for the next attempt
|
||||
e->time.waketime = nextwake;
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
e->nextwake = nextwake;
|
||||
e->time.func = endstop_oversample_event;
|
||||
return endstop_oversample_event(t);
|
||||
}
|
||||
|
||||
// Timer callback for an end stop that is sampling extra times
|
||||
static uint_fast8_t
|
||||
endstop_oversample_event(struct timer *t)
|
||||
{
|
||||
struct endstop *e = container_of(t, struct endstop, time);
|
||||
uint8_t val = gpio_in_read(e->pin);
|
||||
if ((val ? ~e->flags : e->flags) & ESF_PIN_HIGH) {
|
||||
// No longer matching - reschedule for the next attempt
|
||||
e->time.func = endstop_event;
|
||||
e->time.waketime = e->nextwake;
|
||||
e->trigger_count = e->sample_count;
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
uint8_t count = e->trigger_count - 1;
|
||||
if (!count) {
|
||||
trsync_do_trigger(e->ts, e->trigger_reason);
|
||||
return SF_DONE;
|
||||
}
|
||||
e->trigger_count = count;
|
||||
e->time.waketime += e->sample_time;
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
|
||||
void
|
||||
command_config_endstop(uint32_t *args)
|
||||
{
|
||||
struct endstop *e = oid_alloc(args[0], command_config_endstop, sizeof(*e));
|
||||
e->pin = gpio_in_setup(args[1], args[2]);
|
||||
}
|
||||
DECL_COMMAND(command_config_endstop, "config_endstop oid=%c pin=%c pull_up=%c");
|
||||
|
||||
// Home an axis
|
||||
void
|
||||
command_endstop_home(uint32_t *args)
|
||||
{
|
||||
struct endstop *e = oid_lookup(args[0], command_config_endstop);
|
||||
sched_del_timer(&e->time);
|
||||
e->time.waketime = args[1];
|
||||
e->sample_time = args[2];
|
||||
e->sample_count = args[3];
|
||||
if (!e->sample_count) {
|
||||
// Disable end stop checking
|
||||
e->ts = NULL;
|
||||
e->flags = 0;
|
||||
return;
|
||||
}
|
||||
e->rest_time = args[4];
|
||||
e->time.func = endstop_event;
|
||||
e->trigger_count = e->sample_count;
|
||||
e->flags = ESF_HOMING | (args[5] ? ESF_PIN_HIGH : 0);
|
||||
e->ts = trsync_oid_lookup(args[6]);
|
||||
e->trigger_reason = args[7];
|
||||
sched_add_timer(&e->time);
|
||||
}
|
||||
DECL_COMMAND(command_endstop_home,
|
||||
"endstop_home oid=%c clock=%u sample_ticks=%u sample_count=%c"
|
||||
" rest_ticks=%u pin_value=%c trsync_oid=%c trigger_reason=%c");
|
||||
|
||||
void
|
||||
command_endstop_query_state(uint32_t *args)
|
||||
{
|
||||
uint8_t oid = args[0];
|
||||
struct endstop *e = oid_lookup(oid, command_config_endstop);
|
||||
|
||||
irq_disable();
|
||||
uint8_t eflags = e->flags;
|
||||
uint32_t nextwake = e->nextwake;
|
||||
irq_enable();
|
||||
|
||||
sendf("endstop_state oid=%c homing=%c next_clock=%u pin_value=%c"
|
||||
, oid, !!(eflags & ESF_HOMING), nextwake, gpio_in_read(e->pin));
|
||||
}
|
||||
DECL_COMMAND(command_endstop_query_state, "endstop_query_state oid=%c");
|
||||
23
src/generic/alloc.c
Normal file
23
src/generic/alloc.c
Normal file
@@ -0,0 +1,23 @@
|
||||
// Generic implementation of dynamic memory pool
|
||||
//
|
||||
// Copyright (C) 2016,2017 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "misc.h" // dynmem_start
|
||||
|
||||
static char dynmem_pool[20 * 1024];
|
||||
|
||||
// Return the start of memory available for dynamic allocations
|
||||
void *
|
||||
dynmem_start(void)
|
||||
{
|
||||
return dynmem_pool;
|
||||
}
|
||||
|
||||
// Return the end of memory available for dynamic allocations
|
||||
void *
|
||||
dynmem_end(void)
|
||||
{
|
||||
return &dynmem_pool[sizeof(dynmem_pool)];
|
||||
}
|
||||
119
src/generic/armcm_boot.c
Normal file
119
src/generic/armcm_boot.c
Normal file
@@ -0,0 +1,119 @@
|
||||
// ARM Cortex-M vector table and initial bootup handling
|
||||
//
|
||||
// Copyright (C) 2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "armcm_boot.h" // DECL_ARMCM_IRQ
|
||||
#include "autoconf.h" // CONFIG_MCU
|
||||
#include "board/internal.h" // SysTick
|
||||
#include "command.h" // DECL_CONSTANT_STR
|
||||
#include "misc.h" // dynmem_start
|
||||
|
||||
// Export MCU type
|
||||
DECL_CONSTANT_STR("MCU", CONFIG_MCU);
|
||||
|
||||
// Symbols created by armcm_link.lds.S linker script
|
||||
extern uint32_t _data_start, _data_end, _data_flash;
|
||||
extern uint32_t _bss_start, _bss_end, _stack_start;
|
||||
extern uint32_t _stack_end;
|
||||
|
||||
/****************************************************************
|
||||
* Basic interrupt handlers
|
||||
****************************************************************/
|
||||
|
||||
static void __noreturn
|
||||
reset_handler_stage_two(void)
|
||||
{
|
||||
int i;
|
||||
|
||||
// Clear all enabled user interrupts and user pending interrupts
|
||||
for (i = 0; i < ARRAY_SIZE(NVIC->ICER); i++) {
|
||||
NVIC->ICER[i] = 0xFFFFFFFF;
|
||||
__DSB();
|
||||
NVIC->ICPR[i] = 0xFFFFFFFF;
|
||||
}
|
||||
|
||||
// Reset all user interrupt priorities
|
||||
for (i = 0; i < ARRAY_SIZE(NVIC->IP); i++)
|
||||
NVIC->IP[i] = 0;
|
||||
|
||||
// Disable SysTick interrupt
|
||||
SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk;
|
||||
__DSB();
|
||||
|
||||
// Clear pending pendsv and systick interrupts
|
||||
SCB->ICSR = SCB_ICSR_PENDSVCLR_Msk | SCB_ICSR_PENDSTCLR_Msk;
|
||||
|
||||
// Reset all system interrupt priorities
|
||||
#if __CORTEX_M >= 7
|
||||
for (i = 0; i < ARRAY_SIZE(SCB->SHPR); i++)
|
||||
SCB->SHPR[i] = 0;
|
||||
#else
|
||||
for (i = 0; i < ARRAY_SIZE(SCB->SHP); i++)
|
||||
SCB->SHP[i] = 0;
|
||||
#endif
|
||||
|
||||
__DSB();
|
||||
__ISB();
|
||||
__enable_irq();
|
||||
|
||||
// Copy global variables from flash to ram
|
||||
uint32_t count = (&_data_end - &_data_start) * 4;
|
||||
__builtin_memcpy(&_data_start, &_data_flash, count);
|
||||
|
||||
// Clear the bss segment
|
||||
__builtin_memset(&_bss_start, 0, (&_bss_end - &_bss_start) * 4);
|
||||
|
||||
barrier();
|
||||
|
||||
// Initializing the C library isn't needed...
|
||||
//__libc_init_array();
|
||||
|
||||
// Run the main board specific code
|
||||
armcm_main();
|
||||
|
||||
// The armcm_main() call should not return
|
||||
for (;;)
|
||||
;
|
||||
}
|
||||
|
||||
// Initial code entry point - invoked by the processor after a reset
|
||||
// Reset interrupts and stack to take control from bootloaders
|
||||
void
|
||||
ResetHandler(void)
|
||||
{
|
||||
__disable_irq();
|
||||
|
||||
// Explicitly load the stack pointer, jump to stage two
|
||||
asm volatile("mov sp, %0\n bx %1"
|
||||
: : "r"(&_stack_end), "r"(reset_handler_stage_two));
|
||||
}
|
||||
DECL_ARMCM_IRQ(ResetHandler, -15);
|
||||
|
||||
// Code called for any undefined interrupts
|
||||
void
|
||||
DefaultHandler(void)
|
||||
{
|
||||
for (;;)
|
||||
;
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Dynamic memory range
|
||||
****************************************************************/
|
||||
|
||||
// Return the start of memory available for dynamic allocations
|
||||
void *
|
||||
dynmem_start(void)
|
||||
{
|
||||
return &_bss_end;
|
||||
}
|
||||
|
||||
// Return the end of memory available for dynamic allocations
|
||||
void *
|
||||
dynmem_end(void)
|
||||
{
|
||||
return &_stack_start;
|
||||
}
|
||||
22
src/generic/armcm_boot.h
Normal file
22
src/generic/armcm_boot.h
Normal file
@@ -0,0 +1,22 @@
|
||||
#ifndef __GENERIC_ARMCM_BOOT_H
|
||||
#define __GENERIC_ARMCM_BOOT_H
|
||||
|
||||
#include "ctr.h" // DECL_CTR_INT
|
||||
|
||||
void armcm_main(void);
|
||||
|
||||
// Declare an IRQ handler
|
||||
#define DECL_ARMCM_IRQ(FUNC, NUM) \
|
||||
DECL_CTR_INT("DECL_ARMCM_IRQ " __stringify(FUNC), 1, CTR_INT(NUM))
|
||||
|
||||
// Statically declare an IRQ handler and run-time enable it
|
||||
#define armcm_enable_irq(FUNC, NUM, PRIORITY) do { \
|
||||
DECL_ARMCM_IRQ(FUNC, (NUM)); \
|
||||
NVIC_SetPriority((NUM), (PRIORITY)); \
|
||||
NVIC_EnableIRQ((NUM)); \
|
||||
} while (0)
|
||||
|
||||
// Vectors created by scripts/buildcommands.py from DECL_ARMCM_IRQ commands
|
||||
extern const void * const VectorTable[];
|
||||
|
||||
#endif // armcm_boot.h
|
||||
75
src/generic/armcm_irq.c
Normal file
75
src/generic/armcm_irq.c
Normal file
@@ -0,0 +1,75 @@
|
||||
// Definitions for irq enable/disable on ARM Cortex-M processors
|
||||
//
|
||||
// Copyright (C) 2017-2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "board/internal.h" // __CORTEX_M
|
||||
#include "irq.h" // irqstatus_t
|
||||
#include "sched.h" // DECL_SHUTDOWN
|
||||
|
||||
void
|
||||
irq_disable(void)
|
||||
{
|
||||
asm volatile("cpsid i" ::: "memory");
|
||||
}
|
||||
|
||||
void
|
||||
irq_enable(void)
|
||||
{
|
||||
asm volatile("cpsie i" ::: "memory");
|
||||
}
|
||||
|
||||
irqstatus_t
|
||||
irq_save(void)
|
||||
{
|
||||
irqstatus_t flag;
|
||||
asm volatile("mrs %0, primask" : "=r" (flag) :: "memory");
|
||||
irq_disable();
|
||||
return flag;
|
||||
}
|
||||
|
||||
void
|
||||
irq_restore(irqstatus_t flag)
|
||||
{
|
||||
asm volatile("msr primask, %0" :: "r" (flag) : "memory");
|
||||
}
|
||||
|
||||
void
|
||||
irq_wait(void)
|
||||
{
|
||||
if (__CORTEX_M >= 7)
|
||||
// Cortex-m7 may disable cpu counter on wfi, so use nop
|
||||
asm volatile("cpsie i\n nop\n cpsid i\n" ::: "memory");
|
||||
else
|
||||
asm volatile("cpsie i\n wfi\n cpsid i\n" ::: "memory");
|
||||
}
|
||||
|
||||
void
|
||||
irq_poll(void)
|
||||
{
|
||||
}
|
||||
|
||||
// Clear the active irq if a shutdown happened in an irq handler
|
||||
void
|
||||
clear_active_irq(void)
|
||||
{
|
||||
uint32_t psr;
|
||||
asm volatile("mrs %0, psr" : "=r" (psr));
|
||||
if (!(psr & 0x1ff))
|
||||
// Shutdown did not occur in an irq - nothing to do.
|
||||
return;
|
||||
// Clear active irq status
|
||||
psr = 1<<24; // T-bit
|
||||
uint32_t temp;
|
||||
asm volatile(
|
||||
" push { %1 }\n"
|
||||
" adr %0, 1f\n"
|
||||
" push { %0 }\n"
|
||||
" push { r0, r1, r2, r3, r4, lr }\n"
|
||||
" bx %2\n"
|
||||
".balign 4\n"
|
||||
"1:\n"
|
||||
: "=&r"(temp) : "r"(psr), "r"(0xfffffff9) : "r12", "cc");
|
||||
}
|
||||
DECL_SHUTDOWN(clear_active_irq);
|
||||
73
src/generic/armcm_link.lds.S
Normal file
73
src/generic/armcm_link.lds.S
Normal file
@@ -0,0 +1,73 @@
|
||||
// Generic ARM Cortex-M linker script
|
||||
//
|
||||
// Copyright (C) 2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_FLASH_START
|
||||
|
||||
OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
|
||||
OUTPUT_ARCH(arm)
|
||||
|
||||
MEMORY
|
||||
{
|
||||
rom (rx) : ORIGIN = CONFIG_FLASH_START , LENGTH = CONFIG_FLASH_SIZE
|
||||
ram (rwx) : ORIGIN = CONFIG_RAM_START , LENGTH = CONFIG_RAM_SIZE
|
||||
}
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text : {
|
||||
. = ALIGN(4);
|
||||
_text_vectortable_start = .;
|
||||
KEEP(*(.vector_table))
|
||||
_text_vectortable_end = .;
|
||||
*(.text .text.*)
|
||||
*(.rodata .rodata*)
|
||||
} > rom
|
||||
|
||||
. = ALIGN(4);
|
||||
_data_flash = .;
|
||||
|
||||
#if CONFIG_ARMCM_RAM_VECTORTABLE
|
||||
.ram_vectortable (NOLOAD) : {
|
||||
_ram_vectortable_start = .;
|
||||
. = . + ( _text_vectortable_end - _text_vectortable_start ) ;
|
||||
_ram_vectortable_end = .;
|
||||
} > ram
|
||||
#endif
|
||||
|
||||
.data : AT (_data_flash)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_data_start = .;
|
||||
*(.ramfunc .ramfunc.*);
|
||||
*(.data .data.*);
|
||||
. = ALIGN(4);
|
||||
_data_end = .;
|
||||
} > ram
|
||||
|
||||
.bss (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_bss_start = .;
|
||||
*(.bss .bss.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_bss_end = .;
|
||||
} > ram
|
||||
|
||||
_stack_start = CONFIG_RAM_START + CONFIG_RAM_SIZE - CONFIG_STACK_SIZE ;
|
||||
.stack _stack_start (NOLOAD) :
|
||||
{
|
||||
. = . + CONFIG_STACK_SIZE;
|
||||
_stack_end = .;
|
||||
} > ram
|
||||
|
||||
/DISCARD/ : {
|
||||
// The .init/.fini sections are used by __libc_init_array(), but
|
||||
// that isn't needed so no need to include them in the binary.
|
||||
*(.init)
|
||||
*(.fini)
|
||||
}
|
||||
}
|
||||
48
src/generic/armcm_reset.c
Normal file
48
src/generic/armcm_reset.c
Normal file
@@ -0,0 +1,48 @@
|
||||
// Generic reset command handler for ARM Cortex-M boards
|
||||
//
|
||||
// Copyright (C) 2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// 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 "board/internal.h" // NVIC_SystemReset
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "command.h" // DECL_COMMAND_FLAGS
|
||||
|
||||
#define CANBOOT_SIGNATURE 0x21746f6f426e6143
|
||||
#define CANBOOT_REQUEST 0x5984E3FA6CA1589B
|
||||
#define CANBOOT_BYPASS 0x7b06ec45a9a8243d
|
||||
|
||||
static void
|
||||
canboot_reset(uint64_t req_signature)
|
||||
{
|
||||
if (!(CONFIG_FLASH_START & 0x00FFFFFF))
|
||||
// No bootloader
|
||||
return;
|
||||
uint32_t *bl_vectors = (uint32_t *)(CONFIG_FLASH_START & 0xFF000000);
|
||||
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();
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
try_request_canboot(void)
|
||||
{
|
||||
canboot_reset(CANBOOT_REQUEST);
|
||||
}
|
||||
|
||||
void
|
||||
command_reset(uint32_t *args)
|
||||
{
|
||||
canboot_reset(CANBOOT_BYPASS);
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_reset, HF_IN_SHUTDOWN, "reset");
|
||||
6
src/generic/armcm_reset.h
Normal file
6
src/generic/armcm_reset.h
Normal file
@@ -0,0 +1,6 @@
|
||||
#ifndef __GENERIC_ARMCM_RESET_H
|
||||
#define __GENERIC_ARMCM_RESET_H
|
||||
|
||||
void try_request_canboot(void);
|
||||
|
||||
#endif // armcm_reset.h
|
||||
176
src/generic/armcm_timer.c
Normal file
176
src/generic/armcm_timer.c
Normal file
@@ -0,0 +1,176 @@
|
||||
// Timer based on ARM Cortex-M3/M4 SysTick and DWT logic
|
||||
//
|
||||
// Copyright (C) 2017-2019 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_CLOCK_FREQ
|
||||
#include "armcm_boot.h" // DECL_ARMCM_IRQ
|
||||
#include "board/internal.h" // SysTick
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "board/misc.h" // timer_from_us
|
||||
#include "command.h" // shutdown
|
||||
#include "sched.h" // sched_timer_dispatch
|
||||
|
||||
DECL_CONSTANT("CLOCK_FREQ", CONFIG_CLOCK_FREQ);
|
||||
|
||||
// Return the number of clock ticks for a given number of microseconds
|
||||
uint32_t
|
||||
timer_from_us(uint32_t us)
|
||||
{
|
||||
return us * (CONFIG_CLOCK_FREQ / 1000000);
|
||||
}
|
||||
|
||||
// Return true if time1 is before time2. Always use this function to
|
||||
// compare times as regular C comparisons can fail if the counter
|
||||
// rolls over.
|
||||
uint8_t
|
||||
timer_is_before(uint32_t time1, uint32_t time2)
|
||||
{
|
||||
return (int32_t)(time1 - time2) < 0;
|
||||
}
|
||||
|
||||
// Set the next irq time
|
||||
static void
|
||||
timer_set_diff(uint32_t value)
|
||||
{
|
||||
SysTick->LOAD = value;
|
||||
SysTick->VAL = 0;
|
||||
SysTick->LOAD = 0;
|
||||
}
|
||||
|
||||
// Return the current time (in absolute clock ticks).
|
||||
uint32_t
|
||||
timer_read_time(void)
|
||||
{
|
||||
return DWT->CYCCNT;
|
||||
}
|
||||
|
||||
// Activate timer dispatch as soon as possible
|
||||
void
|
||||
timer_kick(void)
|
||||
{
|
||||
SysTick->LOAD = 0;
|
||||
SysTick->VAL = 0;
|
||||
SCB->ICSR = SCB_ICSR_PENDSTSET_Msk;
|
||||
}
|
||||
|
||||
// Implement simple early-boot delay mechanism
|
||||
void
|
||||
udelay(uint32_t usecs)
|
||||
{
|
||||
if (!(CoreDebug->DEMCR & CoreDebug_DEMCR_TRCENA_Msk)) {
|
||||
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
|
||||
DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk;
|
||||
}
|
||||
|
||||
uint32_t end = timer_read_time() + timer_from_us(usecs);
|
||||
while (timer_is_before(timer_read_time(), end))
|
||||
;
|
||||
}
|
||||
|
||||
// Dummy timer to avoid scheduling a SysTick irq greater than 0xffffff
|
||||
static uint_fast8_t
|
||||
timer_wrap_event(struct timer *t)
|
||||
{
|
||||
t->waketime += 0xffffff;
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
static struct timer wrap_timer = {
|
||||
.func = timer_wrap_event,
|
||||
.waketime = 0xffffff,
|
||||
};
|
||||
void
|
||||
timer_reset(void)
|
||||
{
|
||||
if (timer_from_us(100000) <= 0xffffff)
|
||||
// Timer in sched.c already ensures SysTick wont overflow
|
||||
return;
|
||||
sched_add_timer(&wrap_timer);
|
||||
}
|
||||
DECL_SHUTDOWN(timer_reset);
|
||||
|
||||
void
|
||||
timer_init(void)
|
||||
{
|
||||
// Enable Debug Watchpoint and Trace (DWT) for its 32bit timer
|
||||
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
|
||||
DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk;
|
||||
DWT->CYCCNT = 0;
|
||||
|
||||
// Schedule a recurring timer on fast cpus
|
||||
timer_reset();
|
||||
|
||||
// Enable SysTick
|
||||
irqstatus_t flag = irq_save();
|
||||
NVIC_SetPriority(SysTick_IRQn, 2);
|
||||
SysTick->CTRL = (SysTick_CTRL_CLKSOURCE_Msk | SysTick_CTRL_TICKINT_Msk
|
||||
| SysTick_CTRL_ENABLE_Msk);
|
||||
timer_kick();
|
||||
irq_restore(flag);
|
||||
}
|
||||
DECL_INIT(timer_init);
|
||||
|
||||
static uint32_t timer_repeat_until;
|
||||
#define TIMER_IDLE_REPEAT_TICKS timer_from_us(500)
|
||||
#define TIMER_REPEAT_TICKS timer_from_us(100)
|
||||
|
||||
#define TIMER_MIN_TRY_TICKS timer_from_us(2)
|
||||
#define TIMER_DEFER_REPEAT_TICKS timer_from_us(5)
|
||||
|
||||
// Invoke timers
|
||||
static uint32_t
|
||||
timer_dispatch_many(void)
|
||||
{
|
||||
uint32_t tru = timer_repeat_until;
|
||||
for (;;) {
|
||||
// Run the next software timer
|
||||
uint32_t next = sched_timer_dispatch();
|
||||
|
||||
uint32_t now = timer_read_time();
|
||||
int32_t diff = next - now;
|
||||
if (diff > (int32_t)TIMER_MIN_TRY_TICKS)
|
||||
// Schedule next timer normally.
|
||||
return diff;
|
||||
|
||||
if (unlikely(timer_is_before(tru, now))) {
|
||||
// Check if there are too many repeat timers
|
||||
if (diff < (int32_t)(-timer_from_us(1000)))
|
||||
try_shutdown("Rescheduled timer in the past");
|
||||
if (sched_tasks_busy()) {
|
||||
timer_repeat_until = now + TIMER_REPEAT_TICKS;
|
||||
return TIMER_DEFER_REPEAT_TICKS;
|
||||
}
|
||||
timer_repeat_until = tru = now + TIMER_IDLE_REPEAT_TICKS;
|
||||
}
|
||||
|
||||
// Next timer in the past or near future - wait for it to be ready
|
||||
irq_enable();
|
||||
while (unlikely(diff > 0))
|
||||
diff = next - timer_read_time();
|
||||
irq_disable();
|
||||
}
|
||||
}
|
||||
|
||||
// IRQ handler
|
||||
void __visible __aligned(16) // aligning helps stabilize perf benchmarks
|
||||
SysTick_Handler(void)
|
||||
{
|
||||
irq_disable();
|
||||
uint32_t diff = timer_dispatch_many();
|
||||
timer_set_diff(diff);
|
||||
irq_enable();
|
||||
}
|
||||
DECL_ARMCM_IRQ(SysTick_Handler, SysTick_IRQn);
|
||||
|
||||
// Make sure timer_repeat_until doesn't wrap 32bit comparisons
|
||||
void
|
||||
timer_task(void)
|
||||
{
|
||||
uint32_t now = timer_read_time();
|
||||
irq_disable();
|
||||
if (timer_is_before(timer_repeat_until, now))
|
||||
timer_repeat_until = now;
|
||||
irq_enable();
|
||||
}
|
||||
DECL_TASK(timer_task);
|
||||
8
src/generic/armcm_timer.h
Normal file
8
src/generic/armcm_timer.h
Normal file
@@ -0,0 +1,8 @@
|
||||
#ifndef __GENERIC_ARMCM_TIMER_H
|
||||
#define __GENERIC_ARMCM_TIMER_H
|
||||
|
||||
#include <stdint.h> // uint32_t
|
||||
|
||||
void udelay(uint32_t usecs);
|
||||
|
||||
#endif // armcm_timer.h
|
||||
32
src/generic/canbus.c
Normal file
32
src/generic/canbus.c
Normal file
@@ -0,0 +1,32 @@
|
||||
// Wrapper functions connecting canserial.c to low-level can hardware
|
||||
//
|
||||
// Copyright (C) 2022 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "canbus.h" // canbus_send
|
||||
#include "canserial.h" // canserial_send
|
||||
|
||||
int
|
||||
canserial_send(struct canbus_msg *msg)
|
||||
{
|
||||
return canbus_send(msg);
|
||||
}
|
||||
|
||||
void
|
||||
canserial_set_filter(uint32_t id)
|
||||
{
|
||||
canbus_set_filter(id);
|
||||
}
|
||||
|
||||
void
|
||||
canbus_notify_tx(void)
|
||||
{
|
||||
canserial_notify_tx();
|
||||
}
|
||||
|
||||
void
|
||||
canbus_process_data(struct canbus_msg *msg)
|
||||
{
|
||||
canserial_process_data(msg);
|
||||
}
|
||||
28
src/generic/canbus.h
Normal file
28
src/generic/canbus.h
Normal file
@@ -0,0 +1,28 @@
|
||||
#ifndef __CANBUS_H__
|
||||
#define __CANBUS_H__
|
||||
|
||||
#include <stdint.h> // uint32_t
|
||||
|
||||
struct canbus_msg {
|
||||
uint32_t id;
|
||||
uint32_t dlc;
|
||||
union {
|
||||
uint8_t data[8];
|
||||
uint32_t data32[2];
|
||||
};
|
||||
};
|
||||
|
||||
#define CANMSG_ID_RTR (1<<30)
|
||||
#define CANMSG_ID_EFF (1<<31)
|
||||
|
||||
#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);
|
||||
|
||||
// canbus.c
|
||||
void canbus_notify_tx(void);
|
||||
void canbus_process_data(struct canbus_msg *msg);
|
||||
|
||||
#endif // canbus.h
|
||||
344
src/generic/canserial.c
Normal file
344
src/generic/canserial.c
Normal file
@@ -0,0 +1,344 @@
|
||||
// Generic handling of serial over CAN support
|
||||
//
|
||||
// Copyright (C) 2019 Eug Krashtan <eug.krashtan@gmail.com>
|
||||
// Copyright (C) 2020 Pontus Borg <glpontus@gmail.com>
|
||||
// Copyright (C) 2021 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/armcm_reset.h" // try_request_canboot
|
||||
#include "board/io.h" // readb
|
||||
#include "board/irq.h" // irq_save
|
||||
#include "board/misc.h" // console_sendf
|
||||
#include "canbus.h" // canbus_set_uuid
|
||||
#include "canserial.h" // canserial_notify_tx
|
||||
#include "command.h" // DECL_CONSTANT
|
||||
#include "fasthash.h" // fasthash64
|
||||
#include "sched.h" // sched_wake_task
|
||||
|
||||
#define CANBUS_UUID_LEN 6
|
||||
|
||||
// Global storage
|
||||
static struct canbus_data {
|
||||
uint32_t assigned_id;
|
||||
uint8_t uuid[CANBUS_UUID_LEN];
|
||||
|
||||
// Tx data
|
||||
struct task_wake tx_wake;
|
||||
uint8_t transmit_pos, transmit_max;
|
||||
|
||||
// Rx data
|
||||
struct task_wake rx_wake;
|
||||
uint8_t receive_pos;
|
||||
uint32_t admin_pull_pos, admin_push_pos;
|
||||
|
||||
// Transfer buffers
|
||||
struct canbus_msg admin_queue[8];
|
||||
uint8_t transmit_buf[96];
|
||||
uint8_t receive_buf[192];
|
||||
} CanData;
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Data transmission over CAN
|
||||
****************************************************************/
|
||||
|
||||
void
|
||||
canserial_notify_tx(void)
|
||||
{
|
||||
sched_wake_task(&CanData.tx_wake);
|
||||
}
|
||||
|
||||
void
|
||||
canserial_tx_task(void)
|
||||
{
|
||||
if (!sched_check_wake(&CanData.tx_wake))
|
||||
return;
|
||||
uint32_t id = CanData.assigned_id;
|
||||
if (!id) {
|
||||
CanData.transmit_pos = CanData.transmit_max = 0;
|
||||
return;
|
||||
}
|
||||
struct canbus_msg msg;
|
||||
msg.id = id + 1;
|
||||
uint32_t tpos = CanData.transmit_pos, tmax = CanData.transmit_max;
|
||||
for (;;) {
|
||||
int avail = tmax - tpos, now = avail > 8 ? 8 : avail;
|
||||
if (avail <= 0)
|
||||
break;
|
||||
msg.dlc = now;
|
||||
memcpy(msg.data, &CanData.transmit_buf[tpos], now);
|
||||
int ret = canserial_send(&msg);
|
||||
if (ret <= 0)
|
||||
break;
|
||||
tpos += now;
|
||||
}
|
||||
CanData.transmit_pos = tpos;
|
||||
}
|
||||
DECL_TASK(canserial_tx_task);
|
||||
|
||||
// Encode and transmit a "response" message
|
||||
void
|
||||
console_sendf(const struct command_encoder *ce, va_list args)
|
||||
{
|
||||
// Verify space for message
|
||||
uint32_t tpos = CanData.transmit_pos, tmax = CanData.transmit_max;
|
||||
if (tpos >= tmax)
|
||||
CanData.transmit_pos = CanData.transmit_max = tpos = tmax = 0;
|
||||
uint32_t max_size = ce->max_size;
|
||||
if (tmax + max_size > sizeof(CanData.transmit_buf)) {
|
||||
if (tmax + max_size - tpos > sizeof(CanData.transmit_buf))
|
||||
// Not enough space for message
|
||||
return;
|
||||
// Move buffer
|
||||
tmax -= tpos;
|
||||
memmove(&CanData.transmit_buf[0], &CanData.transmit_buf[tpos], tmax);
|
||||
CanData.transmit_pos = tpos = 0;
|
||||
CanData.transmit_max = tmax;
|
||||
}
|
||||
|
||||
// Generate message
|
||||
uint32_t msglen = command_encode_and_frame(&CanData.transmit_buf[tmax]
|
||||
, ce, args);
|
||||
|
||||
// Start message transmit
|
||||
CanData.transmit_max = tmax + msglen;
|
||||
canserial_notify_tx();
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* CAN "admin" command handling
|
||||
****************************************************************/
|
||||
|
||||
// Available commands and responses
|
||||
#define CANBUS_CMD_QUERY_UNASSIGNED 0x00
|
||||
#define CANBUS_CMD_SET_KLIPPER_NODEID 0x01
|
||||
#define CANBUS_CMD_REQUEST_BOOTLOADER 0x02
|
||||
#define CANBUS_RESP_NEED_NODEID 0x20
|
||||
|
||||
// Helper to verify a UUID in a command matches this chip's UUID
|
||||
static int
|
||||
can_check_uuid(struct canbus_msg *msg)
|
||||
{
|
||||
return (msg->dlc >= 7
|
||||
&& memcmp(&msg->data[1], CanData.uuid, sizeof(CanData.uuid)) == 0);
|
||||
}
|
||||
|
||||
// Helpers to encode/decode a CAN identifier to a 1-byte "nodeid"
|
||||
static int
|
||||
can_get_nodeid(void)
|
||||
{
|
||||
if (!CanData.assigned_id)
|
||||
return 0;
|
||||
return (CanData.assigned_id - 0x100) >> 1;
|
||||
}
|
||||
static uint32_t
|
||||
can_decode_nodeid(int nodeid)
|
||||
{
|
||||
return (nodeid << 1) + 0x100;
|
||||
}
|
||||
|
||||
static void
|
||||
can_process_query_unassigned(struct canbus_msg *msg)
|
||||
{
|
||||
if (CanData.assigned_id)
|
||||
return;
|
||||
struct canbus_msg send;
|
||||
send.id = CANBUS_ID_ADMIN_RESP;
|
||||
send.dlc = 8;
|
||||
send.data[0] = CANBUS_RESP_NEED_NODEID;
|
||||
memcpy(&send.data[1], CanData.uuid, sizeof(CanData.uuid));
|
||||
send.data[7] = CANBUS_CMD_SET_KLIPPER_NODEID;
|
||||
// Send with retry
|
||||
for (;;) {
|
||||
int ret = canserial_send(&send);
|
||||
if (ret >= 0)
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
can_id_conflict(void)
|
||||
{
|
||||
CanData.assigned_id = 0;
|
||||
canserial_set_filter(CanData.assigned_id);
|
||||
shutdown("Another CAN node assigned this ID");
|
||||
}
|
||||
|
||||
static void
|
||||
can_process_set_klipper_nodeid(struct canbus_msg *msg)
|
||||
{
|
||||
if (msg->dlc < 8)
|
||||
return;
|
||||
uint32_t newid = can_decode_nodeid(msg->data[7]);
|
||||
if (can_check_uuid(msg)) {
|
||||
if (newid != CanData.assigned_id) {
|
||||
CanData.assigned_id = newid;
|
||||
canserial_set_filter(CanData.assigned_id);
|
||||
}
|
||||
} else if (newid == CanData.assigned_id) {
|
||||
can_id_conflict();
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
can_process_request_bootloader(struct canbus_msg *msg)
|
||||
{
|
||||
if (!can_check_uuid(msg))
|
||||
return;
|
||||
try_request_canboot();
|
||||
}
|
||||
|
||||
// Handle an "admin" command
|
||||
static void
|
||||
can_process_admin(struct canbus_msg *msg)
|
||||
{
|
||||
if (!msg->dlc)
|
||||
return;
|
||||
switch (msg->data[0]) {
|
||||
case CANBUS_CMD_QUERY_UNASSIGNED:
|
||||
can_process_query_unassigned(msg);
|
||||
break;
|
||||
case CANBUS_CMD_SET_KLIPPER_NODEID:
|
||||
can_process_set_klipper_nodeid(msg);
|
||||
break;
|
||||
case CANBUS_CMD_REQUEST_BOOTLOADER:
|
||||
can_process_request_bootloader(msg);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* CAN packet reading
|
||||
****************************************************************/
|
||||
|
||||
static void
|
||||
canserial_notify_rx(void)
|
||||
{
|
||||
sched_wake_task(&CanData.rx_wake);
|
||||
}
|
||||
|
||||
DECL_CONSTANT("RECEIVE_WINDOW", ARRAY_SIZE(CanData.receive_buf));
|
||||
|
||||
// Handle incoming data (called from IRQ handler)
|
||||
int
|
||||
canserial_process_data(struct canbus_msg *msg)
|
||||
{
|
||||
uint32_t id = msg->id;
|
||||
if (CanData.assigned_id && id == CanData.assigned_id) {
|
||||
// Add to incoming data buffer
|
||||
int rpos = CanData.receive_pos;
|
||||
uint32_t len = CANMSG_DATA_LEN(msg);
|
||||
if (len > sizeof(CanData.receive_buf) - rpos)
|
||||
return -1;
|
||||
memcpy(&CanData.receive_buf[rpos], msg->data, len);
|
||||
CanData.receive_pos = rpos + len;
|
||||
canserial_notify_rx();
|
||||
} else if (id == CANBUS_ID_ADMIN
|
||||
|| (CanData.assigned_id && id == CanData.assigned_id + 1)) {
|
||||
// Add to admin command queue
|
||||
uint32_t pushp = CanData.admin_push_pos;
|
||||
if (pushp >= CanData.admin_pull_pos + ARRAY_SIZE(CanData.admin_queue))
|
||||
// No space - drop message
|
||||
return -1;
|
||||
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
|
||||
static void
|
||||
console_pop_input(int len)
|
||||
{
|
||||
int copied = 0;
|
||||
for (;;) {
|
||||
int rpos = readb(&CanData.receive_pos);
|
||||
int needcopy = rpos - len;
|
||||
if (needcopy) {
|
||||
memmove(&CanData.receive_buf[copied]
|
||||
, &CanData.receive_buf[copied + len], needcopy - copied);
|
||||
copied = needcopy;
|
||||
canserial_notify_rx();
|
||||
}
|
||||
irqstatus_t flag = irq_save();
|
||||
if (rpos != readb(&CanData.receive_pos)) {
|
||||
// Raced with irq handler - retry
|
||||
irq_restore(flag);
|
||||
continue;
|
||||
}
|
||||
CanData.receive_pos = needcopy;
|
||||
irq_restore(flag);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Task to process incoming commands and admin messages
|
||||
void
|
||||
canserial_rx_task(void)
|
||||
{
|
||||
if (!sched_check_wake(&CanData.rx_wake))
|
||||
return;
|
||||
|
||||
// Process pending admin messages
|
||||
for (;;) {
|
||||
uint32_t pushp = readl(&CanData.admin_push_pos);
|
||||
uint32_t pullp = CanData.admin_pull_pos;
|
||||
if (pushp == pullp)
|
||||
break;
|
||||
uint32_t pos = pullp % ARRAY_SIZE(CanData.admin_queue);
|
||||
struct canbus_msg *msg = &CanData.admin_queue[pos];
|
||||
uint32_t id = msg->id;
|
||||
if (CanData.assigned_id && id == CanData.assigned_id + 1)
|
||||
can_id_conflict();
|
||||
else if (id == CANBUS_ID_ADMIN)
|
||||
can_process_admin(msg);
|
||||
CanData.admin_pull_pos = pullp + 1;
|
||||
}
|
||||
|
||||
// Check for a complete message block and process it
|
||||
uint_fast8_t rpos = readb(&CanData.receive_pos), pop_count;
|
||||
int ret = command_find_block(CanData.receive_buf, rpos, &pop_count);
|
||||
if (ret > 0)
|
||||
command_dispatch(CanData.receive_buf, pop_count);
|
||||
if (ret) {
|
||||
console_pop_input(pop_count);
|
||||
if (ret > 0)
|
||||
command_send_ack();
|
||||
}
|
||||
}
|
||||
DECL_TASK(canserial_rx_task);
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Setup and shutdown
|
||||
****************************************************************/
|
||||
|
||||
void
|
||||
command_get_canbus_id(uint32_t *args)
|
||||
{
|
||||
sendf("canbus_id canbus_uuid=%.*s canbus_nodeid=%u"
|
||||
, sizeof(CanData.uuid), CanData.uuid, can_get_nodeid());
|
||||
}
|
||||
DECL_COMMAND_FLAGS(command_get_canbus_id, HF_IN_SHUTDOWN, "get_canbus_id");
|
||||
|
||||
void
|
||||
canserial_set_uuid(uint8_t *raw_uuid, uint32_t raw_uuid_len)
|
||||
{
|
||||
uint64_t hash = fasthash64(raw_uuid, raw_uuid_len, 0xA16231A7);
|
||||
memcpy(CanData.uuid, &hash, sizeof(CanData.uuid));
|
||||
canserial_notify_rx();
|
||||
}
|
||||
|
||||
void
|
||||
canserial_shutdown(void)
|
||||
{
|
||||
canserial_notify_tx();
|
||||
canserial_notify_rx();
|
||||
}
|
||||
DECL_SHUTDOWN(canserial_shutdown);
|
||||
19
src/generic/canserial.h
Normal file
19
src/generic/canserial.h
Normal file
@@ -0,0 +1,19 @@
|
||||
#ifndef __CANSERIAL_H__
|
||||
#define __CANSERIAL_H__
|
||||
|
||||
#include <stdint.h> // uint32_t
|
||||
|
||||
#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);
|
||||
void canserial_set_uuid(uint8_t *raw_uuid, uint32_t raw_uuid_len);
|
||||
|
||||
#endif // canbus.h
|
||||
22
src/generic/crc16_ccitt.c
Normal file
22
src/generic/crc16_ccitt.c
Normal file
@@ -0,0 +1,22 @@
|
||||
// Code for crc16_ccitt
|
||||
//
|
||||
// Copyright (C) 2016 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "misc.h" // crc16_ccitt
|
||||
|
||||
// Implement the standard crc "ccitt" algorithm on the given buffer
|
||||
uint16_t
|
||||
crc16_ccitt(uint8_t *buf, uint_fast8_t len)
|
||||
{
|
||||
uint16_t crc = 0xffff;
|
||||
while (len--) {
|
||||
uint8_t data = *buf++;
|
||||
data ^= crc & 0xff;
|
||||
data ^= data << 4;
|
||||
crc = ((((uint16_t)data << 8) | (crc >> 8)) ^ (uint8_t)(data >> 4)
|
||||
^ ((uint16_t)data << 3));
|
||||
}
|
||||
return crc;
|
||||
}
|
||||
44
src/generic/gpio.h
Normal file
44
src/generic/gpio.h
Normal file
@@ -0,0 +1,44 @@
|
||||
#ifndef __GENERIC_GPIO_H
|
||||
#define __GENERIC_GPIO_H
|
||||
|
||||
#include <stdint.h> // uint8_t
|
||||
|
||||
struct gpio_out {
|
||||
uint8_t pin;
|
||||
};
|
||||
struct gpio_out gpio_out_setup(uint8_t pin, uint8_t val);
|
||||
void gpio_out_reset(struct gpio_out g, uint8_t val);
|
||||
void gpio_out_toggle_noirq(struct gpio_out g);
|
||||
void gpio_out_toggle(struct gpio_out g);
|
||||
void gpio_out_write(struct gpio_out g, uint8_t val);
|
||||
|
||||
struct gpio_in {
|
||||
uint8_t pin;
|
||||
};
|
||||
struct gpio_in gpio_in_setup(uint8_t pin, int8_t pull_up);
|
||||
void gpio_in_reset(struct gpio_in g, int8_t pull_up);
|
||||
uint8_t gpio_in_read(struct gpio_in g);
|
||||
|
||||
struct gpio_pwm {
|
||||
uint8_t pin;
|
||||
};
|
||||
struct gpio_pwm gpio_pwm_setup(uint8_t pin, uint32_t cycle_time, uint8_t val);
|
||||
void gpio_pwm_write(struct gpio_pwm g, uint8_t val);
|
||||
|
||||
struct gpio_adc {
|
||||
uint8_t pin;
|
||||
};
|
||||
struct gpio_adc gpio_adc_setup(uint8_t pin);
|
||||
uint32_t gpio_adc_sample(struct gpio_adc g);
|
||||
uint16_t gpio_adc_read(struct gpio_adc g);
|
||||
void gpio_adc_cancel_sample(struct gpio_adc g);
|
||||
|
||||
struct spi_config {
|
||||
uint32_t cfg;
|
||||
};
|
||||
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 // gpio.h
|
||||
35
src/generic/io.h
Normal file
35
src/generic/io.h
Normal file
@@ -0,0 +1,35 @@
|
||||
#ifndef __GENERIC_IO_H
|
||||
#define __GENERIC_IO_H
|
||||
|
||||
#include <stdint.h> // uint32_t
|
||||
#include "compiler.h" // barrier
|
||||
|
||||
static inline void writel(void *addr, uint32_t val) {
|
||||
barrier();
|
||||
*(volatile uint32_t *)addr = val;
|
||||
}
|
||||
static inline void writew(void *addr, uint16_t val) {
|
||||
barrier();
|
||||
*(volatile uint16_t *)addr = val;
|
||||
}
|
||||
static inline void writeb(void *addr, uint8_t val) {
|
||||
barrier();
|
||||
*(volatile uint8_t *)addr = val;
|
||||
}
|
||||
static inline uint32_t readl(const void *addr) {
|
||||
uint32_t val = *(volatile const uint32_t *)addr;
|
||||
barrier();
|
||||
return val;
|
||||
}
|
||||
static inline uint16_t readw(const void *addr) {
|
||||
uint16_t val = *(volatile const uint16_t *)addr;
|
||||
barrier();
|
||||
return val;
|
||||
}
|
||||
static inline uint8_t readb(const void *addr) {
|
||||
uint8_t val = *(volatile const uint8_t *)addr;
|
||||
barrier();
|
||||
return val;
|
||||
}
|
||||
|
||||
#endif // io.h
|
||||
13
src/generic/irq.h
Normal file
13
src/generic/irq.h
Normal file
@@ -0,0 +1,13 @@
|
||||
#ifndef __GENERIC_IRQ_H
|
||||
#define __GENERIC_IRQ_H
|
||||
|
||||
typedef unsigned long irqstatus_t;
|
||||
|
||||
void irq_disable(void);
|
||||
void irq_enable(void);
|
||||
irqstatus_t irq_save(void);
|
||||
void irq_restore(irqstatus_t flag);
|
||||
void irq_wait(void);
|
||||
void irq_poll(void);
|
||||
|
||||
#endif // irq.h
|
||||
21
src/generic/misc.h
Normal file
21
src/generic/misc.h
Normal file
@@ -0,0 +1,21 @@
|
||||
#ifndef __GENERIC_MISC_H
|
||||
#define __GENERIC_MISC_H
|
||||
|
||||
#include <stdarg.h> // va_list
|
||||
#include <stdint.h> // uint8_t
|
||||
|
||||
struct command_encoder;
|
||||
void console_sendf(const struct command_encoder *ce, va_list args);
|
||||
void *console_receive_buffer(void);
|
||||
|
||||
uint32_t timer_from_us(uint32_t us);
|
||||
uint8_t timer_is_before(uint32_t time1, uint32_t time2);
|
||||
uint32_t timer_read_time(void);
|
||||
void timer_kick(void);
|
||||
|
||||
void *dynmem_start(void);
|
||||
void *dynmem_end(void);
|
||||
|
||||
uint16_t crc16_ccitt(uint8_t *buf, uint_fast8_t len);
|
||||
|
||||
#endif // misc.h
|
||||
14
src/generic/pgm.h
Normal file
14
src/generic/pgm.h
Normal file
@@ -0,0 +1,14 @@
|
||||
#ifndef __GENERIC_PGM_H
|
||||
#define __GENERIC_PGM_H
|
||||
// This header provides wrappers for the AVR specific "PROGMEM"
|
||||
// declarations on non-avr platforms.
|
||||
|
||||
#define NEED_PROGMEM 0
|
||||
#define PROGMEM
|
||||
#define PSTR(S) S
|
||||
#define READP(VAR) VAR
|
||||
#define vsnprintf_P(D, S, F, A) vsnprintf(D, S, F, A)
|
||||
#define strcasecmp_P(S1, S2) strcasecmp(S1, S2)
|
||||
#define memcpy_P(DST, SRC, SIZE) memcpy((DST), (SRC), (SIZE))
|
||||
|
||||
#endif // pgm.h
|
||||
122
src/generic/serial_irq.c
Normal file
122
src/generic/serial_irq.c
Normal file
@@ -0,0 +1,122 @@
|
||||
// Generic interrupt based serial uart helper code
|
||||
//
|
||||
// Copyright (C) 2016-2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memmove
|
||||
#include "autoconf.h" // CONFIG_SERIAL_BAUD
|
||||
#include "board/io.h" // readb
|
||||
#include "board/irq.h" // irq_save
|
||||
#include "board/misc.h" // console_sendf
|
||||
#include "board/pgm.h" // READP
|
||||
#include "command.h" // DECL_CONSTANT
|
||||
#include "sched.h" // sched_wake_tasks
|
||||
#include "serial_irq.h" // serial_enable_tx_irq
|
||||
|
||||
#define RX_BUFFER_SIZE 192
|
||||
|
||||
static uint8_t receive_buf[RX_BUFFER_SIZE], receive_pos;
|
||||
static uint8_t transmit_buf[96], transmit_pos, transmit_max;
|
||||
|
||||
DECL_CONSTANT("SERIAL_BAUD", CONFIG_SERIAL_BAUD);
|
||||
DECL_CONSTANT("RECEIVE_WINDOW", RX_BUFFER_SIZE);
|
||||
|
||||
// Rx interrupt - store read data
|
||||
void
|
||||
serial_rx_byte(uint_fast8_t data)
|
||||
{
|
||||
if (data == MESSAGE_SYNC)
|
||||
sched_wake_tasks();
|
||||
if (receive_pos >= sizeof(receive_buf))
|
||||
// Serial overflow - ignore it as crc error will force retransmit
|
||||
return;
|
||||
receive_buf[receive_pos++] = data;
|
||||
}
|
||||
|
||||
// Tx interrupt - get next byte to transmit
|
||||
int
|
||||
serial_get_tx_byte(uint8_t *pdata)
|
||||
{
|
||||
if (transmit_pos >= transmit_max)
|
||||
return -1;
|
||||
*pdata = transmit_buf[transmit_pos++];
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Remove from the receive buffer the given number of bytes
|
||||
static void
|
||||
console_pop_input(uint_fast8_t len)
|
||||
{
|
||||
uint_fast8_t copied = 0;
|
||||
for (;;) {
|
||||
uint_fast8_t rpos = readb(&receive_pos);
|
||||
uint_fast8_t needcopy = rpos - len;
|
||||
if (needcopy) {
|
||||
memmove(&receive_buf[copied], &receive_buf[copied + len]
|
||||
, needcopy - copied);
|
||||
copied = needcopy;
|
||||
sched_wake_tasks();
|
||||
}
|
||||
irqstatus_t flag = irq_save();
|
||||
if (rpos != readb(&receive_pos)) {
|
||||
// Raced with irq handler - retry
|
||||
irq_restore(flag);
|
||||
continue;
|
||||
}
|
||||
receive_pos = needcopy;
|
||||
irq_restore(flag);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Process any incoming commands
|
||||
void
|
||||
console_task(void)
|
||||
{
|
||||
uint_fast8_t rpos = readb(&receive_pos), pop_count;
|
||||
int_fast8_t ret = command_find_block(receive_buf, rpos, &pop_count);
|
||||
if (ret > 0)
|
||||
command_dispatch(receive_buf, pop_count);
|
||||
if (ret) {
|
||||
console_pop_input(pop_count);
|
||||
if (ret > 0)
|
||||
command_send_ack();
|
||||
}
|
||||
}
|
||||
DECL_TASK(console_task);
|
||||
|
||||
// Encode and transmit a "response" message
|
||||
void
|
||||
console_sendf(const struct command_encoder *ce, va_list args)
|
||||
{
|
||||
// Verify space for message
|
||||
uint_fast8_t tpos = readb(&transmit_pos), tmax = readb(&transmit_max);
|
||||
if (tpos >= tmax) {
|
||||
tpos = tmax = 0;
|
||||
writeb(&transmit_max, 0);
|
||||
writeb(&transmit_pos, 0);
|
||||
}
|
||||
uint_fast8_t max_size = READP(ce->max_size);
|
||||
if (tmax + max_size > sizeof(transmit_buf)) {
|
||||
if (tmax + max_size - tpos > sizeof(transmit_buf))
|
||||
// Not enough space for message
|
||||
return;
|
||||
// Disable TX irq and move buffer
|
||||
writeb(&transmit_max, 0);
|
||||
tpos = readb(&transmit_pos);
|
||||
tmax -= tpos;
|
||||
memmove(&transmit_buf[0], &transmit_buf[tpos], tmax);
|
||||
writeb(&transmit_pos, 0);
|
||||
writeb(&transmit_max, tmax);
|
||||
serial_enable_tx_irq();
|
||||
}
|
||||
|
||||
// Generate message
|
||||
uint8_t *buf = &transmit_buf[tmax];
|
||||
uint_fast8_t msglen = command_encode_and_frame(buf, ce, args);
|
||||
|
||||
// Start message transmit
|
||||
writeb(&transmit_max, tmax + msglen);
|
||||
serial_enable_tx_irq();
|
||||
}
|
||||
13
src/generic/serial_irq.h
Normal file
13
src/generic/serial_irq.h
Normal file
@@ -0,0 +1,13 @@
|
||||
#ifndef __GENERIC_SERIAL_IRQ_H
|
||||
#define __GENERIC_SERIAL_IRQ_H
|
||||
|
||||
#include <stdint.h> // uint32_t
|
||||
|
||||
// callback provided by board specific code
|
||||
void serial_enable_tx_irq(void);
|
||||
|
||||
// serial_irq.c
|
||||
void serial_rx_byte(uint_fast8_t data);
|
||||
int serial_get_tx_byte(uint8_t *pdata);
|
||||
|
||||
#endif // serial_irq.h
|
||||
83
src/generic/timer_irq.c
Normal file
83
src/generic/timer_irq.c
Normal file
@@ -0,0 +1,83 @@
|
||||
// Generic interrupt based timer helper functions
|
||||
//
|
||||
// Copyright (C) 2017 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "autoconf.h" // CONFIG_CLOCK_FREQ
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "board/misc.h" // timer_from_us
|
||||
#include "board/timer_irq.h" // timer_dispatch_many
|
||||
#include "command.h" // shutdown
|
||||
#include "sched.h" // sched_timer_dispatch
|
||||
|
||||
DECL_CONSTANT("CLOCK_FREQ", CONFIG_CLOCK_FREQ);
|
||||
|
||||
// Return the number of clock ticks for a given number of microseconds
|
||||
uint32_t
|
||||
timer_from_us(uint32_t us)
|
||||
{
|
||||
return us * (CONFIG_CLOCK_FREQ / 1000000);
|
||||
}
|
||||
|
||||
// Return true if time1 is before time2. Always use this function to
|
||||
// compare times as regular C comparisons can fail if the counter
|
||||
// rolls over.
|
||||
uint8_t
|
||||
timer_is_before(uint32_t time1, uint32_t time2)
|
||||
{
|
||||
return (int32_t)(time1 - time2) < 0;
|
||||
}
|
||||
|
||||
static uint32_t timer_repeat_until;
|
||||
#define TIMER_IDLE_REPEAT_TICKS timer_from_us(500)
|
||||
#define TIMER_REPEAT_TICKS timer_from_us(100)
|
||||
|
||||
#define TIMER_MIN_TRY_TICKS timer_from_us(2)
|
||||
#define TIMER_DEFER_REPEAT_TICKS timer_from_us(5)
|
||||
|
||||
// Invoke timers - called from board irq code.
|
||||
uint32_t
|
||||
timer_dispatch_many(void)
|
||||
{
|
||||
uint32_t tru = timer_repeat_until;
|
||||
for (;;) {
|
||||
// Run the next software timer
|
||||
uint32_t next = sched_timer_dispatch();
|
||||
|
||||
uint32_t now = timer_read_time();
|
||||
int32_t diff = next - now;
|
||||
if (diff > (int32_t)TIMER_MIN_TRY_TICKS)
|
||||
// Schedule next timer normally.
|
||||
return next;
|
||||
|
||||
if (unlikely(timer_is_before(tru, now))) {
|
||||
// Check if there are too many repeat timers
|
||||
if (diff < (int32_t)(-timer_from_us(1000)))
|
||||
try_shutdown("Rescheduled timer in the past");
|
||||
if (sched_tasks_busy()) {
|
||||
timer_repeat_until = now + TIMER_REPEAT_TICKS;
|
||||
return now + TIMER_DEFER_REPEAT_TICKS;
|
||||
}
|
||||
timer_repeat_until = tru = now + TIMER_IDLE_REPEAT_TICKS;
|
||||
}
|
||||
|
||||
// Next timer in the past or near future - wait for it to be ready
|
||||
irq_enable();
|
||||
while (unlikely(diff > 0))
|
||||
diff = next - timer_read_time();
|
||||
irq_disable();
|
||||
}
|
||||
}
|
||||
|
||||
// Make sure timer_repeat_until doesn't wrap 32bit comparisons
|
||||
void
|
||||
timer_task(void)
|
||||
{
|
||||
uint32_t now = timer_read_time();
|
||||
irq_disable();
|
||||
if (timer_is_before(timer_repeat_until, now))
|
||||
timer_repeat_until = now;
|
||||
irq_enable();
|
||||
}
|
||||
DECL_TASK(timer_task);
|
||||
6
src/generic/timer_irq.h
Normal file
6
src/generic/timer_irq.h
Normal file
@@ -0,0 +1,6 @@
|
||||
#ifndef __GENERIC_TIMER_IRQ_H
|
||||
#define __GENERIC_TIMER_IRQ_H
|
||||
|
||||
uint32_t timer_dispatch_many(void);
|
||||
|
||||
#endif // timer_irq.h
|
||||
675
src/generic/usb_canbus.c
Normal file
675
src/generic/usb_canbus.c
Normal file
@@ -0,0 +1,675 @@
|
||||
// Support for Linux "gs_usb" CANbus adapter emulation
|
||||
//
|
||||
// Copyright (C) 2018-2022 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memmove
|
||||
#include "autoconf.h" // CONFIG_USB_VENDOR_ID
|
||||
#include "board/canbus.h" // canbus_notify_tx
|
||||
#include "board/canserial.h" // canserial_notify_tx
|
||||
#include "board/io.h" // readl
|
||||
#include "board/misc.h" // console_sendf
|
||||
#include "board/pgm.h" // PROGMEM
|
||||
#include "board/usb_cdc_ep.h" // USB_CDC_EP_BULK_IN
|
||||
#include "byteorder.h" // cpu_to_le16
|
||||
#include "generic/usbstd.h" // struct usb_device_descriptor
|
||||
#include "sched.h" // sched_wake_task
|
||||
#include "usb_cdc.h" // usb_notify_ep0
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Linux "gs_usb" definitions
|
||||
****************************************************************/
|
||||
|
||||
#define USB_GSUSB_1_VENDOR_ID 0x1d50
|
||||
#define USB_GSUSB_1_PRODUCT_ID 0x606f
|
||||
|
||||
enum gs_usb_breq {
|
||||
GS_USB_BREQ_HOST_FORMAT = 0,
|
||||
GS_USB_BREQ_BITTIMING,
|
||||
GS_USB_BREQ_MODE,
|
||||
GS_USB_BREQ_BERR,
|
||||
GS_USB_BREQ_BT_CONST,
|
||||
GS_USB_BREQ_DEVICE_CONFIG,
|
||||
GS_USB_BREQ_TIMESTAMP,
|
||||
GS_USB_BREQ_IDENTIFY,
|
||||
GS_USB_BREQ_GET_USER_ID,
|
||||
GS_USB_BREQ_SET_USER_ID,
|
||||
GS_USB_BREQ_DATA_BITTIMING,
|
||||
GS_USB_BREQ_BT_CONST_EXT,
|
||||
};
|
||||
|
||||
struct gs_host_config {
|
||||
uint32_t byte_order;
|
||||
} __packed;
|
||||
|
||||
struct gs_device_config {
|
||||
uint8_t reserved1;
|
||||
uint8_t reserved2;
|
||||
uint8_t reserved3;
|
||||
uint8_t icount;
|
||||
uint32_t sw_version;
|
||||
uint32_t hw_version;
|
||||
} __packed;
|
||||
|
||||
struct gs_device_bt_const {
|
||||
uint32_t feature;
|
||||
uint32_t fclk_can;
|
||||
uint32_t tseg1_min;
|
||||
uint32_t tseg1_max;
|
||||
uint32_t tseg2_min;
|
||||
uint32_t tseg2_max;
|
||||
uint32_t sjw_max;
|
||||
uint32_t brp_min;
|
||||
uint32_t brp_max;
|
||||
uint32_t brp_inc;
|
||||
} __packed;
|
||||
|
||||
struct gs_device_bittiming {
|
||||
uint32_t prop_seg;
|
||||
uint32_t phase_seg1;
|
||||
uint32_t phase_seg2;
|
||||
uint32_t sjw;
|
||||
uint32_t brp;
|
||||
} __packed;
|
||||
|
||||
struct gs_device_mode {
|
||||
uint32_t mode;
|
||||
uint32_t flags;
|
||||
} __packed;
|
||||
|
||||
struct gs_host_frame {
|
||||
uint32_t echo_id;
|
||||
uint32_t can_id;
|
||||
|
||||
uint8_t can_dlc;
|
||||
uint8_t channel;
|
||||
uint8_t flags;
|
||||
uint8_t reserved;
|
||||
|
||||
union {
|
||||
uint8_t data[8];
|
||||
uint32_t data32[2];
|
||||
};
|
||||
} __packed;
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Message sending
|
||||
****************************************************************/
|
||||
|
||||
// Global storage
|
||||
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;
|
||||
uint32_t assigned_id;
|
||||
|
||||
// Data from physical canbus interface
|
||||
uint32_t pull_pos, push_pos;
|
||||
struct canbus_msg queue[8];
|
||||
} UsbCan;
|
||||
|
||||
enum {
|
||||
HS_TX_ECHO = 1,
|
||||
HS_TX_HW = 2,
|
||||
HS_TX_LOCAL = 4,
|
||||
};
|
||||
|
||||
void
|
||||
canbus_notify_tx(void)
|
||||
{
|
||||
sched_wake_task(&UsbCan.wake);
|
||||
}
|
||||
|
||||
// Handle incoming data from hw canbus interface (called from IRQ handler)
|
||||
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))
|
||||
// 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;
|
||||
usb_notify_bulk_out();
|
||||
}
|
||||
|
||||
// Send a message to the Linux host
|
||||
static int
|
||||
send_frame(struct canbus_msg *msg)
|
||||
{
|
||||
struct gs_host_frame gs = {};
|
||||
gs.echo_id = 0xffffffff;
|
||||
gs.can_id = msg->id;
|
||||
gs.can_dlc = msg->dlc;
|
||||
gs.data32[0] = msg->data32[0];
|
||||
gs.data32[1] = msg->data32[1];
|
||||
return usb_send_bulk_in(&gs, sizeof(gs));
|
||||
}
|
||||
|
||||
// Send any pending hw frames to host
|
||||
static int
|
||||
drain_hw_queue(void)
|
||||
{
|
||||
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;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
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;
|
||||
|
||||
// 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_HW) {
|
||||
ret = canbus_send(&msg);
|
||||
if (ret < 0)
|
||||
return;
|
||||
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 (ret < 0)
|
||||
return;
|
||||
UsbCan.host_status = 0;
|
||||
continue;
|
||||
}
|
||||
|
||||
// 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;
|
||||
}
|
||||
}
|
||||
DECL_TASK(usbcan_task);
|
||||
|
||||
int
|
||||
canserial_send(struct canbus_msg *msg)
|
||||
{
|
||||
int ret = drain_hw_queue();
|
||||
if (ret < 0)
|
||||
goto retry_later;
|
||||
ret = send_frame(msg);
|
||||
if (ret < 0)
|
||||
goto retry_later;
|
||||
UsbCan.notify_local = 0;
|
||||
return msg->dlc;
|
||||
retry_later:
|
||||
UsbCan.notify_local = 1;
|
||||
return -1;
|
||||
}
|
||||
|
||||
void
|
||||
canserial_set_filter(uint32_t id)
|
||||
{
|
||||
UsbCan.assigned_id = id;
|
||||
}
|
||||
|
||||
void
|
||||
usb_notify_bulk_out(void)
|
||||
{
|
||||
canbus_notify_tx();
|
||||
}
|
||||
|
||||
void
|
||||
usb_notify_bulk_in(void)
|
||||
{
|
||||
canbus_notify_tx();
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* USB descriptors
|
||||
****************************************************************/
|
||||
|
||||
#define CONCAT1(a, b) a ## b
|
||||
#define CONCAT(a, b) CONCAT1(a, b)
|
||||
#define USB_STR_MANUFACTURER u"Klipper"
|
||||
#define USB_STR_PRODUCT CONCAT(u,CONFIG_MCU)
|
||||
#define USB_STR_SERIAL CONCAT(u,CONFIG_USB_SERIAL_NUMBER)
|
||||
|
||||
// String descriptors
|
||||
enum {
|
||||
USB_STR_ID_MANUFACTURER = 1, USB_STR_ID_PRODUCT, USB_STR_ID_SERIAL,
|
||||
};
|
||||
|
||||
#define SIZE_cdc_string_langids (sizeof(cdc_string_langids) + 2)
|
||||
|
||||
static const struct usb_string_descriptor cdc_string_langids PROGMEM = {
|
||||
.bLength = SIZE_cdc_string_langids,
|
||||
.bDescriptorType = USB_DT_STRING,
|
||||
.data = { cpu_to_le16(USB_LANGID_ENGLISH_US) },
|
||||
};
|
||||
|
||||
#define SIZE_cdc_string_manufacturer \
|
||||
(sizeof(cdc_string_manufacturer) + sizeof(USB_STR_MANUFACTURER) - 2)
|
||||
|
||||
static const struct usb_string_descriptor cdc_string_manufacturer PROGMEM = {
|
||||
.bLength = SIZE_cdc_string_manufacturer,
|
||||
.bDescriptorType = USB_DT_STRING,
|
||||
.data = USB_STR_MANUFACTURER,
|
||||
};
|
||||
|
||||
#define SIZE_cdc_string_product \
|
||||
(sizeof(cdc_string_product) + sizeof(USB_STR_PRODUCT) - 2)
|
||||
|
||||
static const struct usb_string_descriptor cdc_string_product PROGMEM = {
|
||||
.bLength = SIZE_cdc_string_product,
|
||||
.bDescriptorType = USB_DT_STRING,
|
||||
.data = USB_STR_PRODUCT,
|
||||
};
|
||||
|
||||
#define SIZE_cdc_string_serial \
|
||||
(sizeof(cdc_string_serial) + sizeof(USB_STR_SERIAL) - 2)
|
||||
|
||||
static const struct usb_string_descriptor cdc_string_serial PROGMEM = {
|
||||
.bLength = SIZE_cdc_string_serial,
|
||||
.bDescriptorType = USB_DT_STRING,
|
||||
.data = USB_STR_SERIAL,
|
||||
};
|
||||
|
||||
// Device descriptor
|
||||
static const struct usb_device_descriptor gs_device_descriptor PROGMEM = {
|
||||
.bLength = sizeof(gs_device_descriptor),
|
||||
.bDescriptorType = USB_DT_DEVICE,
|
||||
.bcdUSB = cpu_to_le16(0x0200),
|
||||
.bMaxPacketSize0 = USB_CDC_EP0_SIZE,
|
||||
.idVendor = cpu_to_le16(USB_GSUSB_1_VENDOR_ID),
|
||||
.idProduct = cpu_to_le16(USB_GSUSB_1_PRODUCT_ID),
|
||||
.iManufacturer = USB_STR_ID_MANUFACTURER,
|
||||
.iProduct = USB_STR_ID_PRODUCT,
|
||||
.iSerialNumber = USB_STR_ID_SERIAL,
|
||||
.bNumConfigurations = 1,
|
||||
};
|
||||
|
||||
// Config descriptor
|
||||
static const struct config_s {
|
||||
struct usb_config_descriptor config;
|
||||
struct usb_interface_descriptor iface0;
|
||||
struct usb_endpoint_descriptor ep1;
|
||||
struct usb_endpoint_descriptor ep2;
|
||||
} PACKED gs_config_descriptor PROGMEM = {
|
||||
.config = {
|
||||
.bLength = sizeof(gs_config_descriptor.config),
|
||||
.bDescriptorType = USB_DT_CONFIG,
|
||||
.wTotalLength = cpu_to_le16(sizeof(gs_config_descriptor)),
|
||||
.bNumInterfaces = 1,
|
||||
.bConfigurationValue = 1,
|
||||
.bmAttributes = 0xC0,
|
||||
.bMaxPower = 50,
|
||||
},
|
||||
.iface0 = {
|
||||
.bLength = sizeof(gs_config_descriptor.iface0),
|
||||
.bDescriptorType = USB_DT_INTERFACE,
|
||||
.bInterfaceNumber = 0,
|
||||
.bNumEndpoints = 2,
|
||||
.bInterfaceClass = 255,
|
||||
.bInterfaceSubClass = 255,
|
||||
.bInterfaceProtocol = 255,
|
||||
},
|
||||
.ep1 = {
|
||||
.bLength = sizeof(gs_config_descriptor.ep1),
|
||||
.bDescriptorType = USB_DT_ENDPOINT,
|
||||
.bEndpointAddress = USB_CDC_EP_BULK_OUT,
|
||||
.bmAttributes = USB_ENDPOINT_XFER_BULK,
|
||||
.wMaxPacketSize = cpu_to_le16(USB_CDC_EP_BULK_OUT_SIZE),
|
||||
},
|
||||
.ep2 = {
|
||||
.bLength = sizeof(gs_config_descriptor.ep2),
|
||||
.bDescriptorType = USB_DT_ENDPOINT,
|
||||
.bEndpointAddress = USB_CDC_EP_BULK_IN | USB_DIR_IN,
|
||||
.bmAttributes = USB_ENDPOINT_XFER_BULK,
|
||||
.wMaxPacketSize = cpu_to_le16(USB_CDC_EP_BULK_IN_SIZE),
|
||||
},
|
||||
};
|
||||
|
||||
// List of available descriptors
|
||||
static const struct descriptor_s {
|
||||
uint_fast16_t wValue;
|
||||
uint_fast16_t wIndex;
|
||||
const void *desc;
|
||||
uint_fast8_t size;
|
||||
} usb_descriptors[] PROGMEM = {
|
||||
{ USB_DT_DEVICE<<8, 0x0000,
|
||||
&gs_device_descriptor, sizeof(gs_device_descriptor) },
|
||||
{ USB_DT_CONFIG<<8, 0x0000,
|
||||
&gs_config_descriptor, sizeof(gs_config_descriptor) },
|
||||
{ USB_DT_STRING<<8, 0x0000,
|
||||
&cdc_string_langids, SIZE_cdc_string_langids },
|
||||
{ (USB_DT_STRING<<8) | USB_STR_ID_MANUFACTURER, USB_LANGID_ENGLISH_US,
|
||||
&cdc_string_manufacturer, SIZE_cdc_string_manufacturer },
|
||||
{ (USB_DT_STRING<<8) | USB_STR_ID_PRODUCT, USB_LANGID_ENGLISH_US,
|
||||
&cdc_string_product, SIZE_cdc_string_product },
|
||||
#if !CONFIG_USB_SERIAL_NUMBER_CHIPID
|
||||
{ (USB_DT_STRING<<8) | USB_STR_ID_SERIAL, USB_LANGID_ENGLISH_US,
|
||||
&cdc_string_serial, SIZE_cdc_string_serial },
|
||||
#endif
|
||||
};
|
||||
|
||||
// Fill in a USB serial string descriptor from a chip id
|
||||
void
|
||||
usb_fill_serial(struct usb_string_descriptor *desc, int strlen, void *id)
|
||||
{
|
||||
desc->bLength = sizeof(*desc) + strlen * sizeof(desc->data[0]);
|
||||
desc->bDescriptorType = USB_DT_STRING;
|
||||
|
||||
uint8_t *src = id;
|
||||
int i;
|
||||
for (i = 0; i < strlen; i++) {
|
||||
uint8_t c = i & 1 ? src[i/2] & 0x0f : src[i/2] >> 4;
|
||||
desc->data[i] = c < 10 ? c + '0' : c - 10 + 'A';
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* USB endpoint 0 control message handling
|
||||
****************************************************************/
|
||||
|
||||
// State tracking
|
||||
enum {
|
||||
UX_READ = 1<<0, UX_SEND = 1<<1, UX_SEND_PROGMEM = 1<<2, UX_SEND_ZLP = 1<<3
|
||||
};
|
||||
|
||||
static void *usb_xfer_data;
|
||||
static uint8_t usb_xfer_size, usb_xfer_flags;
|
||||
|
||||
// Set the USB "stall" condition
|
||||
static void
|
||||
usb_do_stall(void)
|
||||
{
|
||||
usb_stall_ep0();
|
||||
usb_xfer_flags = 0;
|
||||
}
|
||||
|
||||
// Transfer data on the usb endpoint 0
|
||||
static void
|
||||
usb_do_xfer(void *data, uint_fast8_t size, uint_fast8_t flags)
|
||||
{
|
||||
for (;;) {
|
||||
uint_fast8_t xs = size;
|
||||
if (xs > USB_CDC_EP0_SIZE)
|
||||
xs = USB_CDC_EP0_SIZE;
|
||||
int_fast8_t ret;
|
||||
if (flags & UX_READ)
|
||||
ret = usb_read_ep0(data, xs);
|
||||
else if (NEED_PROGMEM && flags & UX_SEND_PROGMEM)
|
||||
ret = usb_send_ep0_progmem(data, xs);
|
||||
else
|
||||
ret = usb_send_ep0(data, xs);
|
||||
if (ret == xs) {
|
||||
// Success
|
||||
data += xs;
|
||||
size -= xs;
|
||||
if (!size) {
|
||||
// Entire transfer completed successfully
|
||||
if (flags & UX_READ) {
|
||||
// Send status packet at end of read
|
||||
flags = UX_SEND;
|
||||
continue;
|
||||
}
|
||||
if (xs == USB_CDC_EP0_SIZE && flags & UX_SEND_ZLP)
|
||||
// Must send zero-length-packet
|
||||
continue;
|
||||
usb_xfer_flags = 0;
|
||||
usb_notify_ep0();
|
||||
return;
|
||||
}
|
||||
continue;
|
||||
}
|
||||
if (ret == -1) {
|
||||
// Interface busy - retry later
|
||||
usb_xfer_data = data;
|
||||
usb_xfer_size = size;
|
||||
usb_xfer_flags = flags;
|
||||
return;
|
||||
}
|
||||
// Error
|
||||
usb_do_stall();
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
usb_req_get_descriptor(struct usb_ctrlrequest *req)
|
||||
{
|
||||
if (req->bRequestType != USB_DIR_IN)
|
||||
goto fail;
|
||||
void *desc = NULL;
|
||||
uint_fast8_t flags, size, i;
|
||||
for (i=0; i<ARRAY_SIZE(usb_descriptors); i++) {
|
||||
const struct descriptor_s *d = &usb_descriptors[i];
|
||||
if (READP(d->wValue) == req->wValue
|
||||
&& READP(d->wIndex) == req->wIndex) {
|
||||
flags = NEED_PROGMEM ? UX_SEND_PROGMEM : UX_SEND;
|
||||
size = READP(d->size);
|
||||
desc = (void*)READP(d->desc);
|
||||
}
|
||||
}
|
||||
if (CONFIG_USB_SERIAL_NUMBER_CHIPID
|
||||
&& req->wValue == ((USB_DT_STRING<<8) | USB_STR_ID_SERIAL)
|
||||
&& req->wIndex == USB_LANGID_ENGLISH_US) {
|
||||
struct usb_string_descriptor *usbserial_serialid;
|
||||
usbserial_serialid = usbserial_get_serialid();
|
||||
flags = UX_SEND;
|
||||
size = usbserial_serialid->bLength;
|
||||
desc = (void*)usbserial_serialid;
|
||||
}
|
||||
if (desc) {
|
||||
if (size > req->wLength)
|
||||
size = req->wLength;
|
||||
else if (size < req->wLength)
|
||||
flags |= UX_SEND_ZLP;
|
||||
usb_do_xfer(desc, size, flags);
|
||||
return;
|
||||
}
|
||||
fail:
|
||||
usb_do_stall();
|
||||
}
|
||||
|
||||
static void
|
||||
usb_req_set_address(struct usb_ctrlrequest *req)
|
||||
{
|
||||
if (req->bRequestType || req->wIndex || req->wLength) {
|
||||
usb_do_stall();
|
||||
return;
|
||||
}
|
||||
usb_set_address(req->wValue);
|
||||
}
|
||||
|
||||
static void
|
||||
usb_req_set_configuration(struct usb_ctrlrequest *req)
|
||||
{
|
||||
if (req->bRequestType || req->wValue != 1 || req->wIndex || req->wLength) {
|
||||
usb_do_stall();
|
||||
return;
|
||||
}
|
||||
usb_set_configure();
|
||||
usb_notify_bulk_in();
|
||||
usb_notify_bulk_out();
|
||||
usb_do_xfer(NULL, 0, UX_SEND);
|
||||
}
|
||||
|
||||
struct gs_host_config host_config;
|
||||
|
||||
static void
|
||||
gs_breq_host_format(struct usb_ctrlrequest *req)
|
||||
{
|
||||
// Like candlightfw, little-endian is always used. Read and ignore value.
|
||||
usb_do_xfer(&host_config, sizeof(host_config), UX_READ);
|
||||
}
|
||||
|
||||
static const struct gs_device_config device_config PROGMEM = {
|
||||
.sw_version = 2,
|
||||
.hw_version = 1,
|
||||
};
|
||||
|
||||
static void
|
||||
gs_breq_device_config(struct usb_ctrlrequest *req)
|
||||
{
|
||||
usb_do_xfer((void*)&device_config, sizeof(device_config), UX_SEND);
|
||||
}
|
||||
|
||||
static const struct gs_device_bt_const bt_const PROGMEM = {
|
||||
// These are just dummy values for now
|
||||
.feature = 0,
|
||||
.fclk_can = 48000000,
|
||||
.tseg1_min = 1,
|
||||
.tseg1_max = 16,
|
||||
.tseg2_min = 1,
|
||||
.tseg2_max = 8,
|
||||
.sjw_max = 4,
|
||||
.brp_min = 1,
|
||||
.brp_max = 1024,
|
||||
.brp_inc = 1,
|
||||
};
|
||||
|
||||
static void
|
||||
gs_breq_bt_const(struct usb_ctrlrequest *req)
|
||||
{
|
||||
usb_do_xfer((void*)&bt_const, sizeof(bt_const), UX_SEND);
|
||||
}
|
||||
|
||||
struct gs_device_bittiming device_bittiming;
|
||||
|
||||
static void
|
||||
gs_breq_bittiming(struct usb_ctrlrequest *req)
|
||||
{
|
||||
// Bit timing is ignored for now
|
||||
usb_do_xfer(&device_bittiming, sizeof(device_bittiming), UX_READ);
|
||||
}
|
||||
|
||||
struct gs_device_mode device_mode;
|
||||
|
||||
static void
|
||||
gs_breq_mode(struct usb_ctrlrequest *req)
|
||||
{
|
||||
// Mode is ignored for now
|
||||
usb_do_xfer(&device_mode, sizeof(device_mode), UX_READ);
|
||||
}
|
||||
|
||||
static void
|
||||
usb_state_ready(void)
|
||||
{
|
||||
struct usb_ctrlrequest req;
|
||||
int_fast8_t ret = usb_read_ep0_setup(&req, sizeof(req));
|
||||
if (ret != sizeof(req))
|
||||
return;
|
||||
uint32_t req_type = req.bRequestType & USB_TYPE_MASK;
|
||||
if (req_type == USB_TYPE_STANDARD) {
|
||||
switch (req.bRequest) {
|
||||
case USB_REQ_GET_DESCRIPTOR: usb_req_get_descriptor(&req); break;
|
||||
case USB_REQ_SET_ADDRESS: usb_req_set_address(&req); break;
|
||||
case USB_REQ_SET_CONFIGURATION: usb_req_set_configuration(&req); break;
|
||||
default: usb_do_stall(); break;
|
||||
}
|
||||
} else if (req_type == USB_TYPE_VENDOR) {
|
||||
switch (req.bRequest) {
|
||||
case GS_USB_BREQ_HOST_FORMAT: gs_breq_host_format(&req); break;
|
||||
case GS_USB_BREQ_DEVICE_CONFIG: gs_breq_device_config(&req); break;
|
||||
case GS_USB_BREQ_BT_CONST: gs_breq_bt_const(&req); break;
|
||||
case GS_USB_BREQ_BITTIMING: gs_breq_bittiming(&req); break;
|
||||
case GS_USB_BREQ_MODE: gs_breq_mode(&req); break;
|
||||
default: usb_do_stall(); break;
|
||||
}
|
||||
} else {
|
||||
usb_do_stall();
|
||||
}
|
||||
}
|
||||
|
||||
// State tracking dispatch
|
||||
static struct task_wake usb_ep0_wake;
|
||||
|
||||
void
|
||||
usb_notify_ep0(void)
|
||||
{
|
||||
sched_wake_task(&usb_ep0_wake);
|
||||
}
|
||||
|
||||
void
|
||||
usb_ep0_task(void)
|
||||
{
|
||||
if (!sched_check_wake(&usb_ep0_wake))
|
||||
return;
|
||||
if (usb_xfer_flags)
|
||||
usb_do_xfer(usb_xfer_data, usb_xfer_size, usb_xfer_flags);
|
||||
else
|
||||
usb_state_ready();
|
||||
}
|
||||
DECL_TASK(usb_ep0_task);
|
||||
|
||||
void
|
||||
usb_shutdown(void)
|
||||
{
|
||||
usb_notify_bulk_in();
|
||||
usb_notify_bulk_out();
|
||||
usb_notify_ep0();
|
||||
}
|
||||
DECL_SHUTDOWN(usb_shutdown);
|
||||
535
src/generic/usb_cdc.c
Normal file
535
src/generic/usb_cdc.c
Normal file
@@ -0,0 +1,535 @@
|
||||
// Support for standard serial port over USB emulation
|
||||
//
|
||||
// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include <string.h> // memmove
|
||||
#include "autoconf.h" // CONFIG_USB_VENDOR_ID
|
||||
#include "board/misc.h" // console_sendf
|
||||
#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" // output
|
||||
#include "generic/usbstd.h" // struct usb_device_descriptor
|
||||
#include "generic/usbstd_cdc.h" // struct usb_cdc_header_descriptor
|
||||
#include "sched.h" // sched_wake_task
|
||||
#include "usb_cdc.h" // usb_notify_ep0
|
||||
|
||||
// To debug a USB connection over UART, uncomment the two macros
|
||||
// below, alter the board KConfig to "select USBSERIAL" on a serial
|
||||
// UART build (so both USB and UART are enabled in a single build),
|
||||
// compile the code using serial UART, add output() calls to the USB
|
||||
// code as needed, deploy the new binary, and then connect via
|
||||
// console.py using UART to see those output() messages.
|
||||
//#define console_sendf(ce,va) console_sendf_usb(ce,va)
|
||||
//#define command_find_and_dispatch(rb, rp, pc) ({*(pc) = rp; 1;})
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Message block sending
|
||||
****************************************************************/
|
||||
|
||||
static struct task_wake usb_bulk_in_wake;
|
||||
static uint8_t transmit_buf[192], transmit_pos;
|
||||
|
||||
void
|
||||
usb_notify_bulk_in(void)
|
||||
{
|
||||
sched_wake_task(&usb_bulk_in_wake);
|
||||
}
|
||||
|
||||
void
|
||||
usb_bulk_in_task(void)
|
||||
{
|
||||
if (!sched_check_wake(&usb_bulk_in_wake))
|
||||
return;
|
||||
uint_fast8_t tpos = transmit_pos;
|
||||
if (!tpos)
|
||||
return;
|
||||
uint_fast8_t max_tpos = (tpos > USB_CDC_EP_BULK_IN_SIZE
|
||||
? USB_CDC_EP_BULK_IN_SIZE : tpos);
|
||||
int_fast8_t ret = usb_send_bulk_in(transmit_buf, max_tpos);
|
||||
if (ret <= 0)
|
||||
return;
|
||||
uint_fast8_t needcopy = tpos - ret;
|
||||
if (needcopy) {
|
||||
memmove(transmit_buf, &transmit_buf[ret], needcopy);
|
||||
usb_notify_bulk_in();
|
||||
}
|
||||
transmit_pos = needcopy;
|
||||
}
|
||||
DECL_TASK(usb_bulk_in_task);
|
||||
|
||||
// Encode and transmit a "response" message
|
||||
void
|
||||
console_sendf(const struct command_encoder *ce, va_list args)
|
||||
{
|
||||
// Verify space for message
|
||||
uint_fast8_t tpos = transmit_pos, max_size = READP(ce->max_size);
|
||||
if (tpos + max_size > sizeof(transmit_buf))
|
||||
// Not enough space for message
|
||||
return;
|
||||
|
||||
// Generate message
|
||||
uint8_t *buf = &transmit_buf[tpos];
|
||||
uint_fast8_t msglen = command_encode_and_frame(buf, ce, args);
|
||||
|
||||
// Start message transmit
|
||||
transmit_pos = tpos + msglen;
|
||||
usb_notify_bulk_in();
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* Message block reading
|
||||
****************************************************************/
|
||||
|
||||
static struct task_wake usb_bulk_out_wake;
|
||||
static uint8_t receive_buf[128], receive_pos;
|
||||
|
||||
void
|
||||
usb_notify_bulk_out(void)
|
||||
{
|
||||
sched_wake_task(&usb_bulk_out_wake);
|
||||
}
|
||||
|
||||
void
|
||||
usb_bulk_out_task(void)
|
||||
{
|
||||
if (!sched_check_wake(&usb_bulk_out_wake))
|
||||
return;
|
||||
// Read data
|
||||
uint_fast8_t rpos = receive_pos, pop_count;
|
||||
if (rpos + USB_CDC_EP_BULK_OUT_SIZE <= sizeof(receive_buf)) {
|
||||
int_fast8_t ret = usb_read_bulk_out(
|
||||
&receive_buf[rpos], USB_CDC_EP_BULK_OUT_SIZE);
|
||||
if (ret > 0) {
|
||||
rpos += ret;
|
||||
usb_notify_bulk_out();
|
||||
}
|
||||
} else {
|
||||
usb_notify_bulk_out();
|
||||
}
|
||||
// Process a message block
|
||||
int_fast8_t ret = command_find_and_dispatch(receive_buf, rpos, &pop_count);
|
||||
if (ret) {
|
||||
// Move buffer
|
||||
uint_fast8_t needcopy = rpos - pop_count;
|
||||
if (needcopy) {
|
||||
memmove(receive_buf, &receive_buf[pop_count], needcopy);
|
||||
usb_notify_bulk_out();
|
||||
}
|
||||
rpos = needcopy;
|
||||
}
|
||||
receive_pos = rpos;
|
||||
}
|
||||
DECL_TASK(usb_bulk_out_task);
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* USB descriptors
|
||||
****************************************************************/
|
||||
|
||||
#define CONCAT1(a, b) a ## b
|
||||
#define CONCAT(a, b) CONCAT1(a, b)
|
||||
#define USB_STR_MANUFACTURER u"Klipper"
|
||||
#define USB_STR_PRODUCT CONCAT(u,CONFIG_MCU)
|
||||
#define USB_STR_SERIAL CONCAT(u,CONFIG_USB_SERIAL_NUMBER)
|
||||
|
||||
// String descriptors
|
||||
enum {
|
||||
USB_STR_ID_MANUFACTURER = 1, USB_STR_ID_PRODUCT, USB_STR_ID_SERIAL,
|
||||
};
|
||||
|
||||
#define SIZE_cdc_string_langids (sizeof(cdc_string_langids) + 2)
|
||||
|
||||
static const struct usb_string_descriptor cdc_string_langids PROGMEM = {
|
||||
.bLength = SIZE_cdc_string_langids,
|
||||
.bDescriptorType = USB_DT_STRING,
|
||||
.data = { cpu_to_le16(USB_LANGID_ENGLISH_US) },
|
||||
};
|
||||
|
||||
#define SIZE_cdc_string_manufacturer \
|
||||
(sizeof(cdc_string_manufacturer) + sizeof(USB_STR_MANUFACTURER) - 2)
|
||||
|
||||
static const struct usb_string_descriptor cdc_string_manufacturer PROGMEM = {
|
||||
.bLength = SIZE_cdc_string_manufacturer,
|
||||
.bDescriptorType = USB_DT_STRING,
|
||||
.data = USB_STR_MANUFACTURER,
|
||||
};
|
||||
|
||||
#define SIZE_cdc_string_product \
|
||||
(sizeof(cdc_string_product) + sizeof(USB_STR_PRODUCT) - 2)
|
||||
|
||||
static const struct usb_string_descriptor cdc_string_product PROGMEM = {
|
||||
.bLength = SIZE_cdc_string_product,
|
||||
.bDescriptorType = USB_DT_STRING,
|
||||
.data = USB_STR_PRODUCT,
|
||||
};
|
||||
|
||||
#define SIZE_cdc_string_serial \
|
||||
(sizeof(cdc_string_serial) + sizeof(USB_STR_SERIAL) - 2)
|
||||
|
||||
static const struct usb_string_descriptor cdc_string_serial PROGMEM = {
|
||||
.bLength = SIZE_cdc_string_serial,
|
||||
.bDescriptorType = USB_DT_STRING,
|
||||
.data = USB_STR_SERIAL,
|
||||
};
|
||||
|
||||
// Device descriptor
|
||||
static const struct usb_device_descriptor cdc_device_descriptor PROGMEM = {
|
||||
.bLength = sizeof(cdc_device_descriptor),
|
||||
.bDescriptorType = USB_DT_DEVICE,
|
||||
.bcdUSB = cpu_to_le16(0x0200),
|
||||
.bDeviceClass = USB_CLASS_COMM,
|
||||
.bMaxPacketSize0 = USB_CDC_EP0_SIZE,
|
||||
.idVendor = cpu_to_le16(CONFIG_USB_VENDOR_ID),
|
||||
.idProduct = cpu_to_le16(CONFIG_USB_DEVICE_ID),
|
||||
.bcdDevice = cpu_to_le16(0x0100),
|
||||
.iManufacturer = USB_STR_ID_MANUFACTURER,
|
||||
.iProduct = USB_STR_ID_PRODUCT,
|
||||
.iSerialNumber = USB_STR_ID_SERIAL,
|
||||
.bNumConfigurations = 1,
|
||||
};
|
||||
|
||||
// Config descriptor
|
||||
static const struct config_s {
|
||||
struct usb_config_descriptor config;
|
||||
struct usb_interface_descriptor iface0;
|
||||
struct usb_cdc_header_descriptor cdc_hdr;
|
||||
struct usb_cdc_acm_descriptor cdc_acm;
|
||||
struct usb_cdc_union_descriptor cdc_union;
|
||||
struct usb_endpoint_descriptor ep1;
|
||||
struct usb_interface_descriptor iface1;
|
||||
struct usb_endpoint_descriptor ep2;
|
||||
struct usb_endpoint_descriptor ep3;
|
||||
} PACKED cdc_config_descriptor PROGMEM = {
|
||||
.config = {
|
||||
.bLength = sizeof(cdc_config_descriptor.config),
|
||||
.bDescriptorType = USB_DT_CONFIG,
|
||||
.wTotalLength = cpu_to_le16(sizeof(cdc_config_descriptor)),
|
||||
.bNumInterfaces = 2,
|
||||
.bConfigurationValue = 1,
|
||||
.bmAttributes = 0xC0,
|
||||
.bMaxPower = 50,
|
||||
},
|
||||
.iface0 = {
|
||||
.bLength = sizeof(cdc_config_descriptor.iface0),
|
||||
.bDescriptorType = USB_DT_INTERFACE,
|
||||
.bInterfaceNumber = 0,
|
||||
.bNumEndpoints = 1,
|
||||
.bInterfaceClass = USB_CLASS_COMM,
|
||||
.bInterfaceSubClass = USB_CDC_SUBCLASS_ACM,
|
||||
.bInterfaceProtocol = USB_CDC_ACM_PROTO_AT_V25TER,
|
||||
},
|
||||
.cdc_hdr = {
|
||||
.bLength = sizeof(cdc_config_descriptor.cdc_hdr),
|
||||
.bDescriptorType = USB_CDC_CS_INTERFACE,
|
||||
.bDescriptorSubType = USB_CDC_HEADER_TYPE,
|
||||
.bcdCDC = 0x0110,
|
||||
},
|
||||
.cdc_acm = {
|
||||
.bLength = sizeof(cdc_config_descriptor.cdc_acm),
|
||||
.bDescriptorType = USB_CDC_CS_INTERFACE,
|
||||
.bDescriptorSubType = USB_CDC_ACM_TYPE,
|
||||
.bmCapabilities = 0x06,
|
||||
},
|
||||
.cdc_union = {
|
||||
.bLength = sizeof(cdc_config_descriptor.cdc_union),
|
||||
.bDescriptorType = USB_CDC_CS_INTERFACE,
|
||||
.bDescriptorSubType = USB_CDC_UNION_TYPE,
|
||||
.bMasterInterface0 = 0,
|
||||
.bSlaveInterface0 = 1,
|
||||
},
|
||||
.ep1 = {
|
||||
.bLength = sizeof(cdc_config_descriptor.ep1),
|
||||
.bDescriptorType = USB_DT_ENDPOINT,
|
||||
.bEndpointAddress = USB_CDC_EP_ACM | USB_DIR_IN,
|
||||
.bmAttributes = USB_ENDPOINT_XFER_INT,
|
||||
.wMaxPacketSize = cpu_to_le16(USB_CDC_EP_ACM_SIZE),
|
||||
.bInterval = 255,
|
||||
},
|
||||
.iface1 = {
|
||||
.bLength = sizeof(cdc_config_descriptor.iface1),
|
||||
.bDescriptorType = USB_DT_INTERFACE,
|
||||
.bInterfaceNumber = 1,
|
||||
.bNumEndpoints = 2,
|
||||
.bInterfaceClass = 0x0A,
|
||||
},
|
||||
.ep2 = {
|
||||
.bLength = sizeof(cdc_config_descriptor.ep2),
|
||||
.bDescriptorType = USB_DT_ENDPOINT,
|
||||
.bEndpointAddress = USB_CDC_EP_BULK_OUT,
|
||||
.bmAttributes = USB_ENDPOINT_XFER_BULK,
|
||||
.wMaxPacketSize = cpu_to_le16(USB_CDC_EP_BULK_OUT_SIZE),
|
||||
},
|
||||
.ep3 = {
|
||||
.bLength = sizeof(cdc_config_descriptor.ep3),
|
||||
.bDescriptorType = USB_DT_ENDPOINT,
|
||||
.bEndpointAddress = USB_CDC_EP_BULK_IN | USB_DIR_IN,
|
||||
.bmAttributes = USB_ENDPOINT_XFER_BULK,
|
||||
.wMaxPacketSize = cpu_to_le16(USB_CDC_EP_BULK_IN_SIZE),
|
||||
},
|
||||
};
|
||||
|
||||
// List of available descriptors
|
||||
static const struct descriptor_s {
|
||||
uint_fast16_t wValue;
|
||||
uint_fast16_t wIndex;
|
||||
const void *desc;
|
||||
uint_fast8_t size;
|
||||
} cdc_descriptors[] PROGMEM = {
|
||||
{ USB_DT_DEVICE<<8, 0x0000,
|
||||
&cdc_device_descriptor, sizeof(cdc_device_descriptor) },
|
||||
{ USB_DT_CONFIG<<8, 0x0000,
|
||||
&cdc_config_descriptor, sizeof(cdc_config_descriptor) },
|
||||
{ USB_DT_STRING<<8, 0x0000,
|
||||
&cdc_string_langids, SIZE_cdc_string_langids },
|
||||
{ (USB_DT_STRING<<8) | USB_STR_ID_MANUFACTURER, USB_LANGID_ENGLISH_US,
|
||||
&cdc_string_manufacturer, SIZE_cdc_string_manufacturer },
|
||||
{ (USB_DT_STRING<<8) | USB_STR_ID_PRODUCT, USB_LANGID_ENGLISH_US,
|
||||
&cdc_string_product, SIZE_cdc_string_product },
|
||||
#if !CONFIG_USB_SERIAL_NUMBER_CHIPID
|
||||
{ (USB_DT_STRING<<8) | USB_STR_ID_SERIAL, USB_LANGID_ENGLISH_US,
|
||||
&cdc_string_serial, SIZE_cdc_string_serial },
|
||||
#endif
|
||||
};
|
||||
|
||||
// Fill in a USB serial string descriptor from a chip id
|
||||
void
|
||||
usb_fill_serial(struct usb_string_descriptor *desc, int strlen, void *id)
|
||||
{
|
||||
desc->bLength = sizeof(*desc) + strlen * sizeof(desc->data[0]);
|
||||
desc->bDescriptorType = USB_DT_STRING;
|
||||
|
||||
uint8_t *src = id;
|
||||
int i;
|
||||
for (i = 0; i < strlen; i++) {
|
||||
uint8_t c = i & 1 ? src[i/2] & 0x0f : src[i/2] >> 4;
|
||||
desc->data[i] = c < 10 ? c + '0' : c - 10 + 'A';
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************
|
||||
* USB endpoint 0 control message handling
|
||||
****************************************************************/
|
||||
|
||||
// State tracking
|
||||
enum {
|
||||
UX_READ = 1<<0, UX_SEND = 1<<1, UX_SEND_PROGMEM = 1<<2, UX_SEND_ZLP = 1<<3
|
||||
};
|
||||
|
||||
static void *usb_xfer_data;
|
||||
static uint8_t usb_xfer_size, usb_xfer_flags;
|
||||
|
||||
// Set the USB "stall" condition
|
||||
static void
|
||||
usb_do_stall(void)
|
||||
{
|
||||
usb_stall_ep0();
|
||||
usb_xfer_flags = 0;
|
||||
}
|
||||
|
||||
// Transfer data on the usb endpoint 0
|
||||
static void
|
||||
usb_do_xfer(void *data, uint_fast8_t size, uint_fast8_t flags)
|
||||
{
|
||||
for (;;) {
|
||||
uint_fast8_t xs = size;
|
||||
if (xs > USB_CDC_EP0_SIZE)
|
||||
xs = USB_CDC_EP0_SIZE;
|
||||
int_fast8_t ret;
|
||||
if (flags & UX_READ)
|
||||
ret = usb_read_ep0(data, xs);
|
||||
else if (NEED_PROGMEM && flags & UX_SEND_PROGMEM)
|
||||
ret = usb_send_ep0_progmem(data, xs);
|
||||
else
|
||||
ret = usb_send_ep0(data, xs);
|
||||
if (ret == xs) {
|
||||
// Success
|
||||
data += xs;
|
||||
size -= xs;
|
||||
if (!size) {
|
||||
// Entire transfer completed successfully
|
||||
if (flags & UX_READ) {
|
||||
// Send status packet at end of read
|
||||
flags = UX_SEND;
|
||||
continue;
|
||||
}
|
||||
if (xs == USB_CDC_EP0_SIZE && flags & UX_SEND_ZLP)
|
||||
// Must send zero-length-packet
|
||||
continue;
|
||||
usb_xfer_flags = 0;
|
||||
usb_notify_ep0();
|
||||
return;
|
||||
}
|
||||
continue;
|
||||
}
|
||||
if (ret == -1) {
|
||||
// Interface busy - retry later
|
||||
usb_xfer_data = data;
|
||||
usb_xfer_size = size;
|
||||
usb_xfer_flags = flags;
|
||||
return;
|
||||
}
|
||||
// Error
|
||||
usb_do_stall();
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
usb_req_get_descriptor(struct usb_ctrlrequest *req)
|
||||
{
|
||||
if (req->bRequestType != USB_DIR_IN)
|
||||
goto fail;
|
||||
void *desc = NULL;
|
||||
uint_fast8_t flags, size, i;
|
||||
for (i=0; i<ARRAY_SIZE(cdc_descriptors); i++) {
|
||||
const struct descriptor_s *d = &cdc_descriptors[i];
|
||||
if (READP(d->wValue) == req->wValue
|
||||
&& READP(d->wIndex) == req->wIndex) {
|
||||
flags = NEED_PROGMEM ? UX_SEND_PROGMEM : UX_SEND;
|
||||
size = READP(d->size);
|
||||
desc = (void*)READP(d->desc);
|
||||
}
|
||||
}
|
||||
if (CONFIG_USB_SERIAL_NUMBER_CHIPID
|
||||
&& req->wValue == ((USB_DT_STRING<<8) | USB_STR_ID_SERIAL)
|
||||
&& req->wIndex == USB_LANGID_ENGLISH_US) {
|
||||
struct usb_string_descriptor *usbserial_serialid;
|
||||
usbserial_serialid = usbserial_get_serialid();
|
||||
flags = UX_SEND;
|
||||
size = usbserial_serialid->bLength;
|
||||
desc = (void*)usbserial_serialid;
|
||||
}
|
||||
if (desc) {
|
||||
if (size > req->wLength)
|
||||
size = req->wLength;
|
||||
else if (size < req->wLength)
|
||||
flags |= UX_SEND_ZLP;
|
||||
usb_do_xfer(desc, size, flags);
|
||||
return;
|
||||
}
|
||||
fail:
|
||||
usb_do_stall();
|
||||
}
|
||||
|
||||
static void
|
||||
usb_req_set_address(struct usb_ctrlrequest *req)
|
||||
{
|
||||
if (req->bRequestType || req->wIndex || req->wLength) {
|
||||
usb_do_stall();
|
||||
return;
|
||||
}
|
||||
usb_set_address(req->wValue);
|
||||
}
|
||||
|
||||
static void
|
||||
usb_req_set_configuration(struct usb_ctrlrequest *req)
|
||||
{
|
||||
if (req->bRequestType || req->wValue != 1 || req->wIndex || req->wLength) {
|
||||
usb_do_stall();
|
||||
return;
|
||||
}
|
||||
usb_set_configure();
|
||||
usb_notify_bulk_in();
|
||||
usb_notify_bulk_out();
|
||||
usb_do_xfer(NULL, 0, UX_SEND);
|
||||
}
|
||||
|
||||
static struct usb_cdc_line_coding line_coding;
|
||||
static uint8_t line_control_state;
|
||||
|
||||
static void
|
||||
check_reboot(void)
|
||||
{
|
||||
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();
|
||||
}
|
||||
|
||||
static void
|
||||
usb_req_set_line_coding(struct usb_ctrlrequest *req)
|
||||
{
|
||||
if (req->bRequestType != 0x21 || req->wValue || req->wIndex
|
||||
|| req->wLength != sizeof(line_coding)) {
|
||||
usb_do_stall();
|
||||
return;
|
||||
}
|
||||
usb_do_xfer(&line_coding, sizeof(line_coding), UX_READ);
|
||||
check_reboot();
|
||||
}
|
||||
|
||||
static void
|
||||
usb_req_get_line_coding(struct usb_ctrlrequest *req)
|
||||
{
|
||||
if (req->bRequestType != 0xa1 || req->wValue || req->wIndex
|
||||
|| req->wLength < sizeof(line_coding)) {
|
||||
usb_do_stall();
|
||||
return;
|
||||
}
|
||||
usb_do_xfer(&line_coding, sizeof(line_coding), UX_SEND);
|
||||
}
|
||||
|
||||
static void
|
||||
usb_req_set_line(struct usb_ctrlrequest *req)
|
||||
{
|
||||
if (req->bRequestType != 0x21 || req->wIndex || req->wLength) {
|
||||
usb_do_stall();
|
||||
return;
|
||||
}
|
||||
line_control_state = req->wValue;
|
||||
usb_do_xfer(NULL, 0, UX_SEND);
|
||||
check_reboot();
|
||||
}
|
||||
|
||||
static void
|
||||
usb_state_ready(void)
|
||||
{
|
||||
struct usb_ctrlrequest req;
|
||||
int_fast8_t ret = usb_read_ep0_setup(&req, sizeof(req));
|
||||
if (ret != sizeof(req))
|
||||
return;
|
||||
switch (req.bRequest) {
|
||||
case USB_REQ_GET_DESCRIPTOR: usb_req_get_descriptor(&req); break;
|
||||
case USB_REQ_SET_ADDRESS: usb_req_set_address(&req); break;
|
||||
case USB_REQ_SET_CONFIGURATION: usb_req_set_configuration(&req); break;
|
||||
case USB_CDC_REQ_SET_LINE_CODING: usb_req_set_line_coding(&req); break;
|
||||
case USB_CDC_REQ_GET_LINE_CODING: usb_req_get_line_coding(&req); break;
|
||||
case USB_CDC_REQ_SET_CONTROL_LINE_STATE: usb_req_set_line(&req); break;
|
||||
default: usb_do_stall(); break;
|
||||
}
|
||||
}
|
||||
|
||||
// State tracking dispatch
|
||||
static struct task_wake usb_ep0_wake;
|
||||
|
||||
void
|
||||
usb_notify_ep0(void)
|
||||
{
|
||||
sched_wake_task(&usb_ep0_wake);
|
||||
}
|
||||
|
||||
void
|
||||
usb_ep0_task(void)
|
||||
{
|
||||
if (!sched_check_wake(&usb_ep0_wake))
|
||||
return;
|
||||
if (usb_xfer_flags)
|
||||
usb_do_xfer(usb_xfer_data, usb_xfer_size, usb_xfer_flags);
|
||||
else
|
||||
usb_state_ready();
|
||||
}
|
||||
DECL_TASK(usb_ep0_task);
|
||||
|
||||
void
|
||||
usb_shutdown(void)
|
||||
{
|
||||
usb_notify_bulk_in();
|
||||
usb_notify_bulk_out();
|
||||
usb_notify_ep0();
|
||||
}
|
||||
DECL_SHUTDOWN(usb_shutdown);
|
||||
33
src/generic/usb_cdc.h
Normal file
33
src/generic/usb_cdc.h
Normal file
@@ -0,0 +1,33 @@
|
||||
#ifndef __GENERIC_USB_CDC_H
|
||||
#define __GENERIC_USB_CDC_H
|
||||
|
||||
#include <stdint.h> // uint_fast8_t
|
||||
|
||||
// endpoint sizes
|
||||
enum {
|
||||
USB_CDC_EP0_SIZE = 16,
|
||||
USB_CDC_EP_ACM_SIZE = 8,
|
||||
USB_CDC_EP_BULK_OUT_SIZE = 64,
|
||||
USB_CDC_EP_BULK_IN_SIZE = 64,
|
||||
};
|
||||
|
||||
// callbacks provided by board specific code
|
||||
int_fast8_t usb_read_bulk_out(void *data, uint_fast8_t max_len);
|
||||
int_fast8_t usb_send_bulk_in(void *data, uint_fast8_t len);
|
||||
int_fast8_t usb_read_ep0(void *data, uint_fast8_t max_len);
|
||||
int_fast8_t usb_read_ep0_setup(void *data, uint_fast8_t max_len);
|
||||
int_fast8_t usb_send_ep0(const void *data, uint_fast8_t len);
|
||||
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
|
||||
void usb_fill_serial(struct usb_string_descriptor *desc, int strlen, void *id);
|
||||
void usb_notify_bulk_in(void);
|
||||
void usb_notify_bulk_out(void);
|
||||
void usb_notify_ep0(void);
|
||||
|
||||
#endif // usb_cdc.h
|
||||
11
src/generic/usb_cdc_ep.h
Normal file
11
src/generic/usb_cdc_ep.h
Normal file
@@ -0,0 +1,11 @@
|
||||
#ifndef __GENERIC_USB_CDC_EP_H
|
||||
#define __GENERIC_USB_CDC_EP_H
|
||||
|
||||
// Default USB endpoint ids
|
||||
enum {
|
||||
USB_CDC_EP_BULK_IN = 1,
|
||||
USB_CDC_EP_BULK_OUT = 2,
|
||||
USB_CDC_EP_ACM = 3,
|
||||
};
|
||||
|
||||
#endif // usb_cdc_ep.h
|
||||
128
src/generic/usbstd.h
Normal file
128
src/generic/usbstd.h
Normal file
@@ -0,0 +1,128 @@
|
||||
// Standard definitions for USB commands and data structures
|
||||
#ifndef __GENERIC_USBSTD_H
|
||||
#define __GENERIC_USBSTD_H
|
||||
|
||||
#include <stdint.h> // uint8_t
|
||||
#include "compiler.h" // PACKED
|
||||
|
||||
#define USB_DIR_OUT 0 /* to device */
|
||||
#define USB_DIR_IN 0x80 /* to host */
|
||||
|
||||
#define USB_TYPE_MASK (0x03 << 5)
|
||||
#define USB_TYPE_STANDARD (0x00 << 5)
|
||||
#define USB_TYPE_CLASS (0x01 << 5)
|
||||
#define USB_TYPE_VENDOR (0x02 << 5)
|
||||
#define USB_TYPE_RESERVED (0x03 << 5)
|
||||
|
||||
#define USB_REQ_GET_STATUS 0x00
|
||||
#define USB_REQ_CLEAR_FEATURE 0x01
|
||||
#define USB_REQ_SET_FEATURE 0x03
|
||||
#define USB_REQ_SET_ADDRESS 0x05
|
||||
#define USB_REQ_GET_DESCRIPTOR 0x06
|
||||
#define USB_REQ_SET_DESCRIPTOR 0x07
|
||||
#define USB_REQ_GET_CONFIGURATION 0x08
|
||||
#define USB_REQ_SET_CONFIGURATION 0x09
|
||||
#define USB_REQ_GET_INTERFACE 0x0A
|
||||
#define USB_REQ_SET_INTERFACE 0x0B
|
||||
#define USB_REQ_SYNCH_FRAME 0x0C
|
||||
|
||||
struct usb_ctrlrequest {
|
||||
uint8_t bRequestType;
|
||||
uint8_t bRequest;
|
||||
uint16_t wValue;
|
||||
uint16_t wIndex;
|
||||
uint16_t wLength;
|
||||
} PACKED;
|
||||
|
||||
#define USB_DT_DEVICE 0x01
|
||||
#define USB_DT_CONFIG 0x02
|
||||
#define USB_DT_STRING 0x03
|
||||
#define USB_DT_INTERFACE 0x04
|
||||
#define USB_DT_ENDPOINT 0x05
|
||||
#define USB_DT_DEVICE_QUALIFIER 0x06
|
||||
#define USB_DT_OTHER_SPEED_CONFIG 0x07
|
||||
#define USB_DT_ENDPOINT_COMPANION 0x30
|
||||
|
||||
struct usb_device_descriptor {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
|
||||
uint16_t bcdUSB;
|
||||
uint8_t bDeviceClass;
|
||||
uint8_t bDeviceSubClass;
|
||||
uint8_t bDeviceProtocol;
|
||||
uint8_t bMaxPacketSize0;
|
||||
uint16_t idVendor;
|
||||
uint16_t idProduct;
|
||||
uint16_t bcdDevice;
|
||||
uint8_t iManufacturer;
|
||||
uint8_t iProduct;
|
||||
uint8_t iSerialNumber;
|
||||
uint8_t bNumConfigurations;
|
||||
} PACKED;
|
||||
|
||||
#define USB_CLASS_PER_INTERFACE 0 /* for DeviceClass */
|
||||
#define USB_CLASS_AUDIO 1
|
||||
#define USB_CLASS_COMM 2
|
||||
#define USB_CLASS_HID 3
|
||||
#define USB_CLASS_PHYSICAL 5
|
||||
#define USB_CLASS_STILL_IMAGE 6
|
||||
#define USB_CLASS_PRINTER 7
|
||||
#define USB_CLASS_MASS_STORAGE 8
|
||||
#define USB_CLASS_HUB 9
|
||||
|
||||
struct usb_config_descriptor {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
|
||||
uint16_t wTotalLength;
|
||||
uint8_t bNumInterfaces;
|
||||
uint8_t bConfigurationValue;
|
||||
uint8_t iConfiguration;
|
||||
uint8_t bmAttributes;
|
||||
uint8_t bMaxPower;
|
||||
} PACKED;
|
||||
|
||||
struct usb_interface_descriptor {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
|
||||
uint8_t bInterfaceNumber;
|
||||
uint8_t bAlternateSetting;
|
||||
uint8_t bNumEndpoints;
|
||||
uint8_t bInterfaceClass;
|
||||
uint8_t bInterfaceSubClass;
|
||||
uint8_t bInterfaceProtocol;
|
||||
uint8_t iInterface;
|
||||
} PACKED;
|
||||
|
||||
struct usb_endpoint_descriptor {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
|
||||
uint8_t bEndpointAddress;
|
||||
uint8_t bmAttributes;
|
||||
uint16_t wMaxPacketSize;
|
||||
uint8_t bInterval;
|
||||
} PACKED;
|
||||
|
||||
#define USB_ENDPOINT_NUMBER_MASK 0x0f /* in bEndpointAddress */
|
||||
#define USB_ENDPOINT_DIR_MASK 0x80
|
||||
|
||||
#define USB_ENDPOINT_XFERTYPE_MASK 0x03 /* in bmAttributes */
|
||||
#define USB_ENDPOINT_XFER_CONTROL 0
|
||||
#define USB_ENDPOINT_XFER_ISOC 1
|
||||
#define USB_ENDPOINT_XFER_BULK 2
|
||||
#define USB_ENDPOINT_XFER_INT 3
|
||||
#define USB_ENDPOINT_MAX_ADJUSTABLE 0x80
|
||||
|
||||
struct usb_string_descriptor {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
//uint16_t data[];
|
||||
typeof(*u"") data[];
|
||||
} PACKED;
|
||||
|
||||
#define USB_LANGID_ENGLISH_US 0x0409
|
||||
|
||||
#endif // usbstd.h
|
||||
49
src/generic/usbstd_cdc.h
Normal file
49
src/generic/usbstd_cdc.h
Normal file
@@ -0,0 +1,49 @@
|
||||
// Standard definitions for USB CDC devices
|
||||
#ifndef __GENERIC_USBSTD_CDC_H
|
||||
#define __GENERIC_USBSTD_CDC_H
|
||||
|
||||
#define USB_CDC_SUBCLASS_ACM 0x02
|
||||
|
||||
#define USB_CDC_ACM_PROTO_AT_V25TER 1
|
||||
|
||||
struct usb_cdc_header_descriptor {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
uint8_t bDescriptorSubType;
|
||||
uint16_t bcdCDC;
|
||||
} PACKED;
|
||||
|
||||
#define USB_CDC_HEADER_TYPE 0x00
|
||||
#define USB_CDC_ACM_TYPE 0x02
|
||||
#define USB_CDC_UNION_TYPE 0x06
|
||||
|
||||
#define USB_CDC_CS_INTERFACE 0x24
|
||||
#define USB_CDC_CS_ENDPOINT 0x25
|
||||
|
||||
struct usb_cdc_acm_descriptor {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
uint8_t bDescriptorSubType;
|
||||
uint8_t bmCapabilities;
|
||||
} PACKED;
|
||||
|
||||
struct usb_cdc_union_descriptor {
|
||||
uint8_t bLength;
|
||||
uint8_t bDescriptorType;
|
||||
uint8_t bDescriptorSubType;
|
||||
uint8_t bMasterInterface0;
|
||||
uint8_t bSlaveInterface0;
|
||||
} PACKED;
|
||||
|
||||
#define USB_CDC_REQ_SET_LINE_CODING 0x20
|
||||
#define USB_CDC_REQ_GET_LINE_CODING 0x21
|
||||
#define USB_CDC_REQ_SET_CONTROL_LINE_STATE 0x22
|
||||
|
||||
struct usb_cdc_line_coding {
|
||||
uint32_t dwDTERate;
|
||||
uint8_t bCharFormat;
|
||||
uint8_t bParityType;
|
||||
uint8_t bDataBits;
|
||||
} PACKED;
|
||||
|
||||
#endif // usbstd_cdc.h
|
||||
215
src/gpiocmds.c
Normal file
215
src/gpiocmds.c
Normal file
@@ -0,0 +1,215 @@
|
||||
// Commands for controlling GPIO output pins
|
||||
//
|
||||
// Copyright (C) 2016-2020 Kevin O'Connor <kevin@koconnor.net>
|
||||
//
|
||||
// This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
|
||||
#include "basecmd.h" // oid_alloc
|
||||
#include "board/gpio.h" // struct gpio_out
|
||||
#include "board/irq.h" // irq_disable
|
||||
#include "board/misc.h" // timer_is_before
|
||||
#include "command.h" // DECL_COMMAND
|
||||
#include "sched.h" // sched_add_timer
|
||||
|
||||
struct digital_out_s {
|
||||
struct timer timer;
|
||||
uint32_t on_duration, off_duration, end_time;
|
||||
struct gpio_out pin;
|
||||
uint32_t max_duration, cycle_time;
|
||||
struct move_queue_head mq;
|
||||
uint8_t flags;
|
||||
};
|
||||
|
||||
struct digital_move {
|
||||
struct move_node node;
|
||||
uint32_t waketime, on_duration;
|
||||
};
|
||||
|
||||
enum {
|
||||
DF_ON=1<<0, DF_TOGGLING=1<<1, DF_CHECK_END=1<<2, DF_DEFAULT_ON=1<<4
|
||||
};
|
||||
|
||||
static uint_fast8_t digital_load_event(struct timer *timer);
|
||||
|
||||
// Software PWM toggle event
|
||||
static uint_fast8_t
|
||||
digital_toggle_event(struct timer *timer)
|
||||
{
|
||||
struct digital_out_s *d = container_of(timer, struct digital_out_s, timer);
|
||||
gpio_out_toggle_noirq(d->pin);
|
||||
d->flags ^= DF_ON;
|
||||
uint32_t waketime = d->timer.waketime;
|
||||
if (d->flags & DF_ON)
|
||||
waketime += d->on_duration;
|
||||
else
|
||||
waketime += d->off_duration;
|
||||
if (d->flags & DF_CHECK_END && !timer_is_before(waketime, d->end_time)) {
|
||||
// End of normal pulsing - next event loads new pwm settings
|
||||
d->timer.func = digital_load_event;
|
||||
waketime = d->end_time;
|
||||
}
|
||||
d->timer.waketime = waketime;
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
|
||||
// Load next pin output setting
|
||||
static uint_fast8_t
|
||||
digital_load_event(struct timer *timer)
|
||||
{
|
||||
// Apply next update and remove it from queue
|
||||
struct digital_out_s *d = container_of(timer, struct digital_out_s, timer);
|
||||
if (move_queue_empty(&d->mq))
|
||||
shutdown("Missed scheduling of next digital out event");
|
||||
struct move_node *mn = move_queue_pop(&d->mq);
|
||||
struct digital_move *m = container_of(mn, struct digital_move, node);
|
||||
uint32_t on_duration = m->on_duration;
|
||||
uint8_t flags = on_duration ? DF_ON : 0;
|
||||
gpio_out_write(d->pin, flags);
|
||||
move_free(m);
|
||||
|
||||
// Calculate next end_time and flags
|
||||
uint32_t end_time = 0;
|
||||
if (!flags || on_duration >= d->cycle_time) {
|
||||
// Pin is in an always on or always off state
|
||||
if (!flags != !(d->flags & DF_DEFAULT_ON) && d->max_duration) {
|
||||
end_time = d->timer.waketime + d->max_duration;
|
||||
flags |= DF_CHECK_END;
|
||||
}
|
||||
} else {
|
||||
flags |= DF_TOGGLING;
|
||||
if (d->max_duration) {
|
||||
end_time = d->timer.waketime + d->max_duration;
|
||||
flags |= DF_CHECK_END;
|
||||
}
|
||||
}
|
||||
if (!move_queue_empty(&d->mq)) {
|
||||
struct move_node *nn = move_queue_first(&d->mq);
|
||||
uint32_t wake = container_of(nn, struct digital_move, node)->waketime;
|
||||
if (flags & DF_CHECK_END && timer_is_before(end_time, wake))
|
||||
shutdown("Scheduled digital out event will exceed max_duration");
|
||||
end_time = wake;
|
||||
flags |= DF_CHECK_END;
|
||||
}
|
||||
d->end_time = end_time;
|
||||
d->flags = flags | (d->flags & DF_DEFAULT_ON);
|
||||
|
||||
// Schedule next event
|
||||
if (!(flags & DF_TOGGLING)) {
|
||||
if (!(flags & DF_CHECK_END))
|
||||
// Pin not toggling and nothing scheduled
|
||||
return SF_DONE;
|
||||
d->timer.waketime = end_time;
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
uint32_t waketime = d->timer.waketime + on_duration;
|
||||
if (flags & DF_CHECK_END && !timer_is_before(waketime, end_time)) {
|
||||
d->timer.waketime = end_time;
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
d->timer.func = digital_toggle_event;
|
||||
d->timer.waketime = waketime;
|
||||
d->on_duration = on_duration;
|
||||
d->off_duration = d->cycle_time - on_duration;
|
||||
return SF_RESCHEDULE;
|
||||
}
|
||||
|
||||
void
|
||||
command_config_digital_out(uint32_t *args)
|
||||
{
|
||||
struct gpio_out pin = gpio_out_setup(args[1], !!args[2]);
|
||||
struct digital_out_s *d = oid_alloc(args[0], command_config_digital_out
|
||||
, sizeof(*d));
|
||||
d->pin = pin;
|
||||
d->flags = (args[2] ? DF_ON : 0) | (args[3] ? DF_DEFAULT_ON : 0);
|
||||
d->max_duration = args[4];
|
||||
move_queue_setup(&d->mq, sizeof(struct digital_move));
|
||||
}
|
||||
DECL_COMMAND(command_config_digital_out,
|
||||
"config_digital_out oid=%c pin=%u value=%c"
|
||||
" default_value=%c max_duration=%u");
|
||||
|
||||
void
|
||||
command_set_digital_out_pwm_cycle(uint32_t *args)
|
||||
{
|
||||
struct digital_out_s *d = oid_lookup(args[0], command_config_digital_out);
|
||||
irq_disable();
|
||||
if (!move_queue_empty(&d->mq))
|
||||
shutdown("Can not set soft pwm cycle ticks while updates pending");
|
||||
d->cycle_time = args[1];
|
||||
irq_enable();
|
||||
}
|
||||
DECL_COMMAND(command_set_digital_out_pwm_cycle,
|
||||
"set_digital_out_pwm_cycle oid=%c cycle_ticks=%u");
|
||||
|
||||
void
|
||||
command_queue_digital_out(uint32_t *args)
|
||||
{
|
||||
struct digital_out_s *d = oid_lookup(args[0], command_config_digital_out);
|
||||
struct digital_move *m = move_alloc();
|
||||
uint32_t time = m->waketime = args[1];
|
||||
m->on_duration = args[2];
|
||||
|
||||
irq_disable();
|
||||
int first_on_queue = move_queue_push(&m->node, &d->mq);
|
||||
if (!first_on_queue) {
|
||||
irq_enable();
|
||||
return;
|
||||
}
|
||||
uint8_t flags = d->flags;
|
||||
if (flags & DF_CHECK_END && timer_is_before(d->end_time, time))
|
||||
shutdown("Scheduled digital out event will exceed max_duration");
|
||||
d->end_time = time;
|
||||
d->flags = flags | DF_CHECK_END;
|
||||
if (flags & DF_TOGGLING && timer_is_before(d->timer.waketime, time)) {
|
||||
// digital_toggle_event() will schedule a load event when ready
|
||||
} else {
|
||||
// Schedule the loading of the parameters at the requested time
|
||||
sched_del_timer(&d->timer);
|
||||
d->timer.waketime = time;
|
||||
d->timer.func = digital_load_event;
|
||||
sched_add_timer(&d->timer);
|
||||
}
|
||||
irq_enable();
|
||||
}
|
||||
DECL_COMMAND(command_queue_digital_out,
|
||||
"queue_digital_out oid=%c clock=%u on_ticks=%u");
|
||||
|
||||
void
|
||||
command_update_digital_out(uint32_t *args)
|
||||
{
|
||||
struct digital_out_s *d = oid_lookup(args[0], command_config_digital_out);
|
||||
sched_del_timer(&d->timer);
|
||||
if (!move_queue_empty(&d->mq))
|
||||
shutdown("update_digital_out not valid with active queue");
|
||||
uint8_t value = args[1], flags = d->flags, on_flag = value ? DF_ON : 0;
|
||||
gpio_out_write(d->pin, on_flag);
|
||||
if (!on_flag != !(flags & DF_DEFAULT_ON) && d->max_duration) {
|
||||
d->timer.waketime = d->end_time = timer_read_time() + d->max_duration;
|
||||
d->timer.func = digital_load_event;
|
||||
d->flags = (flags & DF_DEFAULT_ON) | on_flag | DF_CHECK_END;
|
||||
sched_add_timer(&d->timer);
|
||||
} else {
|
||||
d->flags = (flags & DF_DEFAULT_ON) | on_flag;
|
||||
}
|
||||
}
|
||||
DECL_COMMAND(command_update_digital_out, "update_digital_out oid=%c value=%c");
|
||||
|
||||
void
|
||||
digital_out_shutdown(void)
|
||||
{
|
||||
uint8_t i;
|
||||
struct digital_out_s *d;
|
||||
foreach_oid(i, d, command_config_digital_out) {
|
||||
gpio_out_write(d->pin, d->flags & DF_DEFAULT_ON);
|
||||
d->flags = d->flags & DF_DEFAULT_ON ? DF_ON | DF_DEFAULT_ON : 0;
|
||||
move_queue_clear(&d->mq);
|
||||
}
|
||||
}
|
||||
DECL_SHUTDOWN(digital_out_shutdown);
|
||||
|
||||
void
|
||||
command_set_digital_out(uint32_t *args)
|
||||
{
|
||||
gpio_out_setup(args[0], args[1]);
|
||||
}
|
||||
DECL_COMMAND(command_set_digital_out, "set_digital_out pin=%u value=%c");
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user