From 28c1a6a74ad241cf35489683dcba029a7cb5dbd4 Mon Sep 17 00:00:00 2001 From: Jake Read <jake.read@cba.mit.edu> Date: Fri, 22 Jan 2021 13:11:36 -0500 Subject: [PATCH] stepper with osape, stable with xyz --- .gitmodules | 3 + 2020-06_ucbus-stepper-melted/eagle.epf | 2 +- .../src/config.h | 7 + .../src/drivers/dacs.h | 2 +- .../src/drivers/dip_ucbus_config.cpp | 55 -- .../src/drivers/dip_ucbus_config.h | 24 - .../src/drivers/step_a4950.h | 2 +- .../src/drivers/ucbus_drop.cpp | 281 ---------- .../src/drivers/ucbus_drop.h | 123 ----- .../src/main.cpp | 120 ++--- .../src/osap/osap.cpp | 487 ------------------ .../src/osap/osap.h | 60 --- .../src/osap/ts.cpp | 64 --- .../src/osap/ts.h | 100 ---- .../src/osap/vport.cpp | 40 -- .../src/osap/vport.h | 52 -- .../src/osap/vport_usbserial.cpp | 141 ----- .../src/osap/vport_usbserial.h | 57 -- .../osape-smoothieroll-drop-stepper/src/osape | 1 + .../src/utils/clocks_d51_module.cpp | 115 ----- .../src/utils/clocks_d51_module.h | 43 -- .../src/utils/cobs.cpp | 60 --- .../src/utils/cobs.h | 24 - .../src/utils/syserror.cpp | 38 -- .../src/utils/syserror.h | 11 - 25 files changed, 54 insertions(+), 1858 deletions(-) create mode 100644 .gitmodules create mode 100644 firmware/osape-smoothieroll-drop-stepper/src/config.h delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/drivers/dip_ucbus_config.cpp delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/drivers/dip_ucbus_config.h delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/drivers/ucbus_drop.cpp delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/drivers/ucbus_drop.h delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/osap/osap.cpp delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/osap/osap.h delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/osap/ts.cpp delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/osap/ts.h delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/osap/vport.cpp delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/osap/vport.h delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/osap/vport_usbserial.cpp delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/osap/vport_usbserial.h create mode 160000 firmware/osape-smoothieroll-drop-stepper/src/osape delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/utils/clocks_d51_module.cpp delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/utils/clocks_d51_module.h delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/utils/cobs.cpp delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/utils/cobs.h delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/utils/syserror.cpp delete mode 100644 firmware/osape-smoothieroll-drop-stepper/src/utils/syserror.h diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..eee21bb --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "firmware/osape-smoothieroll-drop-stepper/src/osape"] + path = firmware/osape-smoothieroll-drop-stepper/src/osape + url = ssh://git@gitlab.cba.mit.edu:846/jakeread/osape.git diff --git a/2020-06_ucbus-stepper-melted/eagle.epf b/2020-06_ucbus-stepper-melted/eagle.epf index 793c8af..404203f 100644 --- a/2020-06_ucbus-stepper-melted/eagle.epf +++ b/2020-06_ucbus-stepper-melted/eagle.epf @@ -58,7 +58,7 @@ Sheet="1" Type="Board Editor" Number=2 File="2020-06_ucbus-stepper-melted.brd" -View="20.0133 22.7202 31.9216 35.358" +View="15.3304 3.43831 50.8884 41.1746" WireWidths=" 0.8 0.9 0.1 0.05 0.5 0 0.3 0.2032 0.1524" PadDiameters=" 0.254 0.3048 0.4064 0.6096 0.8128 1.016 1.27 1.4224 1.6764 1.778 1.9304 2.1844 2.54 3.81 6.4516 0" PadDrills=" 0.2 0.25 0.3 0.35 0.4 0.45 0.5 0.55 0.65 0.7 0.75 0.8 0.85 0.9 1 0.6" diff --git a/firmware/osape-smoothieroll-drop-stepper/src/config.h b/firmware/osape-smoothieroll-drop-stepper/src/config.h new file mode 100644 index 0000000..3f537ba --- /dev/null +++ b/firmware/osape-smoothieroll-drop-stepper/src/config.h @@ -0,0 +1,7 @@ +#ifndef CONFIG_H_ +#define CONFIG_H_ + +//#define UCBUS_IS_HEAD +#define UCBUS_IS_DROP + +#endif \ No newline at end of file diff --git a/firmware/osape-smoothieroll-drop-stepper/src/drivers/dacs.h b/firmware/osape-smoothieroll-drop-stepper/src/drivers/dacs.h index 6d09539..15cc2ea 100644 --- a/firmware/osape-smoothieroll-drop-stepper/src/drivers/dacs.h +++ b/firmware/osape-smoothieroll-drop-stepper/src/drivers/dacs.h @@ -18,7 +18,7 @@ is; no warranty is provided, and users accept all liability. #include <arduino.h> #include "indicators.h" -#include "utils/syserror.h" +#include "../osape/utils/syserror.h" // scrape https://github.com/adafruit/ArduinoCore-samd/blob/master/cores/arduino/wiring_analog.c // scrape https://github.com/adafruit/ArduinoCore-samd/blob/master/cores/arduino/startup.c (clock) diff --git a/firmware/osape-smoothieroll-drop-stepper/src/drivers/dip_ucbus_config.cpp b/firmware/osape-smoothieroll-drop-stepper/src/drivers/dip_ucbus_config.cpp deleted file mode 100644 index e0316b3..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/drivers/dip_ucbus_config.cpp +++ /dev/null @@ -1,55 +0,0 @@ -// DIPs - -#include "dip_ucbus_config.h" - -void dip_init(void){ - // set direction in, - DIP_PORT.DIRCLR.reg = D_BM(D0_PIN) | D_BM(D1_PIN) | D_BM(D2_PIN) | D_BM(D3_PIN) | D_BM(D4_PIN) | D_BM(D5_PIN) | D_BM(D6_PIN) | D_BM(D7_PIN); - // enable in, - DIP_PORT.PINCFG[D0_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D1_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D2_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D3_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D4_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D5_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D6_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D7_PIN].bit.INEN = 1; - // enable pull, - DIP_PORT.PINCFG[D0_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D1_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D2_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D3_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D4_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D5_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D6_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D7_PIN].bit.PULLEN = 1; - // 'pull' references the value set in the 'out' register, so to pulldown: - DIP_PORT.OUTCLR.reg = D_BM(D0_PIN) | D_BM(D1_PIN) | D_BM(D2_PIN) | D_BM(D3_PIN) | D_BM(D4_PIN) | D_BM(D5_PIN) | D_BM(D6_PIN) | D_BM(D7_PIN); -} - -uint8_t dip_read_lower_five(void){ - uint32_t bits[5] = {0,0,0,0,0}; - if(DIP_PORT.IN.reg & D_BM(D7_PIN)) { bits[0] = 1; } - if(DIP_PORT.IN.reg & D_BM(D6_PIN)) { bits[1] = 1; } - if(DIP_PORT.IN.reg & D_BM(D5_PIN)) { bits[2] = 1; } - if(DIP_PORT.IN.reg & D_BM(D4_PIN)) { bits[3] = 1; } - if(DIP_PORT.IN.reg & D_BM(D3_PIN)) { bits[4] = 1; } - /* - bits[0] = (DIP_PORT.IN.reg & D_BM(D7_PIN)) >> D7_PIN; - bits[1] = (DIP_PORT.IN.reg & D_BM(D6_PIN)) >> D6_PIN; - bits[2] = (DIP_PORT.IN.reg & D_BM(D5_PIN)) >> D5_PIN; - bits[3] = (DIP_PORT.IN.reg & D_BM(D4_PIN)) >> D4_PIN; - bits[4] = (DIP_PORT.IN.reg & D_BM(D3_PIN)) >> D3_PIN; - */ - uint32_t word = 0; - word = word | (bits[4] << 4) | (bits[3] << 3) | (bits[2] << 2) | (bits[1] << 1) | (bits[0] << 0); - return (uint8_t)word; -} - -boolean dip_read_pin_0(void){ - return DIP_PORT.IN.reg & D_BM(D0_PIN); -} - -boolean dip_read_pin_1(void){ - return DIP_PORT.IN.reg & D_BM(D1_PIN); -} \ No newline at end of file diff --git a/firmware/osape-smoothieroll-drop-stepper/src/drivers/dip_ucbus_config.h b/firmware/osape-smoothieroll-drop-stepper/src/drivers/dip_ucbus_config.h deleted file mode 100644 index 44eaa00..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/drivers/dip_ucbus_config.h +++ /dev/null @@ -1,24 +0,0 @@ -// DIP switch HAL macros -// pardon the mis-labeling: on board, and in the schem, these are 1-8, -// here they will be 0-7 - -// note: these are 'on' hi by default, from the factory. -// to set low, need to turn the internal pulldown on - -#include <Arduino.h> - -#define D0_PIN 5 -#define D1_PIN 4 -#define D2_PIN 3 -#define D3_PIN 2 -#define D4_PIN 1 -#define D5_PIN 0 -#define D6_PIN 31 -#define D7_PIN 30 -#define DIP_PORT PORT->Group[1] -#define D_BM(val) ((uint32_t)(1 << val)) - -void dip_init(void); -uint8_t dip_read_lower_five(void); -boolean dip_read_pin_0(void); // bus-head (hi) or bus-drop (lo) -boolean dip_read_pin_1(void); // if bus-drop, te-enable (hi) or no (lo) \ No newline at end of file diff --git a/firmware/osape-smoothieroll-drop-stepper/src/drivers/step_a4950.h b/firmware/osape-smoothieroll-drop-stepper/src/drivers/step_a4950.h index 4b42868..e5e5a56 100644 --- a/firmware/osape-smoothieroll-drop-stepper/src/drivers/step_a4950.h +++ b/firmware/osape-smoothieroll-drop-stepper/src/drivers/step_a4950.h @@ -19,7 +19,7 @@ is; no warranty is provided, and users accept all liability. #include "dacs.h" #include "indicators.h" -#include "utils/syserror.h" +#include "../osape/utils/syserror.h" // C_SCALE // 1: DACs go 0->512 (of 4096, peak current is 1.6A at 4096): 0.2A diff --git a/firmware/osape-smoothieroll-drop-stepper/src/drivers/ucbus_drop.cpp b/firmware/osape-smoothieroll-drop-stepper/src/drivers/ucbus_drop.cpp deleted file mode 100644 index 657919b..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/drivers/ucbus_drop.cpp +++ /dev/null @@ -1,281 +0,0 @@ -/* -osap/drivers/ucbus_head.cpp - -beginnings of a uart-based clock / bus combo protocol - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo -projects. Copyright is retained and must be preserved. The work is provided as -is; no warranty is provided, and users accept all liability. -*/ - -#include "ucbus_drop.h" - -UCBus_Drop* UCBus_Drop::instance = 0; - -UCBus_Drop* UCBus_Drop::getInstance(void){ - if(instance == 0){ - instance = new UCBus_Drop(); - } - return instance; -} - -// making this instance globally available, when built, -// recall extern declaration in .h -UCBus_Drop* ucBusDrop = UCBus_Drop::getInstance(); - -UCBus_Drop::UCBus_Drop(void) {} - -// so, first thing, I've some confusion about what might be the best way (again) to implement -// multiple similar drivers. I did this before w/ the cobserialport, I might again want to -// do it, but by writing more static hardware drivers that another parent class (the bus) forwards to -// so the init codes / etc could all be verbatim with hardware registers, instead of this infinite list of defines - -// yeah, this kind of stuff is morning work: focus, tracking little details. go to bed. - -void UCBus_Drop::init(boolean useDipPick, uint8_t ID) { - dip_init(); - if(useDipPick){ - // set our id, - id = dip_read_lower_five(); - } else { - id = ID; - } - if(id > 14){ - id = 14; - } - // set driver output LO to start: tri-state - UBD_DE_PORT.DIRSET.reg = UBD_DE_BM; - UBD_DRIVER_DISABLE; - // set receiver output on, forever: LO to set on - UBD_RE_PORT.DIRSET.reg = UBD_RE_BM; - UBD_RE_PORT.OUTCLR.reg = UBD_RE_BM; - // termination resistor should be set only on one drop, - // or none and physically with a 'tail' cable, or something? - UBD_TE_PORT.DIRSET.reg = UBD_TE_BM; - if(dip_read_pin_1()){ - UBD_TE_PORT.OUTCLR.reg = UBD_TE_BM; - } else { - UBD_TE_PORT.OUTSET.reg = UBD_TE_BM; - } - // rx pin setup - UBD_COMPORT.DIRCLR.reg = UBD_RXBM; - UBD_COMPORT.PINCFG[UBD_RXPIN].bit.PMUXEN = 1; - if(UBD_RXPIN % 2){ - UBD_COMPORT.PMUX[UBD_RXPIN >> 1].reg |= PORT_PMUX_PMUXO(UBD_RXPERIPHERAL); - } else { - UBD_COMPORT.PMUX[UBD_RXPIN >> 1].reg |= PORT_PMUX_PMUXE(UBD_RXPERIPHERAL); - } - // tx - UBD_COMPORT.DIRCLR.reg = UBD_TXBM; - UBD_COMPORT.PINCFG[UBD_TXPIN].bit.PMUXEN = 1; - if(UBD_TXPIN % 2){ - UBD_COMPORT.PMUX[UBD_TXPIN >> 1].reg |= PORT_PMUX_PMUXO(UBD_TXPERIPHERAL); - } else { - UBD_COMPORT.PMUX[UBD_TXPIN >> 1].reg |= PORT_PMUX_PMUXE(UBD_TXPERIPHERAL); - } - // ok, clocks, first line au manuel - // unmask clocks - MCLK->APBAMASK.bit.SERCOM1_ = 1; - GCLK->GENCTRL[UBD_GCLKNUM_PICK].reg = GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DFLL) | GCLK_GENCTRL_GENEN; - while(GCLK->SYNCBUSY.reg & GCLK_SYNCBUSY_GENCTRL(UBD_GCLKNUM_PICK)); - GCLK->PCHCTRL[UBD_SERCOM_CLK].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(UBD_GCLKNUM_PICK); - // then, sercom - while(UBD_SER_USART.SYNCBUSY.bit.ENABLE); - UBD_SER_USART.CTRLA.bit.ENABLE = 0; - while(UBD_SER_USART.SYNCBUSY.bit.SWRST); - UBD_SER_USART.CTRLA.bit.SWRST = 1; - while(UBD_SER_USART.SYNCBUSY.bit.SWRST); - while(UBD_SER_USART.SYNCBUSY.bit.SWRST || UBD_SER_USART.SYNCBUSY.bit.ENABLE); - // ok, well - UBD_SER_USART.CTRLA.reg = SERCOM_USART_CTRLA_MODE(1) | SERCOM_USART_CTRLA_DORD; - UBD_SER_USART.CTRLA.reg |= SERCOM_USART_CTRLA_RXPO(UBD_RXPO) | SERCOM_USART_CTRLA_TXPO(0); - UBD_SER_USART.CTRLA.reg |= SERCOM_USART_CTRLA_FORM(1); // enable even parity - while(UBD_SER_USART.SYNCBUSY.bit.CTRLB); - UBD_SER_USART.CTRLB.reg = SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN | SERCOM_USART_CTRLB_CHSIZE(0); - // enable interrupts - NVIC_EnableIRQ(SERCOM1_2_IRQn); // rx, - NVIC_EnableIRQ(SERCOM1_1_IRQn); // txc ? - NVIC_EnableIRQ(SERCOM1_0_IRQn); // tx, - // set baud - UBD_SER_USART.BAUD.reg = UBD_BAUD_VAL; - // and finally, a kickoff - while(UBD_SER_USART.SYNCBUSY.bit.ENABLE); - UBD_SER_USART.CTRLA.bit.ENABLE = 1; - // enable rx interrupt - UBD_SER_USART.INTENSET.bit.RXC = 1; -} - -void SERCOM1_2_Handler(void){ - //ERRLIGHT_TOGGLE; - ucBusDrop->rxISR(); -} - -void UCBus_Drop::rxISR(void){ - // check parity bit, - uint16_t perr = UBD_SER_USART.STATUS.bit.PERR; - if(perr){ - //DEBUGPIN_ON; - uint8_t clear = UBD_SER_USART.DATA.reg; - UBD_SER_USART.STATUS.bit.PERR = 1; // clear parity error - return; - } - // cleared by reading out, but we are blind feed forward atm - uint8_t data = UBD_SER_USART.DATA.reg; - // for now, just running the clk, on every 0th bit - if((data >> 7) == 0){ // timer bit, on every 0th bit, and beginning of word - inWord[0] = data; - timeTick ++; - timeBlink ++; - if(timeBlink >= blinkTime){ - CLKLIGHT_TOGGLE; - timeBlink = 0; - } - onRxISR(); // on start of each word - } else { // end of word on every 0th bit - inWord[1] = data; - // now decouple, - inHeader = ((inWord[0] >> 1) & 0b00111000) | ((inWord[1] >> 4) & 0b00000111); - inByte = ((inWord[0] << 4) & 0b11110000) | (inWord[1] & 0b00001111); - // now check incoming data, - if((inHeader & 0b00110000) == 0b00100000){ // has-token, CHA - lastWordAHadToken = true; - if(inBufferALen != 0){ // in this case, we didn't read-out of the buffer in time, - inBufferALen = 0; // so we reset it, missing the last packet ! - inBufferARp = 0; - } - inBufferA[inBufferARp] = inByte; - inBufferARp ++; - } else if ((inHeader & 0b00110000) == 0b00000000) { // no-token, CHA - if(lastWordAHadToken){ - inBufferALen = inBufferARp - 1; - onPacketARx(); - } - lastWordAHadToken = false; - } else if ((inHeader & 0b00110000) == 0b00110000) { // has-token, CHB - //DEBUG1PIN_ON; - lastWordBHadToken = true; - if(inBufferBLen != 0){ - inBufferBLen = 0; - inBufferBRp = 0; - } - inBufferB[inBufferBRp] = inByte; - inBufferBRp ++; - } else if ((inHeader & 0b00110000) == 0b00010000) { // no-token, CHB - if(lastWordBHadToken){ - inBufferBLen = inBufferARp - 1; - //onPacketBRx(); // b-channel handled in loop, yah - } - lastWordBHadToken = false; - } - // now check if outgoing tick is ours, - if((inHeader & dropIdMask) == id){ - // our transmit - if(outBufferLen > 0){ - outByte = outBuffer[outBufferRp]; - outHeader = headerMask & (tokenWord | (id & 0b00011111)); - } else { - outByte = 0; - outHeader = headerMask & (noTokenWord | (id & 0b00011111)); - } - outWord[0] = 0b00000000 | ((outHeader << 1) & 0b01110000) | (outByte >> 4); - outWord[1] = 0b10000000 | ((outHeader << 4) & 0b01110000) | (outByte & 0b00001111); - // now transmit, - UBD_DRIVER_ENABLE; - UBD_SER_USART.DATA.reg = outWord[0]; - UBD_SER_USART.INTENSET.bit.DRE = 1; - // now do this, - if(outBufferLen > 0){ - outBufferRp ++; - if(outBufferRp >= outBufferLen){ - outBufferRp = 0; - outBufferLen = 0; - } - } - } else if ((inHeader & dropIdMask) == UBD_CLOCKRESET){ - // reset - timeTick = 0; - } - } // end 1th bit case, - // do every-tick stuff -} - -void SERCOM1_0_Handler(void){ - ucBusDrop->dreISR(); -} - -void UCBus_Drop::dreISR(void){ - UBD_SER_USART.DATA.reg = outWord[1]; // tx the next word, - UBD_SER_USART.INTENCLR.reg = SERCOM_USART_INTENCLR_DRE; // clear this interrupt - UBD_SER_USART.INTENSET.reg = SERCOM_USART_INTENSET_TXC; // now watch transmit complete -} - -void SERCOM1_1_Handler(void){ - ucBusDrop->txcISR(); -} - -void UCBus_Drop::txcISR(void){ - UBD_SER_USART.INTFLAG.bit.TXC = 1; // clear the flag by writing 1 - UBD_SER_USART.INTENCLR.reg = SERCOM_USART_INTENCLR_TXC; // turn off the interrupt - UBD_DRIVER_DISABLE; // turn off the driver, - //DEBUGPIN_TOGGLE; -} - -// -------------------------------------------------------- ASYNC API - -boolean UCBus_Drop::ctr_a(void){ - if(inBufferALen > 0){ - return true; - } else { - return false; - } -} - -boolean UCBus_Drop::ctr_b(void){ - if(inBufferBLen > 0){ - return true; - } else { - return false; - } -} - -size_t UCBus_Drop::read_a(uint8_t *dest){ - if(!ctr_a()) return 0; - NVIC_DisableIRQ(SERCOM1_2_IRQn); - // copy out, irq disabled, TODO safety on missing an interrupt in this case?? clock jitter? - memcpy(dest, inBufferA, inBufferALen); - size_t len = inBufferALen; - inBufferALen = 0; - inBufferARp = 0; - NVIC_EnableIRQ(SERCOM1_2_IRQn); - return len; -} - -size_t UCBus_Drop::read_b(uint8_t *dest){ - if(!ctr_b()) return 0; - NVIC_DisableIRQ(SERCOM1_2_IRQn); - memcpy(dest, inBufferB, inBufferBLen); - size_t len = inBufferBLen; - inBufferBLen = 0; - inBufferBRp = 0; - NVIC_EnableIRQ(SERCOM1_2_IRQn); - return len; -} - -boolean UCBus_Drop::cts(void){ - if(outBufferLen > 0){ - return false; - } else { - return true; - } -} - -void UCBus_Drop::transmit(uint8_t *data, uint16_t len){ - if(!cts()) return; - size_t encLen = cobsEncode(data, len, outBuffer); - outBufferLen = encLen; - outBufferRp = 0; -} \ No newline at end of file diff --git a/firmware/osape-smoothieroll-drop-stepper/src/drivers/ucbus_drop.h b/firmware/osape-smoothieroll-drop-stepper/src/drivers/ucbus_drop.h deleted file mode 100644 index de1d55e..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/drivers/ucbus_drop.h +++ /dev/null @@ -1,123 +0,0 @@ -/* -osap/drivers/ucbus_head.h - -beginnings of a uart-based clock / bus combo protocol - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo -projects. Copyright is retained and must be preserved. The work is provided as -is; no warranty is provided, and users accept all liability. -*/ - -#ifndef UCBUS_DROP_H_ -#define UCBUS_DROP_H_ - -#include <arduino.h> - -#include "indicators.h" -#include "dip_ucbus_config.h" -#include "peripheral_nums.h" -#include "utils/syserror.h" -#include "utils/cobs.h" - -#define UBD_SER_USART SERCOM1->USART -#define UBD_SERCOM_CLK SERCOM1_GCLK_ID_CORE -#define UBD_GCLKNUM_PICK 7 -#define UBD_COMPORT PORT->Group[0] -#define UBD_TXPIN 16 // x-0 -#define UBD_TXBM (uint32_t)(1 << UBD_TXPIN) -#define UBD_RXPIN 18 // x-2 -#define UBD_RXBM (uint32_t)(1 << UBD_RXPIN) -#define UBD_RXPO 2 -#define UBD_TXPERIPHERAL PERIPHERAL_C -#define UBD_RXPERIPHERAL PERIPHERAL_C - -// baud bb baud -// 63019 for a very safe 115200 -// 54351 for a go-karting 512000 -// 43690 for a trotting pace of 1MHz -// 21845 for the E30 2MHz -// 0 for max-speed 3MHz -#define UBD_BAUD_VAL 0 - -#define UBD_DE_PIN 16 // driver output enable: set HI to enable, LO to tri-state the driver -#define UBD_DE_BM (uint32_t)(1 << UBD_DE_PIN) -#define UBD_DE_PORT PORT->Group[1] -#define UBD_DRIVER_ENABLE UBD_DE_PORT.OUTSET.reg = UBD_DE_BM -#define UBD_DRIVER_DISABLE UBD_DE_PORT.OUTCLR.reg = UBD_DE_BM -#define UBD_RE_PIN 19 // receiver output enable, set LO to enable the RO, set HI to tri-state RO -#define UBD_RE_BM (uint32_t)(1 << UBD_RE_PIN) -#define UBD_RE_PORT PORT->Group[0] -#define UBD_TE_PIN 17 // termination enable, drive LO to enable to internal termination resistor, HI to disable -#define UBD_TE_BM (uint32_t)(1 << UBD_TE_PIN) -#define UBD_TE_PORT PORT->Group[0] - -#define UBD_BUFSIZE 1024 - -#define UBD_CLOCKRESET 15 - -#define UB_AK_GOTOPOS 91 -#define UB_AK_SETPOS 92 -#define UB_AK_SETRPM 93 - -class UCBus_Drop { - private: - // singleton-ness - static UCBus_Drop* instance; - // timing, - volatile uint64_t timeBlink = 0; - uint16_t blinkTime = 10000; - // input buffer & word - volatile uint8_t inWord[2]; - volatile uint8_t inHeader; - volatile uint8_t inByte; - volatile boolean lastWordAHadToken = false; - uint8_t inBufferA[UBD_BUFSIZE]; - volatile uint16_t inBufferARp = 0; - volatile uint16_t inBufferALen = 0; // writes at terminal zero, - volatile boolean lastWordBHadToken = false; - uint8_t inBufferB[UBD_BUFSIZE]; - volatile uint16_t inBufferBRp = 0; - volatile uint16_t inBufferBLen = 0; - // output, - volatile uint8_t outWord[2]; - volatile uint8_t outHeader; - volatile uint8_t outByte; - uint8_t outBuffer[UBD_BUFSIZE]; - volatile uint16_t outBufferRp = 0; - volatile uint16_t outBufferLen = 0; - const uint8_t headerMask = 0b00111111; - const uint8_t dropIdMask = 0b00001111; - const uint8_t tokenWord = 0b00100000; - const uint8_t noTokenWord = 0b00000000; - public: - UCBus_Drop(); - static UCBus_Drop* getInstance(void); - // available time count, - volatile uint16_t timeTick = 0; - // isrs - void rxISR(void); - void dreISR(void); - void txcISR(void); - // handlers - void onRxISR(void); - void onPacketARx(void); - //void onPacketBRx(void); - // our physical bus address, - volatile uint8_t id = 0; - // the api, eh - void init(boolean useDipPick, uint8_t ID); - boolean ctr_a(void); // return true if RX complete / buffer ready - boolean ctr_b(void); - size_t read_a(uint8_t *dest); // ship les bytos - size_t read_b(uint8_t *dest); - boolean cts(void); // true if tx buffer empty, - void transmit(uint8_t *data, uint16_t len); -}; - -extern UCBus_Drop* ucBusDrop; - -#endif \ No newline at end of file diff --git a/firmware/osape-smoothieroll-drop-stepper/src/main.cpp b/firmware/osape-smoothieroll-drop-stepper/src/main.cpp index f2090c5..658b290 100644 --- a/firmware/osape-smoothieroll-drop-stepper/src/main.cpp +++ b/firmware/osape-smoothieroll-drop-stepper/src/main.cpp @@ -1,29 +1,12 @@ #include <Arduino.h> #include "drivers/indicators.h" -#include "utils/cobs.h" -#include "osap/osap.h" - -OSAP* osap = new OSAP("stepper motor drop"); - -#include "drivers/ucbus_drop.h" #include "drivers/step_a4950.h" +#include "osape/osap/osap.h" +#include "osape/osap/vport_ucbus_drop.h" -union chunk_float32 { - uint8_t bytes[4]; - float f; -}; - -union chunk_float64 { - uint8_t bytes[8]; - double f; -}; - -// C_SCALE -// 1: DACs go 0->512 (of 4096, peak current is 1.6A at 4096): 0.2A -// 2: DACs go 0->1024, -// ... -// 8: DACs go full width +OSAP* osap = new OSAP("stepper motor drop"); +VPort_UCBus_Drop* vPortUcBusDrop = new VPort_UCBus_Drop(); // clank cz: // Z: Bus Drop 5, Axis Pick 2, Invert ?, SPU 1386.6666667 @@ -32,13 +15,10 @@ union chunk_float64 { // YR: Bus Drop 2, Invert false // X: Bus Drop 3, Invert false -#define BUS_DROP 3 -#define IS_LAST_DROP false - -#define AXIS_PICK 0 // Z: 2, Y: 1, X: 0 +#define AXIS_PICK 0 // E: 3Z: 2, Y: 1, X: 0 #define AXIS_INVERT false // Z: ?, YL: ?, YR: ?, X: ? #define SPU 320.0F //1386.6666667F // always posiive! z: 3200, xy: 400, clank-cz: xy: 320 -#define C_SCALE 0.3F // 0-1, floating +#define C_SCALE 0.4F // 0-1, floating #define TICKS_PER_PACKET 20.0F void setup() { @@ -50,13 +30,19 @@ void setup() { DEBUG4PIN_SETUP; // osap osap->description = "remote stepper drop"; - // bus - ucBusDrop->init(IS_LAST_DROP, BUS_DROP); + osap->addVPort(vPortUcBusDrop); // stepper stepper_hw->init(AXIS_INVERT, C_SCALE); } -uint8_t bChPck[64]; +// have available, +// stepper_hw->setCurrent(currentChunks[AXIS_PICK].f); + +void loop() { + osap->loop(); + stepper_hw->dacRefresh(); +} // end loop + volatile float current_floating_pos = 0.0F; volatile int32_t current_step_pos = 0; @@ -67,55 +53,6 @@ volatile float move_counter = 0.0F; volatile boolean setBlock = false; -void loop() { - DEBUG2PIN_TOGGLE; - osap->loop(); - stepper_hw->dacRefresh(); - // do packet B grab / handle - if(ucBusDrop->ctr_b()){ - uint16_t len = ucBusDrop->read_b(bChPck); - uint16_t ptr = 0; - switch(bChPck[ptr]){ - case AK_SETCURRENT: { - // get currents - ptr ++; - chunk_float32 currentChunks[3]; - currentChunks[0] = { .bytes = { bChPck[ptr ++], bChPck[ptr ++], bChPck[ptr ++], bChPck[ptr ++] } }; - currentChunks[1] = { .bytes = { bChPck[ptr ++], bChPck[ptr ++], bChPck[ptr ++], bChPck[ptr ++] } }; - currentChunks[2] = { .bytes = { bChPck[ptr ++], bChPck[ptr ++], bChPck[ptr ++], bChPck[ptr ++] } }; - // set current - stepper_hw->setCurrent(currentChunks[AXIS_PICK].f); - break; - } - default: - // noop, - break; - } - } -} // end loop - -void UCBus_Drop::onRxISR(void){ - if(setBlock) return; - //DEBUG2PIN_TOGGLE; - move_counter += vel; - boolean move_check = (move_counter > 1.0F); - //DEBUG2PIN_TOGGLE; - if(move_check){ - move_counter -= 1.0F; - if(delta_steps == 0){ - // nothing - } else { - //DEBUG1PIN_TOGGLE; - stepper_hw->step(); - delta_steps --; - if(stepper_hw->getDir()){ - current_step_pos ++; - } else { - current_step_pos --; - } - } - } -} void UCBus_Drop::onPacketARx(void){ if(setBlock) return; @@ -183,6 +120,29 @@ void UCBus_Drop::onPacketARx(void){ //DEBUG2PIN_OFF; } -void OSAP::handleAppPacket(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t pwp){ - vp->clearPacket(pwp); +void UCBus_Drop::onRxISR(void){ + if(setBlock) return; + //DEBUG2PIN_TOGGLE; + move_counter += vel; + boolean move_check = (move_counter > 1.0F); + //DEBUG2PIN_TOGGLE; + if(move_check){ + move_counter -= 1.0F; + if(delta_steps == 0){ + // nothing + } else { + //DEBUG1PIN_TOGGLE; + stepper_hw->step(); + delta_steps --; + if(stepper_hw->getDir()){ + current_step_pos ++; + } else { + current_step_pos --; + } + } + } +} + +void OSAP::handleAppPacket(uint8_t *pck, uint16_t ptr, pckm_t* pckm){ + pckm->vpa->clear(pckm->location); } diff --git a/firmware/osape-smoothieroll-drop-stepper/src/osap/osap.cpp b/firmware/osape-smoothieroll-drop-stepper/src/osap/osap.cpp deleted file mode 100644 index 4b4499c..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/osap/osap.cpp +++ /dev/null @@ -1,487 +0,0 @@ -/* -osap/osap.cpp - -virtual network node - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#include "osap.h" - -uint8_t ringFrame[1028]; - -OSAP::OSAP(String nodeName){ - name = nodeName; -} - -boolean OSAP::addVPort(VPort* vPort){ - if(_numVPorts > OSAP_MAX_VPORTS){ - return false; - } else { - vPort->init(); - _vPorts[_numVPorts ++] = vPort; - return true; - } -} - -void OSAP::forward(uint8_t *pck, uint16_t pl, uint16_t ptr, VPort *vp, uint8_t vpi, uint8_t pwp){ - sysError("NO FWD CODE YET"); - vp->clearPacket(pwp); -} - -void OSAP::write77(uint8_t *pck, VPort *vp){ - uint16_t one = 1; - pck[0] = PK_PPACK; // the '77' - uint16_t bufSpace = vp->getBufSpace(); - ts_writeUint16(bufSpace, pck, &one); - vp->lastRXBufferSpaceTransmitted = bufSpace; - vp->rxSinceTx = 0; -} - -// packet to read from, response to write into, write pointer, maximum response length -// assumes header won't be longer than received max seg length, if it arrived ... -// ptr = DK_x, ptr - 5 = PK_DEST, ptr - 6 = PK_PTR -boolean OSAP::formatResponseHeader(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, uint16_t checksum, VPort *vp, uint16_t vpi){ - // sanity check, this should be pingreq key - // sysError("FRH pck[ptr]: " + String(pck[ptr])); - // buf[(*ptr) ++] = val & 255 - // pck like: - // [rptr] [rend] [ptr] - // [77:3][dep0][e1][e2][e3][pk_ptr][pk_dest][acksegsize:2][checksum:2][dkey-req] - // response (will be) like: - // [wptr] - // [ptr] - // [77:3][dep0][pk_ptr][p3][p2][p1][pk_dest][acksegsize:2][checksum:2][dkey-res] - // ptr here will always indicate end of the header, - // leaves space until pck[3] for the 77-ack, which will write in later on, - // to do this, we read forwarding steps from e1 (incrementing read-ptr) - // and write in tail-to-head, (decrementing write ptr) - uint16_t wptr = ptr - 5; // to beginning of dest, segsize, checksum block - _res[wptr ++] = PK_DEST; - ts_writeUint16(segsize, _res, &wptr); - ts_writeUint16(checksum, _res, &wptr); - wptr -= 5; // back to start of this block, - // now find rptr beginning, - uint16_t rptr = 3; // departure port was trailing 77, - switch(pck[rptr]){ // walk to e1, ignoring original departure information - case PK_PORTF_KEY: - rptr += PK_PORTF_INC; - break; - case PK_BUSF_KEY: - rptr += PK_BUSF_INC; - break; - case PK_BUSB_KEY: - rptr += PK_BUSB_INC; - break; - default: - sysError("nonreq departure key on reverse route, bailing"); - return false; - } - // end switch, now pck[rptr] is at port-type-key of next fwd instruction - // walk rptr forwards, wptr backwards, copying in forwarding segments, max. 16 hops - uint16_t rend = ptr - 6; // read-end per static pck-at-dest end block: 6 for checksum(2) acksegsize(2), dest and ptr - for(uint8_t h = 0; h < 16; h ++){ - if(rptr >= rend){ // terminate when walking past end, - break; - } - switch(pck[rptr]){ - case PK_PORTF_KEY: - wptr -= PK_PORTF_INC; - for(uint8_t i = 0; i < PK_PORTF_INC; i ++){ - _res[wptr + i] = pck[rptr ++]; - } - break; - case PK_BUSF_KEY: - case PK_BUSB_KEY: - wptr -= PK_BUSF_INC; - for(uint8_t i = 0; i < PK_BUSF_INC; i ++){ - _res[wptr + i] = pck[rptr ++]; - } - default: - sysError("rptr: " + String(rptr) + " key here: " + String(pck[rptr])); - sysError("couldn't reverse this path"); - return false; - } - } - // following route-copy-in, - // TODO mod this for busses, - wptr -= 4; - _res[wptr ++] = PK_PORTF_KEY; /// write in departure key type, - ts_writeUint16(vpi, _res, &wptr); // write in departure port, - _res[wptr ++] = PK_PTR; // ptr follows departure key, - // to check, wptr should now be at 7: for 77(3), departure(3:portf), ptr(1) - if(wptr != 7){ // wptr != 7 - sysError("bad response header write"); - return false; - } else { - return true; - } -} - -/* -await osap.query(nextRoute, 'name', 'numVPorts') -await osap.query(nextRoute, 'vport', np, 'name', 'portTypeKey', 'portStatus', 'maxSegLength') -*/ - -void OSAP::writeQueryDown(uint16_t *wptr){ - sysError("QUERYDOWN"); - _res[(*wptr) ++] = EP_ERRKEY; - _res[(*wptr) ++] = EP_ERRKEY_QUERYDOWN; -} - -void OSAP::writeEmpty(uint16_t *wptr){ - sysError("EMPTY"); - _res[(*wptr) ++] = EP_ERRKEY; - _res[(*wptr) ++] = EP_ERRKEY_EMPTY; -} - -// queries for ahn vport, -void OSAP::readRequestVPort(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t rptr, uint16_t *wptr, uint16_t segsize, VPort* vp){ - // could be terminal, could read into endpoints (input / output) of the vport, - for(uint8_t i = 0; i < 16; i ++){ - if(rptr >= pl){ - return; - } - if(*wptr > segsize){ - sysError("QUERYDOWN wptr: " + String(*wptr) + " segsize: " + String(segsize)); - *wptr = ptr; - writeQueryDown(wptr); - return; - } - switch(pck[rptr]){ - case EP_NUMINPUTS: - _res[(*wptr) ++] = EP_NUMINPUTS; - ts_writeUint16(0, _res, wptr); // TODO: vports can have inputs / outputs, - rptr ++; - break; - case EP_NUMOUTPUTS: - _res[(*wptr) ++] = EP_NUMOUTPUTS; - ts_writeUint16(0, _res, wptr); - rptr ++; - break; - case EP_INPUT: - case EP_OUTPUT: - writeEmpty(wptr); // ATM, these just empty - and then return, further args would be for dive - return; - case EP_NAME: - _res[(*wptr) ++] = EP_NAME; - ts_writeString(vp->name, _res, wptr); - rptr ++; - break; - case EP_DESCRIPTION: - _res[(*wptr) ++] = EP_DESCRIPTION; - ts_writeString(vp->description, _res, wptr); - rptr ++; - break; - case EP_PORTTYPEKEY: - _res[(*wptr) ++] = EP_PORTTYPEKEY; // TODO for busses - _res[(*wptr) ++] = vp->portTypeKey; - rptr ++; - break; - case EP_MAXSEGLENGTH: - _res[(*wptr) ++] = EP_MAXSEGLENGTH; - ts_writeUint32(vp->maxSegLength, _res, wptr); - rptr ++; - break; - case EP_PORTSTATUS: - _res[(*wptr) ++] = EP_PORTSTATUS; - ts_writeBoolean(vp->status, _res, wptr); - rptr ++; - break; - case EP_PORTBUFSPACE: - _res[(*wptr) ++] = EP_PORTBUFSPACE; - ts_writeUint16(vp->getBufSpace(), _res, wptr); - rptr ++; - break; - case EP_PORTBUFSIZE: - _res[(*wptr) ++] = EP_PORTBUFSIZE; - ts_writeUint16(vp->getBufSize(), _res, wptr); - rptr ++; - break; - default: - writeEmpty(wptr); - return; - } - } -} - -void OSAP::handleReadRequest(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t pwp){ - if(vp->cts()){ - // resp. code, - // readptr, - uint16_t rptr = ptr + 1; // this will pass the RREQ and ID bytes, next is first query key - uint16_t wptr = ptr; - _res[wptr ++] = DK_RRES; - _res[wptr ++] = pck[rptr ++]; - _res[wptr ++] = pck[rptr ++]; - // read items, - // ok, walk those keys - uint16_t indice = 0; - for(uint8_t i = 0; i < 16; i ++){ - if(rptr >= pl){ - goto endwalk; - } - if(wptr > segsize){ - sysError("QUERYDOWN wptr: " + String(wptr) + " segsize: " + String(segsize)); - wptr = ptr; - writeQueryDown(&wptr); - goto endwalk; - } - switch(pck[rptr]){ - // first up, handle dives which downselect the tree - case EP_VPORT: - rptr ++; - ts_readUint16(&indice, pck, &rptr); - if(indice < _numVPorts){ - _res[wptr ++] = EP_VPORT; - ts_writeUint16(indice, _res, &wptr); - readRequestVPort(pck, pl, ptr, rptr, &wptr, segsize, _vPorts[indice]); - } else { - writeEmpty(&wptr); - } - goto endwalk; - case EP_VMODULE: - writeEmpty(&wptr); - goto endwalk; - // for reading any top-level item, - case EP_NUMVPORTS: - _res[wptr ++] = EP_NUMVPORTS; - ts_writeUint16(_numVPorts, _res, &wptr); - rptr ++; - break; - case EP_NUMVMODULES: - _res[wptr ++] = EP_NUMVMODULES; - ts_writeUint16(_numVModules, _res, &wptr); - rptr ++; - break; - case EP_NAME: - _res[wptr ++] = EP_NAME; - ts_writeString(name, _res, &wptr); - rptr ++; - break; - case EP_DESCRIPTION: - _res[wptr ++] = EP_DESCRIPTION; - ts_writeString(description, _res, &wptr); - rptr ++; - break; - // the default: unclear keys nullify entire response - default: - writeEmpty(&wptr); - goto endwalk; - } // end 1st switch - } - endwalk: ; - //sysError("QUERY ENDWALK, ptr: " + String(ptr) + " wptr: " + String(wptr)); - if(formatResponseHeader(pck, pl, ptr, segsize, wptr - ptr, vp, vpi)){ - vp->clearPacket(pwp); - write77(_res, vp); - vp->sendPacket(_res, wptr); - vp->decrimentRecipBufSpace(); - } else { - sysError("bad response format"); - vp->clearPacket(pwp); - } - } else { - vp->clearPacket(pwp); - } -} - -// pck[ptr] == DK_PINGREQ -void OSAP::handlePingRequest(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t pwp){ - if(vp->cts()){ // resp. path is clear, can write resp. and ship it - // the reversed header will be *the same length* as the received header, - // which was from 0-ptr! - this is great news, we can say: - uint16_t wptr = ptr; // start writing here, leaves room for the header, - _res[wptr ++] = DK_PINGRES; // write in whatever the response is, here just the ping-res key and id - _res[wptr ++] = pck[ptr + 1]; - _res[wptr ++] = pck[ptr + 2]; - // this'll be the 'std' response formatting codes, - // formatResponseHeader doesn't need the _res, that's baked in, and it writes 0-ptr, - // since we wrote into _res following ptr, (header lengths identical), this is safe, - if(formatResponseHeader(pck, pl, ptr, segsize, 3, vp, vpi)){ // write the header: this goes _resp[3] -> _resp[ptr] - vp->clearPacket(pwp); // can now rm the packet, have gleaned all we need from it, - write77(_res, vp); // and *after* rm'ing it, report open space _resp[0] -> _resp[3]; - vp->sendPacket(_res, wptr); // this fn' call should copy-out of our buffer - vp->decrimentRecipBufSpace(); - } else { - sysError("bad response format"); - vp->clearPacket(pwp); - } - } else { - vp->clearPacket(pwp); - } -} - -// write and send ahn reply out, -void OSAP::appReply(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t *reply, uint16_t rl){ - uint16_t wptr = ptr; - for(uint16_t i = 0; i < rl; i ++){ - _res[wptr ++] = reply[i]; - } - if(formatResponseHeader(pck, pl, ptr, segsize, rl, vp, vpi)){ - write77(_res, vp); - vp->sendPacket(_res, wptr); - vp->decrimentRecipBufSpace(); - } else { - sysError("bad response format"); - } -} - -// frame: the buffer, ptr: the location of the ptr (ack or pack), -// vp: port received on, fwp: frame-write-ptr, -// so vp->frames[fwp] = frame, though that isn't exposed here -void OSAP::instructionSwitch(uint8_t *pck, uint16_t pl, uint16_t ptr, VPort *vp, uint8_t vpi, uint8_t pwp){ - // we must *do* something, and (ideally) pop this thing, - switch(pck[ptr]){ - case PK_PORTF_KEY: - case PK_BUSF_KEY: - case PK_BUSB_KEY: - forward(pck, pl, ptr, vp, vpi, pwp); - break; - case PK_DEST: { - ptr ++; // walk past dest key, - uint16_t segsize = 0; - uint16_t checksum = 0; - ts_readUint16(&segsize, pck, &ptr); - ts_readUint16(&checksum, pck, &ptr); - if(checksum != pl - ptr){ - sysError("bad checksum, count: " + String(pl - ptr) + " checksum: " + String(checksum)); - vp->clearPacket(pwp); - } else { - switch(pck[ptr]){ - case DK_APP: - handleAppPacket(pck, pl, ptr, segsize, vp, vpi, pwp); - break; - case DK_PINGREQ: - handlePingRequest(pck, pl, ptr, segsize, vp, vpi, pwp); - break; - case DK_RREQ: - handleReadRequest(pck, pl, ptr, segsize, vp, vpi, pwp); - break; - break; - case DK_WREQ: // no writing yet, - case DK_PINGRES: // not issuing pings from embedded, shouldn't have deal w/ their responses - case DK_RRES: // not issuing requests from embedded, same - case DK_WRES: // not issuing write requests from embedded, again - sysError("WREQ or RES received in embedded, popping"); - vp->clearPacket(pwp); - break; - default: - sysError("non-recognized destination key, popping"); - vp->clearPacket(pwp); - break; - } - } - } - break; - default: - // packet is unrecognized, - sysError("unrecognized instruction key"); - vp->clearPacket(pwp); - break; - } -} - -void OSAP::loop(){ - /* - Also a note - the vp->getFrame(); (which is called often in the loop) doesn't have to be a virtual f. - VPorts can have private \_frames** ptrs-to, and when we start up a vport class, - point that at some statically allocated heap. - also, set a \_numFrames and ahn \_writePtrs*. - */ - /* - another note - this was measured around 25us (long!) - so it would be *tite* if that coule be decreased, especially in recognizing the no-op cases, - where execution could be very - very - small. - */ - unsigned long pat = 0; // packet arrival time - VPort* vp; // vp of vports - unsigned long now = millis(); - // pull one frame per loop per port, - // TODO: can increase speed by pulling more frames per loop ?? - for(uint8_t p = 0; p < _numVPorts; p ++){ - vp = _vPorts[p]; - vp->loop(); // affordance to run phy code, - for(uint8_t t = 0; t < 4; t ++){ // count # of packets to process per port per turn - uint8_t* pck; // the packet we are handling - uint16_t pl = 0; // length of that packet - uint8_t pwp = 0; // packet write pointer: where it was, to write-back clearance - vp->getPacket(&pck, &pl, &pwp, &pat); // gimme the bytes - if(pl > 0){ // have length, will try, - // check prune stale, - if(pat + OSAP_STALETIMEOUT < now){ - //this untested, but should work, yeah? - //sysError("prune stale message on " + String(vp->name)); - vp->clearPacket(pwp); - continue; - } - // check / handle pck - uint16_t ptr = 0; - // new rcrbx? - if(pck[ptr] == PK_PPACK){ - ptr ++; - uint16_t rcrxs; - ts_readUint16(&rcrxs, pck, &ptr); - vp->setRecipRxBufSpace(rcrxs); - } - // anything else? - if(ptr < pl){ - // walk through for instruction, - for(uint8_t i = 0; i < 16; i ++){ - switch(pck[ptr]){ - case PK_PTR: - instructionSwitch(pck, pl, ptr + 1, vp, p, pwp); - goto endWalk; - case PK_PORTF_KEY: // previous instructions, walk over, - ptr += PK_PORTF_INC; - break; - case PK_BUSF_KEY: - ptr += PK_BUSF_INC; - break; - case PK_BUSB_KEY: - ptr += PK_BUSF_INC; - break; - case PK_LLERR: - // someone forwarded us an err-escape, - // we are kind of helpless to help, just escp. - vp->clearPacket(pwp); - goto endWalk; - default: - sysError("bad walk for ptr: key " + String(pck[ptr]) + " at: " + String(ptr)); - vp->clearPacket(pwp); - goto endWalk; - } // end switch - } // end loop for ptr walk, - } else { - // that was just the rcrbx then, - vp->clearPacket(pwp); - } - } else { - break; - } // no frames in this port, - // end of this-port-scan, - endWalk: ; - } // end up-to-8-packets-per-turn - } // end loop over ports (handling rx) - // loop for keepalive conditions, - for(uint8_t p = 0; p < _numVPorts; p ++){ - vp = _vPorts[p]; - // check if needs to tx keepalive, - uint16_t currentRXBufferSpace = vp->getBufSpace(); - if(currentRXBufferSpace > vp->lastRXBufferSpaceTransmitted || vp->lastTxTime + OSAP_TXKEEPALIVEINTERVAL < now){ - // has open space not reported, or needs to ping for port keepalive - if(vp->cts()){ - write77(_res, vp); - vp->sendPacket(_res, 3); - vp->decrimentRecipBufSpace(); - } - } - } // end loop over ports (keepalive) -} \ No newline at end of file diff --git a/firmware/osape-smoothieroll-drop-stepper/src/osap/osap.h b/firmware/osape-smoothieroll-drop-stepper/src/osap/osap.h deleted file mode 100644 index 5242ba0..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/osap/osap.h +++ /dev/null @@ -1,60 +0,0 @@ -/* -osap/osap.h - -virtual network node - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#ifndef OSAP_H_ -#define OSAP_H_ - -#include <arduino.h> -#include "ts.h" -#include "vport.h" -#include "./drivers/indicators.h" -#include "./utils/cobs.h" - -#define OSAP_MAX_VPORTS 16 -#define RES_LENGTH 2048 -#define OSAP_STALETIMEOUT 600 -#define OSAP_TXKEEPALIVEINTERVAL 300 - -class OSAP { -private: - // yonder ports, - VPort* _vPorts[16]; - uint8_t _numVPorts = 0; - // yither vmodules - uint8_t _numVModules = 0; - // dishing output, temp write buffer - uint8_t _res[RES_LENGTH]; -public: - OSAP(String nodeName); - // props - String name; - String description = "undescribed osap node"; - // fns - boolean addVPort(VPort* vPort); - void forward(uint8_t *pck, uint16_t pl, uint16_t ptr, VPort *vp, uint8_t vpi, uint8_t pwp); - void write77(uint8_t *pck, VPort *vp); - boolean formatResponseHeader(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, uint16_t checksum, VPort *vp, uint16_t vpi); - void writeQueryDown(uint16_t *wptr); - void writeEmpty(uint16_t *wptr); - void readRequestVPort(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t rptr, uint16_t *wptr, uint16_t segsize, VPort* vp); - void handleReadRequest(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t pwp); - void handlePingRequest(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t pwp); - void appReply(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t *reply, uint16_t rl); - void instructionSwitch(uint8_t *pck, uint16_t pl, uint16_t ptr, VPort *vp, uint8_t vpi, uint8_t pwp); - void loop(); - // the handoff, - void handleAppPacket(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t pwp); -}; - -#endif diff --git a/firmware/osape-smoothieroll-drop-stepper/src/osap/ts.cpp b/firmware/osape-smoothieroll-drop-stepper/src/osap/ts.cpp deleted file mode 100644 index 1a39900..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/osap/ts.cpp +++ /dev/null @@ -1,64 +0,0 @@ -/* -osap/ts.cpp - -typeset / keys / writing / reading - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#include "ts.h" - -void ts_writeBoolean(boolean val, unsigned char *buf, uint16_t *ptr){ - if(val){ - buf[(*ptr) ++] = 1; - } else { - buf[(*ptr) ++] = 0; - } -} - -void ts_readUint16(uint16_t *val, unsigned char *buf, uint16_t *ptr){ - *val = buf[(*ptr) + 1] << 8 | buf[(*ptr)]; - *ptr += 2; -} - -void ts_writeUint16(uint16_t val, unsigned char *buf, uint16_t *ptr){ - buf[(*ptr) ++] = val & 255; - buf[(*ptr) ++] = (val >> 8) & 255; -} - -void ts_writeUint32(uint32_t val, unsigned char *buf, uint16_t *ptr){ - buf[(*ptr) ++] = val & 255; - buf[(*ptr) ++] = (val >> 8) & 255; - buf[(*ptr) ++] = (val >> 16) & 255; - buf[(*ptr) ++] = (val >> 24) & 255; -} - -union chunk_float32 { - uint8_t bytes[4]; - float f; -}; - -void ts_writeFloat32(float val, volatile unsigned char *buf, uint16_t *ptr){ - chunk_float32 chunk; - chunk.f = val; - buf[(*ptr) ++] = chunk.bytes[0]; - buf[(*ptr) ++] = chunk.bytes[1]; - buf[(*ptr) ++] = chunk.bytes[2]; - buf[(*ptr) ++] = chunk.bytes[3]; -} - -void ts_writeString(String val, unsigned char *buf, uint16_t *ptr){ - uint32_t len = val.length(); - buf[(*ptr) ++] = len & 255; - buf[(*ptr) ++] = (len >> 8) & 255; - buf[(*ptr) ++] = (len >> 16) & 255; - buf[(*ptr) ++] = (len >> 24) & 255; - val.getBytes(&buf[*ptr], len + 1); - *ptr += len; -} diff --git a/firmware/osape-smoothieroll-drop-stepper/src/osap/ts.h b/firmware/osape-smoothieroll-drop-stepper/src/osap/ts.h deleted file mode 100644 index 1029171..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/osap/ts.h +++ /dev/null @@ -1,100 +0,0 @@ -/* -osap/ts.h - -typeset / keys / writing / reading - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#include <arduino.h> - -// -------------------------------------------------------- Routing (Packet) Keys - -#define PK_PPACK 77 -#define PK_PTR 88 -#define PK_DEST 99 -#define PK_LLERR 44 -#define PK_PORTF_KEY 11 -#define PK_PORTF_INC 3 -#define PK_BUSF_KEY 12 -#define PK_BUSF_INC 5 -#define PK_BUSB_KEY 14 -#define PK_BUSB_INC 5 - -// -------------------------------------------------------- Destination Keys (arrival layer) - -#define DK_APP 100 // application codes, go to -> main -#define DK_PINGREQ 101 // ping request -#define DK_PINGRES 102 // ping reply -#define DK_RREQ 111 // read request -#define DK_RRES 112 // read response -#define DK_WREQ 113 // write request -#define DK_WRES 114 // write response - -// -------------------------------------------------------- Application Keys - -#define AK_OK 100 -#define AK_ERR 200 -#define AK_GOTOPOS 101 // goto pos -#define AK_SETPOS 102 // set position to xyz -#define AK_SETCURRENT 103 // set currents xyz -#define AK_SETRPM 105 // set spindle -#define AK_QUERYMOVING 111 // is moving? -#define AK_QUERYPOS 112 // get current pos -#define AK_QUERYQUEUELEN 113 // current queue len? - -// -------------------------------------------------------- MVC Endpoints - -#define EP_ERRKEY 150 -#define EP_ERRKEY_QUERYDOWN 151 -#define EP_ERRKEY_EMPTY 153 -#define EP_ERRKEY_UNCLEAR 154 - -#define EP_NAME 171 -#define EP_DESCRIPTION 172 - -#define EP_NUMVPORTS 181 -#define EP_VPORT 182 -#define EP_PORTTYPEKEY 183 -#define EP_MAXSEGLENGTH 184 -#define EP_PORTSTATUS 185 -#define EP_PORTBUFSPACE 186 -#define EP_PORTBUFSIZE 187 - -#define EP_NUMVMODULES 201 -#define EP_VMODULE 202 - -#define EP_NUMINPUTS 211 -#define EP_INPUT 212 - -#define EP_NUMOUTPUTS 221 -#define EP_OUTPUT 222 - -#define EP_TYPE 231 -#define EP_VALUE 232 -#define EP_STATUS 233 - -#define EP_NUMROUES 243 -#define EP_ROUTE 235 - -// ... etc, later - -// -------------------------------------------------------- Reading and Writing - -void ts_writeBoolean(boolean val, unsigned char *buf, uint16_t *ptr); - -void ts_readUint16(uint16_t *val, uint8_t *buf, uint16_t *ptr); - -void ts_writeUint16(uint16_t val, unsigned char *buf, uint16_t *ptr); - -void ts_writeUint32(uint32_t val, unsigned char *buf, uint16_t *ptr); - -void ts_writeFloat32(float val, volatile unsigned char *buf, uint16_t *ptr); - -void ts_writeString(String val, unsigned char *buf, uint16_t *ptr); diff --git a/firmware/osape-smoothieroll-drop-stepper/src/osap/vport.cpp b/firmware/osape-smoothieroll-drop-stepper/src/osap/vport.cpp deleted file mode 100644 index e064991..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/osap/vport.cpp +++ /dev/null @@ -1,40 +0,0 @@ -/* -osap/vport.cpp - -virtual port, p2p - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#include "vport.h" - -VPort::VPort(String vPortName){ - name = vPortName; -} - -void VPort::setRecipRxBufSpace(uint16_t len){ - _recipRxBufSpace = len; -} - -void VPort::decrimentRecipBufSpace(void){ - if(_recipRxBufSpace < 1){ - _recipRxBufSpace = 0; - } else { - _recipRxBufSpace --; - } - lastTxTime = millis(); -} - -boolean VPort::cts(void){ - if(_recipRxBufSpace > 0 && status){ - return true; - } else { - return false; - } -} diff --git a/firmware/osape-smoothieroll-drop-stepper/src/osap/vport.h b/firmware/osape-smoothieroll-drop-stepper/src/osap/vport.h deleted file mode 100644 index b705e91..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/osap/vport.h +++ /dev/null @@ -1,52 +0,0 @@ -/* -osap/vport.h - -virtual port, p2p - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#ifndef VPORT_H_ -#define VPORT_H_ - -#include <arduino.h> -#include "./utils/syserror.h" - -class VPort { -private: - uint16_t _recipRxBufSpace = 1; -public: - VPort(String vPortName); - String name; - String description = "undescribed vport"; - uint8_t portTypeKey = PK_PORTF_KEY; - uint16_t maxSegLength = 0; - virtual void init(void) = 0; - virtual void loop(void) = 0; - // keepalive log - uint16_t lastRXBufferSpaceTransmitted = 0; - uint16_t rxSinceTx = 0; // debugging: count packets received since last spaces txd - unsigned long lastTxTime = 0; - // handling incoming frames, - virtual void getPacket(uint8_t** pck, uint16_t* pl, uint8_t* pwp, unsigned long* pat) = 0; - // *be sure* that getPacket sets pl to zero if no packet emerges, - // consider making boolean return, true if packet? - virtual void clearPacket(uint8_t pwp) = 0; - virtual uint16_t getBufSpace(void) = 0; - virtual uint16_t getBufSize(void) = 0; - // dish outgoing frames, and check if open to send them? - boolean status = false; // open / closed-ness -> OSAP can set, VP can set. - virtual boolean cts(void); // is a connection established & is the reciprocal buffer nonzero? - virtual void sendPacket(uint8_t* pck, uint16_t pl) = 0; // take this frame, copying out of the buffer I pass you - // internal state, - void setRecipRxBufSpace(uint16_t len); - void decrimentRecipBufSpace(void); -}; - -#endif diff --git a/firmware/osape-smoothieroll-drop-stepper/src/osap/vport_usbserial.cpp b/firmware/osape-smoothieroll-drop-stepper/src/osap/vport_usbserial.cpp deleted file mode 100644 index ddbc9fd..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/osap/vport_usbserial.cpp +++ /dev/null @@ -1,141 +0,0 @@ -/* -osap/vport.cpp - -virtual port, p2p - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#include "vport_usbserial.h" - -VPort_USBSerial::VPort_USBSerial() -:VPort("usb serial"){ - description = "vport wrap on arduino Serial object"; - // ok, just calls super-constructor -} - -void VPort_USBSerial::init(void){ - // set frame lengths to zero, - for(uint8_t i = 0; i < VPUSB_NUM_SPACES; i ++){ - _pl[i] = 0; - } - Serial.begin(9600); -} - -void VPort_USBSerial::loop(void){ - while(Serial.available()){ - _encodedPacket[_pwp][_bwp] = Serial.read(); - if(_encodedPacket[_pwp][_bwp] == 0){ - rxSinceTx ++; - // sysError(String(getBufSpace()) + " " + String(_bwp)); - // indicate we recv'd zero - // CLKLIGHT_TOGGLE; - // decode from rx-ing frame to interface frame, - status = true; // re-assert open whenever received packet incoming - size_t dcl = cobsDecode(_encodedPacket[_pwp], _bwp, _packet[_pwp]); - _pl[_pwp] = dcl; // this frame now available, has this length, - _packetArrivalTimes[_pwp] = millis(); // time this thing arrived - // reset byte write pointer - _bwp = 0; - // find next empty frame, that's new frame write pointer - boolean set = false; - for(uint8_t i = 0; i <= VPUSB_NUM_SPACES; i ++){ - _pwp ++; - if(_pwp >= VPUSB_NUM_SPACES){ _pwp = 0; } - if(_pl[_pwp] == 0){ // if this frame-write-ptr hasn't been set to occupied, - set = true; - break; // this _pwp is next empty frame, - } - } - if(!set){ - sysError("no empty slot for serial read, protocol error!"); - uint16_t apparentSpace = getBufSpace(); - sysError("reads: " + String(apparentSpace)); - sysError("last txd recip: " + String(lastRXBufferSpaceTransmitted)); - sysError("rxd since last tx: " + String(rxSinceTx)); - sysError(String(_pl[0])); - sysError(String(_pl[1])); - sysError(String(_pl[2])); - sysError(String(_pl[3])); - sysError(String(_pl[4])); - sysError(String(_pl[5])); - sysError(String(_pl[6])); - sysError(String(_pl[7])); - sysError(String(_pl[8])); - delay(5000); - } - } else { - _bwp ++; - } - } -} - -void VPort_USBSerial::getPacket(uint8_t **pck, uint16_t *pl, uint8_t *pwp, unsigned long* pat){ - uint8_t p = _lastPacket; // the last one we delivered, - boolean retrieved = false; - for(uint8_t i = 0; i <= VPUSB_NUM_SPACES; i ++){ - p ++; - if(p >= VPUSB_NUM_SPACES) { p = 0; } - if(_pl[p] > 0){ // this is an occupied packet, deliver that - *pck = _packet[p]; // same, is this passing the ptr, yeah? - *pl = _pl[p]; // I *think* this is how we do this in c? - *pwp = p; // packet write pointer ? the indice of the packet, to clear - *pat = _packetArrivalTimes[p]; - _lastPacket = p; - retrieved = true; - break; - } - } - if(!retrieved){ - *pl = 0; - } -} - -void VPort_USBSerial::clearPacket(uint8_t pwp){ - // frame consumed, clear to write-in, - //sysError("clear " + String(pwp)); - _pl[pwp] = 0; - _packetArrivalTimes[pwp] = 0; -} - -uint16_t VPort_USBSerial::getBufSize(void){ - return VPUSB_NUM_SPACES; -} - -uint16_t VPort_USBSerial::getBufSpace(void){ - uint16_t sum = 0; - // any zero-length frame is not full, - for(uint16_t i = 0; i < VPUSB_NUM_SPACES; i++){ - if(_pl[i] == 0){ - sum ++; - } - } - // but one is being written into, - //if(_bwp > 0){ - sum --; - //} - // if we're very full this might wrap / invert, so - if(sum > VPUSB_NUM_SPACES){ - sum = 0; - } - // arrivaderci - return sum; -} - -void VPort_USBSerial::sendPacket(uint8_t *pck, uint16_t pl){ - size_t encLen = cobsEncode(pck, pl, _encodedOut); - if(Serial.availableForWrite()){ - //DEBUG1PIN_ON; - Serial.write(_encodedOut, encLen); - Serial.flush(); - //DEBUG1PIN_OFF; - } else { - sysError("NOT AVAILABLE"); - } -} diff --git a/firmware/osape-smoothieroll-drop-stepper/src/osap/vport_usbserial.h b/firmware/osape-smoothieroll-drop-stepper/src/osap/vport_usbserial.h deleted file mode 100644 index 4a72d1c..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/osap/vport_usbserial.h +++ /dev/null @@ -1,57 +0,0 @@ -/* -osap/vport_usbserial.h - -virtual port, p2p - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#ifndef VPORT_USBSERIAL_H_ -#define VPORT_USBSERIAL_H_ - -#include <arduino.h> -#include "vport.h" -#include "./utils/cobs.h" -#include "./drivers/indicators.h" - -#define VPUSB_NUM_SPACES 64 -#define VPUSB_SPACE_SIZE 1028 - -class VPort_USBSerial : public VPort { -private: - // unfortunately, looks like we need to write-in to temp, - // and decode out of that - uint8_t _encodedPacket[VPUSB_NUM_SPACES][VPUSB_SPACE_SIZE]; - uint8_t _packet[VPUSB_NUM_SPACES][VPUSB_SPACE_SIZE]; - volatile uint16_t _pl[VPUSB_NUM_SPACES]; - unsigned long _packetArrivalTimes[VPUSB_NUM_SPACES]; - uint8_t _pwp = 0; // packet write pointer, - uint16_t _bwp = 0; // byte write pointer, - uint8_t _lastPacket = 0; // last packet written into - // outgoing cobs-copy-in, - uint8_t _encodedOut[VPUSB_SPACE_SIZE]; - // this is just for debug, - uint8_t _ringPacket[VPUSB_SPACE_SIZE]; -public: - VPort_USBSerial(); - // props - uint16_t maxSegLength = VPUSB_SPACE_SIZE - 6; - // code - void init(void); - void loop(void); - // handle incoming frames - void getPacket(uint8_t** pck, uint16_t* pl, uint8_t* pwp, unsigned long* pat); - void clearPacket(uint8_t pwp); - uint16_t getBufSize(void); - uint16_t getBufSpace(void); - // dish outgoing frames, and check if cts - void sendPacket(uint8_t *pck, uint16_t pl); -}; - -#endif diff --git a/firmware/osape-smoothieroll-drop-stepper/src/osape b/firmware/osape-smoothieroll-drop-stepper/src/osape new file mode 160000 index 0000000..294a5da --- /dev/null +++ b/firmware/osape-smoothieroll-drop-stepper/src/osape @@ -0,0 +1 @@ +Subproject commit 294a5dac3711b23a9cf2386355954c6610c450a3 diff --git a/firmware/osape-smoothieroll-drop-stepper/src/utils/clocks_d51_module.cpp b/firmware/osape-smoothieroll-drop-stepper/src/utils/clocks_d51_module.cpp deleted file mode 100644 index 317c403..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/utils/clocks_d51_module.cpp +++ /dev/null @@ -1,115 +0,0 @@ -/* -utils/clocks_d51_module.cpp - -clock utilities for the D51 as moduuularized, adhoc! -i.e. xtals present on module board or otherwise - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo -projects. Copyright is retained and must be preserved. The work is provided as -is; no warranty is provided, and users accept all liability. -*/ - -#include "clocks_d51_module.h" - -D51_Clock_Boss* D51_Clock_Boss::instance = 0; - -D51_Clock_Boss* D51_Clock_Boss::getInstance(void){ - if(instance == 0){ - instance = new D51_Clock_Boss(); - } - return instance; -} - -D51_Clock_Boss* d51_clock_boss = D51_Clock_Boss::getInstance(); - -D51_Clock_Boss::D51_Clock_Boss(){} - -void D51_Clock_Boss::setup_16mhz_xtal(void){ - if(mhz_xtal_is_setup) return; // already done, - // let's make a clock w/ that xtal: - OSCCTRL->XOSCCTRL[0].bit.RUNSTDBY = 0; - OSCCTRL->XOSCCTRL[0].bit.XTALEN = 1; - // set oscillator current.. - OSCCTRL->XOSCCTRL[0].reg |= OSCCTRL_XOSCCTRL_IMULT(4) | OSCCTRL_XOSCCTRL_IPTAT(3); - OSCCTRL->XOSCCTRL[0].reg |= OSCCTRL_XOSCCTRL_STARTUP(5); - OSCCTRL->XOSCCTRL[0].bit.ENALC = 1; - OSCCTRL->XOSCCTRL[0].bit.ENABLE = 1; - // make the peripheral clock available on this ch - GCLK->GENCTRL[MHZ_XTAL_GCLK_NUM].reg = GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_XOSC0) | GCLK_GENCTRL_GENEN; // GCLK_GENCTRL_SRC_DFLL - while (GCLK->SYNCBUSY.reg & GCLK_SYNCBUSY_GENCTRL(MHZ_XTAL_GCLK_NUM)){ - //DEBUG2PIN_TOGGLE; - }; - mhz_xtal_is_setup = true; -} - -void D51_Clock_Boss::start_100kHz_ticker_tc0(void){ - setup_16mhz_xtal(); - // ok - TC0->COUNT32.CTRLA.bit.ENABLE = 0; - TC1->COUNT32.CTRLA.bit.ENABLE = 0; - // unmask clocks - MCLK->APBAMASK.reg |= MCLK_APBAMASK_TC0 | MCLK_APBAMASK_TC1; - // ok, clock to these channels... - GCLK->PCHCTRL[TC0_GCLK_ID].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(d51_clock_boss->mhz_xtal_gclk_num); - GCLK->PCHCTRL[TC1_GCLK_ID].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(d51_clock_boss->mhz_xtal_gclk_num); - // turn them ooon... - TC0->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_PRESCSYNC_PRESC | TC_CTRLA_PRESCALER_DIV2 | TC_CTRLA_CAPTEN0; - TC1->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_PRESCSYNC_PRESC | TC_CTRLA_PRESCALER_DIV2 | TC_CTRLA_CAPTEN0; - // going to set this up to count at some time, we will tune - // that freq. with - TC0->COUNT32.WAVE.reg = TC_WAVE_WAVEGEN_MFRQ; - TC1->COUNT32.WAVE.reg = TC_WAVE_WAVEGEN_MFRQ; - // allow interrupt to trigger on this event (overflow) - TC0->COUNT32.INTENSET.bit.MC0 = 1; - TC0->COUNT32.INTENSET.bit.MC1 = 1; - // set the period, - while (TC0->COUNT32.SYNCBUSY.bit.CC0); - TC0->COUNT32.CC[0].reg = 80; // at DIV2, 240 for 10us ('realtime') (with - // DFLL), 80 for 10us (with XTAL 16MHZ) - // 400 for 50us, - // enable, sync for enable write - while (TC0->COUNT32.SYNCBUSY.bit.ENABLE); - TC0->COUNT32.CTRLA.bit.ENABLE = 1; - while (TC0->COUNT32.SYNCBUSY.bit.ENABLE); - TC1->COUNT32.CTRLA.bit.ENABLE = 1; - // enable the IRQ - NVIC_EnableIRQ(TC0_IRQn); -} - -void D51_Clock_Boss::start_100kHz_ticker_tc2(void){ - setup_16mhz_xtal(); - // ok - TC2->COUNT32.CTRLA.bit.ENABLE = 0; - TC3->COUNT32.CTRLA.bit.ENABLE = 0; - // unmask clocks - MCLK->APBBMASK.reg |= MCLK_APBBMASK_TC2 | MCLK_APBBMASK_TC3; - // ok, clock to these channels... - GCLK->PCHCTRL[TC2_GCLK_ID].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(d51_clock_boss->mhz_xtal_gclk_num); - GCLK->PCHCTRL[TC3_GCLK_ID].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(d51_clock_boss->mhz_xtal_gclk_num); - // turn them ooon... - TC2->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_PRESCSYNC_PRESC | TC_CTRLA_PRESCALER_DIV2 | TC_CTRLA_CAPTEN0; - TC3->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_PRESCSYNC_PRESC | TC_CTRLA_PRESCALER_DIV2 | TC_CTRLA_CAPTEN0; - // going to set this up to count at some time, we will tune - // that freq. with - TC2->COUNT32.WAVE.reg = TC_WAVE_WAVEGEN_MFRQ; - TC3->COUNT32.WAVE.reg = TC_WAVE_WAVEGEN_MFRQ; - // allow interrupt to trigger on this event (overflow) - TC2->COUNT32.INTENSET.bit.MC0 = 1; - TC2->COUNT32.INTENSET.bit.MC1 = 1; - // set the period, - while (TC2->COUNT32.SYNCBUSY.bit.CC0); - TC2->COUNT32.CC[0].reg = 80; // at DIV2, 240 for 10us ('realtime') (with - // DFLL), 80 for 10us (with XTAL 16MHZ) - // 400 for 50us, - // enable, sync for enable write - while (TC2->COUNT32.SYNCBUSY.bit.ENABLE); - TC2->COUNT32.CTRLA.bit.ENABLE = 1; - while (TC2->COUNT32.SYNCBUSY.bit.ENABLE); - TC3->COUNT32.CTRLA.bit.ENABLE = 1; - // enable the IRQ - NVIC_EnableIRQ(TC2_IRQn); -} \ No newline at end of file diff --git a/firmware/osape-smoothieroll-drop-stepper/src/utils/clocks_d51_module.h b/firmware/osape-smoothieroll-drop-stepper/src/utils/clocks_d51_module.h deleted file mode 100644 index 084141e..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/utils/clocks_d51_module.h +++ /dev/null @@ -1,43 +0,0 @@ -/* -utils/clocks_d51_module.h - -clock utilities for the D51 as moduuularized, adhoc! -i.e. xtals present on module board or otherwise - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo -projects. Copyright is retained and must be preserved. The work is provided as -is; no warranty is provided, and users accept all liability. -*/ - -#ifndef CLOCKS_D51_MODULE_H_ -#define CLOCKS_D51_MODULE_H_ - -#include <Arduino.h> - -#include "../drivers/indicators.h" - -#define MHZ_XTAL_GCLK_NUM 9 - -class D51_Clock_Boss { - private: - static D51_Clock_Boss* instance; - public: - D51_Clock_Boss(); - static D51_Clock_Boss* getInstance(void); - // xtal - volatile boolean mhz_xtal_is_setup = false; - uint32_t mhz_xtal_gclk_num = 9; - void setup_16mhz_xtal(void); - // builds 100kHz clock on TC0 or TC2 - // todo: tell these fns a frequency, - void start_100kHz_ticker_tc0(void); - void start_100kHz_ticker_tc2(void); -}; - -extern D51_Clock_Boss* d51_clock_boss; - -#endif \ No newline at end of file diff --git a/firmware/osape-smoothieroll-drop-stepper/src/utils/cobs.cpp b/firmware/osape-smoothieroll-drop-stepper/src/utils/cobs.cpp deleted file mode 100644 index a2d7378..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/utils/cobs.cpp +++ /dev/null @@ -1,60 +0,0 @@ -/* -utils/cobs.cpp - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#include "cobs.h" -// str8 crib from -// https://en.wikipedia.org/wiki/Consistent_Overhead_Byte_Stuffing - -#define StartBlock() (code_ptr = dst++, code = 1) -#define FinishBlock() (*code_ptr = code) - -size_t cobsEncode(uint8_t *ptr, size_t length, uint8_t *dst){ - const uint8_t *start = dst, *end = ptr + length; - uint8_t code, *code_ptr; /* Where to insert the leading count */ - - StartBlock(); - while (ptr < end) { - if (code != 0xFF) { - uint8_t c = *ptr++; - if (c != 0) { - *dst++ = c; - code++; - continue; - } - } - FinishBlock(); - StartBlock(); - } - FinishBlock(); - // write the actual zero, - *dst++ = 0; - return dst - start; -} - -size_t cobsDecode(uint8_t *ptr, size_t length, uint8_t *dst) -{ - const uint8_t *start = dst, *end = ptr + length; - uint8_t code = 0xFF, copy = 0; - - for (; ptr < end; copy--) { - if (copy != 0) { - *dst++ = *ptr++; - } else { - if (code != 0xFF) - *dst++ = 0; - copy = code = *ptr++; - if (code == 0) - break; /* Source length too long */ - } - } - return dst - start; -} diff --git a/firmware/osape-smoothieroll-drop-stepper/src/utils/cobs.h b/firmware/osape-smoothieroll-drop-stepper/src/utils/cobs.h deleted file mode 100644 index a9e5874..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/utils/cobs.h +++ /dev/null @@ -1,24 +0,0 @@ -/* -utils/cobs.h - -consistent overhead byte stuffing implementation - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#ifndef UTIL_COBS_H_ -#define UTIL_COBS_H_ - -#include <arduino.h> - -size_t cobsEncode(uint8_t *src, size_t len, uint8_t *dest); - -size_t cobsDecode(uint8_t *src, size_t len, uint8_t *dest); - -#endif diff --git a/firmware/osape-smoothieroll-drop-stepper/src/utils/syserror.cpp b/firmware/osape-smoothieroll-drop-stepper/src/utils/syserror.cpp deleted file mode 100644 index a2473fe..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/utils/syserror.cpp +++ /dev/null @@ -1,38 +0,0 @@ -#include "syserror.h" - -uint8_t errBuf[1028]; -uint8_t errEncoded[1028]; - -/* -boolean writeString(unsigned char* dest, uint16_t* dptr, String msg){ - uint16_t len = msg.length(); - dest[(*dptr) ++] = TS_STRING_KEY; - writeLenBytes(dest, dptr, len); - msg.getBytes(dest, len + 1); - return true; -} - -boolean writeLenBytes(unsigned char* dest, uint16_t* dptr, uint16_t len){ - dest[(*dptr) ++] = len; - dest[(*dptr) ++] = (len >> 8) & 255; - return true; -} -*/ - -// config-your-own-ll-escape-hatch -void sysError(String msg){ - // whatever you want, - //ERRLIGHT_ON; - uint32_t len = msg.length(); - errBuf[0] = PK_LLERR; // the ll-errmsg-key - errBuf[1] = len & 255; - errBuf[2] = (len >> 8) & 255; - errBuf[3] = (len >> 16) & 255; - errBuf[4] = (len >> 24) & 255; - msg.getBytes(&errBuf[5], len + 1); - size_t ecl = cobsEncode(errBuf, len + 5, errEncoded); - if(Serial.availableForWrite() > (int64_t)ecl){ - Serial.write(errEncoded, ecl); - Serial.flush(); - } -} diff --git a/firmware/osape-smoothieroll-drop-stepper/src/utils/syserror.h b/firmware/osape-smoothieroll-drop-stepper/src/utils/syserror.h deleted file mode 100644 index b421cc2..0000000 --- a/firmware/osape-smoothieroll-drop-stepper/src/utils/syserror.h +++ /dev/null @@ -1,11 +0,0 @@ -#ifndef SYSERROR_H_ -#define SYSERROR_H_ - -#include <arduino.h> -#include "./drivers/indicators.h" -#include "./utils/cobs.h" -#include "./osap/ts.h" - -void sysError(String msg); - -#endif -- GitLab