--- /dev/null
+# Makefile for the project Bulidbotics firmware
+PROJECT = bbctrl-jig-firmware
+MCU = atxmega192a3u
+CLOCK = 32000000
+VERSION = 0.0.1
+
+TARGET = $(PROJECT).elf
+
+# Compile flags
+CC = avr-gcc
+CPP = avr-g++
+
+COMMON = -mmcu=$(MCU) -flto -fwhole-program
+
+CFLAGS += $(COMMON)
+CFLAGS += -Wall -Werror
+CFLAGS += -Wno-error=strict-aliasing # for _invsqrt
+CFLAGS += -std=gnu99 -DF_CPU=$(CLOCK)UL -O3
+CFLAGS += -funsigned-bitfields -fpack-struct -fshort-enums -funsigned-char
+CFLAGS += -MD -MP -MT $@ -MF build/dep/$(@F).d
+CFLAGS += -Isrc -DVERSION=\"$(VERSION)\"
+
+# Linker flags
+LDFLAGS += $(COMMON) -Wl,-u,vfprintf -lprintf_flt -lm
+LIBS += -lm
+
+# EEPROM flags
+EEFLAGS += -j .eeprom
+EEFLAGS += --set-section-flags=.eeprom="alloc,load"
+EEFLAGS += --change-section-lma .eeprom=0 --no-change-warnings
+
+# Programming flags
+PROGRAMMER = avrispmkII
+#PROGRAMMER = jtag3pdi
+PDEV = usb
+AVRDUDE_OPTS = -c $(PROGRAMMER) -p $(MCU) -P $(PDEV)
+
+FUSE0=0xff
+FUSE1=0x00
+FUSE2=0xbe
+FUSE4=0xff
+FUSE5=0xeb
+
+# SRC
+SRC = $(wildcard src/*.c)
+OBJ = $(patsubst src/%.c,build/%.o,$(SRC))
+
+# Build
+all:
+ @$(MAKE) $(PROJECT).hex
+ @$(MAKE) size
+
+# Compile
+build/%.o: src/%.c
+ @mkdir -p $(shell dirname $@)
+ $(CC) $(INCLUDES) $(CFLAGS) -c -o $@ $<
+
+build/%.o: src/%.S
+ @mkdir -p $(shell dirname $@)
+ $(CC) $(INCLUDES) $(CFLAGS) -c -o $@ $<
+
+# Link
+$(TARGET): $(OBJ)
+ $(CC) $(LDFLAGS) $(OBJ) $(LIBS) -o $@
+
+%.hex: %.elf
+ avr-objcopy -O ihex -R .eeprom -R .fuse -R .lock -R .signature $< $@
+
+%.eep: %.elf
+ avr-objcopy $(EEFLAGS) -O ihex $< $@
+
+%.lss: %.elf
+ avr-objdump -h -S $< > $@
+
+_size:
+ @for X in A B C; do\
+ echo '****************************************************************' ;\
+ avr-size -$$X --mcu=$(MCU) $(SIZE_TARGET) ;\
+ done
+
+size: $(TARGET)
+ @$(MAKE) SIZE_TARGET=$< _size
+
+# Program
+init:
+ $(MAKE) erase
+ -$(MAKE) fuses
+ $(MAKE) program
+
+reset:
+ avrdude $(AVRDUDE_OPTS)
+
+erase:
+ avrdude $(AVRDUDE_OPTS) -e
+
+program: $(PROJECT).hex
+ avrdude $(AVRDUDE_OPTS) -U flash:w:$(PROJECT).hex:i
+
+verify: $(PROJECT).hex
+ avrdude $(AVRDUDE_OPTS) -U flash:v:$(PROJECT).hex:i
+
+fuses:
+ avrdude $(AVRDUDE_OPTS) -U fuse0:w:$(FUSE0):m -U fuse1:w:$(FUSE1):m \
+ -U fuse2:w:$(FUSE2):m -U fuse4:w:$(FUSE4):m -U fuse5:w:$(FUSE5):m
+
+read_fuses:
+ avrdude $(AVRDUDE_OPTS) -q -q -U fuse0:r:-:h -U fuse1:r:-:h -U fuse2:r:-:h \
+ -U fuse4:r:-:h -U fuse5:r:-:h
+
+signature:
+ avrdude $(AVRDUDE_OPTS) -q -q -U signature:r:-:h
+
+prodsig:
+ avrdude $(AVRDUDE_OPTS) -q -q -U prodsig:r:-:h
+
+usersig:
+ avrdude $(AVRDUDE_OPTS) -q -q -U usersig:r:-:h
+
+# Clean
+tidy:
+ rm -f $(shell find -name \*~ -o -name \#\*)
+
+clean: tidy
+ rm -rf $(PROJECT).elf $(PROJECT).hex $(PROJECT).eep $(PROJECT).lss \
+ $(PROJECT).map build
+
+.PHONY: tidy clean size all reset erase program fuses read_fuses prodsig
+.PHONY: signature usersig
+
+# Dependencies
+-include $(shell mkdir -p build/dep) $(wildcard build/dep/*)
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics test jig firmware.
+
+ Copyright (c) 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#pragma once
+
+#include "pins.h"
+
+
+// Pins
+enum {
+ STALL_X_PIN = PORT_A << 3,
+ STALL_Y_PIN,
+ STALL_Z_PIN,
+ STALL_A_PIN,
+ SPIN_DIR_PIN,
+ SPIN_ENABLE_PIN,
+ ANALOG_PIN,
+ PROBE_PIN,
+
+ MIN_X_PIN = PORT_B << 3,
+ MAX_X_PIN,
+ MIN_A_PIN,
+ MAX_A_PIN,
+ MIN_Y_PIN,
+ MAX_Y_PIN,
+ MIN_Z_PIN,
+ MAX_Z_PIN,
+
+ SDA_PIN = PORT_C << 3,
+ SCL_PIN,
+ SERIAL_RX_PIN,
+ SERIAL_TX_PIN,
+ SERIAL_CTS_PIN,
+ SPI_CLK_PIN,
+ SPI_MISO_PIN,
+ SPI_MOSI_PIN,
+
+ ENCODER_X_A_PIN = PORT_D << 3,
+ ENCODER_X_B_PIN,
+ SPI_CS_A_PIN,
+ SPI_CS_Z_PIN,
+ SPIN_PWM_PIN,
+ SWITCH_1_PIN,
+ RS485_RO_PIN,
+ RS485_DI_PIN,
+
+ STEP_Y_PIN = PORT_E << 3,
+ SPI_CS_Y_PIN,
+ DIR_X_PIN,
+ DIR_Y_PIN,
+ STEP_A_PIN,
+ SWITCH_2_PIN,
+ DIR_Z_PIN,
+ DIR_A_PIN,
+
+ STEP_Z_PIN = PORT_F << 3,
+ RS485_RW_PIN,
+ FAULT_PIN,
+ ESTOP_PIN,
+ MOTOR_FAULT_PIN,
+ MOTOR_ENABLE_PIN,
+ NC_0_PIN,
+ NC_1_PIN,
+};
+
+
+// Serial settings
+#define SERIAL_BAUD USART_BAUD_115200
+#define SERIAL_PORT USARTC0
+#define SERIAL_DRE_vect USARTC0_DRE_vect
+#define SERIAL_RXC_vect USARTC0_RXC_vect
+
+
+// Input
+#define INPUT_BUFFER_LEN 255 // text buffer size (255 max)
+
+
+// Encoder
+#define ENCODER_LINES 600
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics test jig firmware.
+
+ Copyright (c) 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#include "encoder.h"
+
+#include "pins.h"
+#include "config.h"
+
+#include <avr/io.h>
+
+
+typedef struct {
+ int8_t pin_a;
+ int8_t pin_b;
+
+ uint16_t position;
+ float velocity;
+} encoder_t;
+
+
+encoder_t encoders[] = {
+ {ENCODER_X_A_PIN, ENCODER_X_B_PIN},
+ {0, 0}
+};
+
+
+void encoder_init() {
+ for (int i = 0; encoders[i].pin_a; i++) {
+ // Inputs
+ DIRCLR_PIN(encoders[i].pin_a);
+ DIRCLR_PIN(encoders[i].pin_b);
+
+ // Pullup and level sensing
+ PINCTRL_PIN(encoders[i].pin_a) = PORT_OPC_PULLUP_gc | PORT_ISC_LEVEL_gc;
+ PINCTRL_PIN(encoders[i].pin_b) = PORT_OPC_PULLUP_gc | PORT_ISC_LEVEL_gc;
+ }
+
+ // Event channel
+ EVSYS_CH0MUX = EVSYS_CHMUX_PORTD_PIN0_gc;
+ EVSYS_CH0CTRL = EVSYS_QDEN_bm | EVSYS_DIGFILT_2SAMPLES_gc;
+
+ // Timer config
+ TCC0.CTRLD = TC_EVACT_QDEC_gc | TC_EVSEL_CH0_gc;
+ TCC0.PER = ENCODER_LINES * 4 - 1;
+ TCC0.CTRLA = TC_CLKSEL_DIV1_gc; // Enable
+}
+
+
+void encoder_rtc_callback() {
+ uint16_t position = TCC0.CNT;
+
+ int32_t delta =
+ ((int32_t)position - encoders[0].position) % (ENCODER_LINES * 4);
+
+ encoders[0].position = position;
+ encoders[0].velocity = encoders[0].velocity * 0.95 + delta * 5.0; // steps/sec
+}
+
+
+uint16_t encoder_get_position(int i) {return encoders[i].position;}
+float encoder_get_velocity(int i) {return encoders[i].velocity;}
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics test jig firmware.
+
+ Copyright (c) 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#pragma once
+
+#include <stdint.h>
+
+void encoder_init();
+void encoder_rtc_callback();
+
+uint16_t encoder_get_position(int i);
+float encoder_get_velocity(int i);
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics test jig firmware.
+
+ Copyright (c) 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#include "usart.h"
+#include "rtc.h"
+#include "encoder.h"
+
+#include <avr/interrupt.h>
+#include <avr/pgmspace.h>
+
+#include <util/delay.h>
+
+#include <stdio.h>
+#include <stdbool.h>
+
+
+static void _clock_init() {
+ // 12-16 MHz crystal; 0.4-16 MHz XTAL w/ 16K CLK startup
+ OSC.XOSCCTRL = OSC_FRQRANGE_12TO16_gc | OSC_XOSCSEL_XTAL_16KCLK_gc;
+ OSC.CTRL = OSC_XOSCEN_bm; // enable external crystal oscillator
+ while (!(OSC.STATUS & OSC_XOSCRDY_bm)); // wait for oscillator ready
+
+ OSC.PLLCTRL = OSC_PLLSRC_XOSC_gc | 2; // PLL source, 2x (32 MHz sys clock)
+ OSC.CTRL = OSC_PLLEN_bm | OSC_XOSCEN_bm; // Enable PLL & External Oscillator
+ while (!(OSC.STATUS & OSC_PLLRDY_bm)); // wait for PLL ready
+
+ CCP = CCP_IOREG_gc;
+ CLK.CTRL = CLK_SCLKSEL_PLL_gc; // switch to PLL clock
+
+ OSC.CTRL &= ~OSC_RC2MEN_bm; // disable internal 2 MHz clock
+}
+
+
+int main() {
+ // Init
+ cli(); // disable interrupts
+
+ _clock_init();
+ rtc_init(); // real-time clock
+ usart_init(); // serial port
+ encoder_init(); // rotary encoders
+
+ sei(); // enable interrupts
+
+ // Splash
+ fprintf_P(stdout, PSTR("\nBuildbotics Jig " VERSION "\n"));
+
+ usart_set(USART_ECHO, true);
+
+ uint32_t timer = 0;
+ uint16_t last = 0;
+
+ // Main loop
+ while (true) {
+ char *line = usart_readline();
+ if (line) {
+ printf("\n%s\n", line);
+ printf("%ld\n", rtc_get_time());
+ }
+
+ if (rtc_expired(timer)) {
+ timer += 100;
+
+ uint16_t encoder = encoder_get_position(0);
+ if (encoder != last) {
+ last = encoder;
+ printf("%5d step %8.2f step/sec\n", encoder, encoder_get_velocity(0));
+ }
+ }
+ }
+
+ return 0;
+}
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics firmware.
+
+ Copyright (c) 2015 - 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#include "pins.h"
+
+
+PORT_t *pin_ports[] = {&PORTA, &PORTB, &PORTC, &PORTD, &PORTE, &PORTF};
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics firmware.
+
+ Copyright (c) 2015 - 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#pragma once
+
+enum {PORT_A = 1, PORT_B, PORT_C, PORT_D, PORT_E, PORT_F};
+
+#define PORT(PIN) pin_ports[(PIN >> 3) - 1]
+#define BM(PIN) (1 << (PIN & 7))
+
+#ifdef __AVR__
+#include <avr/io.h>
+
+extern PORT_t *pin_ports[];
+
+#define DIRSET_PIN(PIN) PORT(PIN)->DIRSET = BM(PIN)
+#define DIRCLR_PIN(PIN) PORT(PIN)->DIRCLR = BM(PIN)
+#define OUTCLR_PIN(PIN) PORT(PIN)->OUTCLR = BM(PIN)
+#define OUTSET_PIN(PIN) PORT(PIN)->OUTSET = BM(PIN)
+#define OUTTGL_PIN(PIN) PORT(PIN)->OUTTGL = BM(PIN)
+#define OUT_PIN(PIN) (!!(PORT(PIN)->OUT & BM(PIN)))
+#define IN_PIN(PIN) (!!(PORT(PIN)->IN & BM(PIN)))
+#define PINCTRL_PIN(PIN) ((&PORT(PIN)->PIN0CTRL)[PIN & 7])
+
+#define SET_PIN(PIN, X) \
+ do {if (X) OUTSET_PIN(PIN); else OUTCLR_PIN(PIN);} while (0);
+
+#endif // __AVR__
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics firmware.
+
+ Copyright (c) 2015 - 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+/* This file defines an X-Macro ring buffer. It can be used like this:
+ *
+ * #define RING_BUF_NAME tx_buf
+ * #define RING_BUF_SIZE 256
+ * #include "ringbuf.def"
+ *
+ * This will define the following functions:
+ *
+ * void <name>_init();
+ * int <name>_empty();
+ * int <name>_full();
+ * <type> <name>_peek();
+ * void <name>_pop();
+ * void <name>_push(<type> data);
+ *
+ * Where <name> is defined by RING_BUF_NAME and <type> by RING_BUF_TYPE.
+ * RING_BUF_SIZE defines the length of the ring buffer and must be a power of 2.
+ *
+ * The data type and index type both default to uint8_t but can be changed by
+ * defining RING_BUF_TYPE and RING_BUF_INDEX_TYPE respectively.
+ *
+ * By default these functions are declared static inline but this can be changed
+ * by defining RING_BUF_FUNC.
+ */
+
+#include <stdint.h>
+
+#ifndef RING_BUF_NAME
+#error Must define RING_BUF_NAME
+#endif
+
+#ifndef RING_BUF_SIZE
+#error Must define RING_BUF_SIZE
+#endif
+
+#ifndef RING_BUF_TYPE
+#define RING_BUF_TYPE uint8_t
+#endif
+
+#ifndef RING_BUF_INDEX_TYPE
+#define RING_BUF_INDEX_TYPE uint8_t
+#endif
+
+#ifndef RING_BUF_FUNC
+#define RING_BUF_FUNC static inline
+#endif
+
+#define RING_BUF_MASK (RING_BUF_SIZE - 1)
+#if (RING_BUF_SIZE & RING_BUF_MASK)
+#error RING_BUF_SIZE is not a power of 2
+#endif
+
+#ifndef CONCAT
+#define _CONCAT(prefix, name) prefix##name
+#define CONCAT(prefix, name) _CONCAT(prefix, name)
+#endif
+
+#define RING_BUF_STRUCT CONCAT(RING_BUF_NAME, _ring_buf_t)
+#define RING_BUF CONCAT(RING_BUF_NAME, _ring_buf)
+
+typedef struct {
+ RING_BUF_TYPE buf[RING_BUF_SIZE];
+ volatile RING_BUF_INDEX_TYPE head;
+ volatile RING_BUF_INDEX_TYPE tail;
+} RING_BUF_STRUCT;
+
+static RING_BUF_STRUCT RING_BUF;
+
+
+RING_BUF_FUNC void CONCAT(RING_BUF_NAME, _init)() {
+ RING_BUF.head = RING_BUF.tail = 0;
+}
+
+
+#define RING_BUF_INC CONCAT(RING_BUF_NAME, _inc)
+RING_BUF_FUNC RING_BUF_INDEX_TYPE RING_BUF_INC(RING_BUF_INDEX_TYPE x) {
+ return (x + 1) & RING_BUF_MASK;
+}
+
+
+RING_BUF_FUNC int CONCAT(RING_BUF_NAME, _empty)() {
+ return RING_BUF.head == RING_BUF.tail;
+}
+
+
+RING_BUF_FUNC int CONCAT(RING_BUF_NAME, _full)() {
+ return RING_BUF.head == RING_BUF_INC(RING_BUF.tail);
+}
+
+
+RING_BUF_FUNC int CONCAT(RING_BUF_NAME, _fill)() {
+ return (RING_BUF.tail - RING_BUF.head) & RING_BUF_MASK;
+}
+
+
+RING_BUF_FUNC int CONCAT(RING_BUF_NAME, _space)() {
+ return RING_BUF_SIZE - CONCAT(RING_BUF_NAME, _fill)();
+}
+
+
+RING_BUF_FUNC RING_BUF_TYPE CONCAT(RING_BUF_NAME, _peek)() {
+ return RING_BUF.buf[RING_BUF.head];
+}
+
+
+RING_BUF_FUNC RING_BUF_TYPE CONCAT(RING_BUF_NAME, _get)(int offset) {
+ return RING_BUF.buf[(RING_BUF.head + offset) & RING_BUF_MASK];
+}
+
+
+RING_BUF_FUNC void CONCAT(RING_BUF_NAME, _pop)() {
+ RING_BUF.head = RING_BUF_INC(RING_BUF.head);
+}
+
+
+RING_BUF_FUNC void CONCAT(RING_BUF_NAME, _push)(RING_BUF_TYPE data) {
+ RING_BUF.buf[RING_BUF.tail] = data;
+ RING_BUF.tail = RING_BUF_INC(RING_BUF.tail);
+}
+
+
+#undef RING_BUF
+#undef RING_BUF_STRUCT
+#undef RING_BUF_INC
+#undef RING_BUF_MASK
+
+#undef RING_BUF_NAME
+#undef RING_BUF_SIZE
+#undef RING_BUF_TYPE
+#undef RING_BUF_INDEX_TYPE
+#undef RING_BUF_FUNC
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics firmware.
+
+ Copyright (c) 2015 - 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#include "rtc.h"
+
+#include "encoder.h"
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+
+
+static uint32_t ticks;
+
+
+ISR(RTC_OVF_vect) {
+ ticks++;
+ encoder_rtc_callback();
+}
+
+
+/// Initialize and start the clock
+/// This routine follows the code in app note AVR1314.
+void rtc_init() {
+ ticks = 0;
+
+ PR.PRGEN &= ~PR_RTC_bm; // Disable power reduction
+
+ OSC.CTRL |= OSC_RC32KEN_bm; // enable internal 32kHz.
+ while (!(OSC.STATUS & OSC_RC32KRDY_bm)); // 32kHz osc stabilize
+ while (RTC.STATUS & RTC_SYNCBUSY_bm); // wait RTC not busy
+
+ CLK.RTCCTRL = CLK_RTCSRC_RCOSC32_gc | CLK_RTCEN_bm; // 32kHz clock as RTC src
+ while (RTC.STATUS & RTC_SYNCBUSY_bm); // wait RTC not busy
+
+ // the following must be in this order or it doesn't work
+ RTC.PER = 33; // overflow period ~1ms
+ RTC.INTCTRL = RTC_OVFINTLVL_LO_gc; // overflow LO interrupt
+ RTC.CTRL = RTC_PRESCALER_DIV1_gc; // no prescale
+
+ PMIC.CTRL |= PMIC_LOLVLEN_bm; // Interrupt level on
+}
+
+
+uint32_t rtc_get_time() {return ticks;}
+bool rtc_expired(uint32_t t) {return 0 <= (int32_t)(ticks - t);}
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics firmware.
+
+ Copyright (c) 2015 - 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#pragma once
+
+
+#include <stdint.h>
+#include <stdbool.h>
+
+void rtc_init();
+uint32_t rtc_get_time();
+int32_t rtc_diff(uint32_t t);
+bool rtc_expired(uint32_t t);
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics test jig firmware.
+
+ Copyright (c) 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#include "usart.h"
+//#include "cpp_magic.h"
+#include "config.h"
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+
+#include <stdio.h>
+#include <stdbool.h>
+
+// Ring buffers
+#define RING_BUF_NAME tx_buf
+#define RING_BUF_SIZE USART_TX_RING_BUF_SIZE
+#include "ringbuf.def"
+
+#define RING_BUF_NAME rx_buf
+#define RING_BUF_SIZE USART_RX_RING_BUF_SIZE
+#include "ringbuf.def"
+
+static int usart_flags = USART_CRLF;
+
+
+static void _set_dre_interrupt(bool enable) {
+ if (enable) SERIAL_PORT.CTRLA |= USART_DREINTLVL_HI_gc;
+ else SERIAL_PORT.CTRLA &= ~USART_DREINTLVL_HI_gc;
+}
+
+
+static void _set_rxc_interrupt(bool enable) {
+ if (enable) {
+ SERIAL_PORT.CTRLA |= USART_RXCINTLVL_HI_gc;
+ if (4 <= rx_buf_space()) OUTCLR_PIN(SERIAL_CTS_PIN); // CTS Lo (enable)
+
+ } else SERIAL_PORT.CTRLA &= ~USART_RXCINTLVL_HI_gc;
+}
+
+
+// Data register empty interrupt vector
+ISR(SERIAL_DRE_vect) {
+ if (tx_buf_empty()) _set_dre_interrupt(false); // Disable interrupt
+
+ else {
+ SERIAL_PORT.DATA = tx_buf_peek();
+ tx_buf_pop();
+ }
+}
+
+
+// Data received interrupt vector
+ISR(SERIAL_RXC_vect) {
+ if (rx_buf_full()) _set_rxc_interrupt(false); // Disable interrupt
+
+ else {
+ uint8_t data = SERIAL_PORT.DATA;
+ rx_buf_push(data);
+ if (rx_buf_space() < 4) OUTSET_PIN(SERIAL_CTS_PIN); // CTS Hi (disable)
+ }
+}
+
+
+static int _usart_putchar(char c, FILE *f) {
+ usart_putc(c);
+ return 0;
+}
+
+static FILE _stdout = FDEV_SETUP_STREAM(_usart_putchar, 0, _FDEV_SETUP_WRITE);
+
+
+void usart_init(void) {
+ // Setup ring buffer
+ tx_buf_init();
+ rx_buf_init();
+
+ PR.PRPC &= ~PR_USART0_bm; // Disable power reduction
+
+ // Setup pins
+ OUTSET_PIN(SERIAL_CTS_PIN); // CTS Hi (disable)
+ DIRSET_PIN(SERIAL_CTS_PIN); // CTS Output
+ OUTSET_PIN(SERIAL_TX_PIN); // Tx High
+ DIRSET_PIN(SERIAL_TX_PIN); // Tx Output
+ DIRCLR_PIN(SERIAL_RX_PIN); // Rx Input
+
+ // Set baud rate
+ usart_set_baud(SERIAL_BAUD);
+
+ // No parity, 8 data bits, 1 stop bit
+ SERIAL_PORT.CTRLC = USART_CMODE_ASYNCHRONOUS_gc | USART_PMODE_DISABLED_gc |
+ USART_CHSIZE_8BIT_gc;
+
+ // Configure receiver and transmitter
+ SERIAL_PORT.CTRLB = USART_RXEN_bm | USART_TXEN_bm | USART_CLK2X_bm;
+
+ PMIC.CTRL |= PMIC_HILVLEN_bm; // Interrupt level on
+
+ // Connect IO
+ stdout = &_stdout;
+ stderr = &_stdout;
+
+ // Enable Rx
+ _set_rxc_interrupt(true);
+}
+
+
+static void _set_baud(uint16_t bsel, uint8_t bscale) {
+ SERIAL_PORT.BAUDCTRLB = (uint8_t)((bscale << 4) | (bsel >> 8));
+ SERIAL_PORT.BAUDCTRLA = bsel;
+}
+
+
+void usart_set_baud(int baud) {
+ // The BSEL / BSCALE values provided below assume a 32 Mhz clock
+ // Assumes CTRLB CLK2X bit (0x04) is set
+ // See http://www.avrcalc.elektronik-projekt.de/xmega/baud_rate_calculator
+
+ switch (baud) {
+ case USART_BAUD_9600: _set_baud(3325, 0b1101); break;
+ case USART_BAUD_19200: _set_baud(3317, 0b1100); break;
+ case USART_BAUD_38400: _set_baud(3301, 0b1011); break;
+ case USART_BAUD_57600: _set_baud(1095, 0b1100); break;
+ case USART_BAUD_115200: _set_baud(1079, 0b1011); break;
+ case USART_BAUD_230400: _set_baud(1047, 0b1010); break;
+ case USART_BAUD_460800: _set_baud(983, 0b1001); break;
+ case USART_BAUD_921600: _set_baud(107, 0b1011); break;
+ case USART_BAUD_500000: _set_baud(1, 0b0010); break;
+ case USART_BAUD_1000000: _set_baud(1, 0b0001); break;
+ }
+}
+
+
+void usart_set(int flag, bool enable) {
+ if (enable) usart_flags |= flag;
+ else usart_flags &= ~flag;
+}
+
+
+bool usart_is_set(int flags) {
+ return (usart_flags & flags) == flags;
+}
+
+
+void usart_putc(char c) {
+ while (tx_buf_full() || (usart_flags & USART_FLUSH)) continue;
+
+ tx_buf_push(c);
+
+ _set_dre_interrupt(true); // Enable interrupt
+
+ if ((usart_flags & USART_CRLF) && c == '\n') usart_putc('\r');
+}
+
+
+void usart_puts(const char *s) {
+ while (*s) usart_putc(*s++);
+}
+
+
+int8_t usart_getc() {
+ while (rx_buf_empty()) continue;
+
+ uint8_t data = rx_buf_peek();
+ rx_buf_pop();
+
+ _set_rxc_interrupt(true); // Enable interrupt
+
+ return data;
+}
+
+
+char *usart_readline() {
+ static char line[INPUT_BUFFER_LEN];
+ static int i = 0;
+ bool eol = false;
+
+ while (!rx_buf_empty()) {
+ char data = usart_getc();
+
+ if (usart_flags & USART_ECHO) usart_putc(data);
+
+ switch (data) {
+ case '\r': case '\n': eol = true; break;
+
+ case '\b': // BS - backspace
+ if (usart_flags & USART_ECHO) {
+ usart_putc(' ');
+ usart_putc('\b');
+ }
+ if (i) i--;
+ break;
+
+ case 0x18: // CAN - Cancel or CTRL-X
+ if (usart_flags & USART_ECHO)
+ while (i) {
+ usart_putc('\b');
+ usart_putc(' ');
+ usart_putc('\b');
+ i--;
+ }
+
+ i = 0;
+ break;
+
+ default:
+ line[i++] = data;
+ if (i == INPUT_BUFFER_LEN - 1) eol = true;
+ break;
+ }
+
+ if (eol) {
+ line[i] = 0;
+ i = 0;
+ return line;
+ }
+ }
+
+ return 0;
+}
+
+
+int16_t usart_peek() {
+ return rx_buf_empty() ? -1 : rx_buf_peek();
+}
+
+
+void usart_flush() {
+ usart_set(USART_FLUSH, true);
+
+ while (!tx_buf_empty() || !(SERIAL_PORT.STATUS & USART_DREIF_bm) ||
+ !(SERIAL_PORT.STATUS & USART_TXCIF_bm))
+ continue;
+}
+
+
+void usart_rx_flush() {
+ rx_buf_init();
+}
+
+
+int16_t usart_rx_space() {
+ return rx_buf_space();
+}
+
+
+int16_t usart_rx_fill() {
+ return rx_buf_fill();
+}
+
+
+int16_t usart_tx_space() {
+ return tx_buf_space();
+}
+
+
+int16_t usart_tx_fill() {
+ return tx_buf_fill();
+}
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics firmware.
+
+ Copyright (c) 2015 - 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#pragma once
+
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#define USART_TX_RING_BUF_SIZE 256
+#define USART_RX_RING_BUF_SIZE 256
+
+enum {
+ USART_BAUD_9600,
+ USART_BAUD_19200,
+ USART_BAUD_38400,
+ USART_BAUD_57600,
+ USART_BAUD_115200,
+ USART_BAUD_230400,
+ USART_BAUD_460800,
+ USART_BAUD_921600,
+ USART_BAUD_500000,
+ USART_BAUD_1000000
+};
+
+enum {
+ USART_CRLF = 1 << 0,
+ USART_ECHO = 1 << 1,
+ USART_XOFF = 1 << 2,
+ USART_FLUSH = 1 << 3,
+};
+
+void usart_init();
+void usart_set_baud(int baud);
+void usart_set(int flag, bool enable);
+bool usart_is_set(int flags);
+void usart_putc(char c);
+void usart_puts(const char *s);
+int8_t usart_getc();
+char *usart_readline();
+int16_t usart_peek();
+void usart_flush();
+
+void usart_rx_flush();
+int16_t usart_rx_fill();
+int16_t usart_rx_space();
+inline bool usart_rx_empty() {return !usart_rx_fill();}
+inline bool usart_rx_full() {return !usart_rx_space();}
+
+int16_t usart_tx_fill();
+int16_t usart_tx_space();
+inline bool usart_tx_empty() {return !usart_tx_fill();}
+inline bool usart_tx_full() {return !usart_tx_space();}