From ecd5e0e8b3e7186b106175d2b9850ac10c32db44 Mon Sep 17 00:00:00 2001
From: Jake Read <jakerobertread@gmail.com>
Date: Thu, 22 Aug 2024 12:13:38 -0400
Subject: [PATCH] new fw for dually-hbridge, and basically working scripto

---
 .../firmware/dual-hbridge/.gitignore          |   5 +
 .../dual-hbridge/.vscode/extensions.json      |  10 +
 .../dual-hbridge/.vscode/settings.json        |   5 +
 .../firmware/dual-hbridge/COBSUSBSerial.cpp   |  89 ----
 .../firmware/dual-hbridge/COBSUSBSerial.h     |  37 --
 .../firmware/dual-hbridge/include/README      |  39 ++
 .../firmware/dual-hbridge/lib/README          |  46 ++
 .../firmware/dual-hbridge/platformio.ini      |  22 +
 .../dual-hbridge/serializationUtes.cpp        |  14 -
 .../firmware/dual-hbridge/serializationUtes.h |  15 -
 .../firmware/dual-hbridge/simple-hbridge.ino  | 129 ------
 .../firmware/dual-hbridge/src/main.cpp        | 142 ++++++
 .../firmware/dual-hbridge/src/maxl/fxp.cpp    |  30 ++
 .../firmware/dual-hbridge/src/maxl/fxp.h      |  16 +
 .../firmware/dual-hbridge/src/maxl/maxl.cpp   | 172 ++++++++
 .../firmware/dual-hbridge/src/maxl/maxl.h     |  57 +++
 .../{ => src/motion}/fixedPointUtes.cpp       |   0
 .../{ => src/motion}/fixedPointUtes.h         |   0
 .../dual-hbridge/{ => src/motion}/lutgen.js   |   0
 .../src/motion/motionStateMachine.cpp         | 237 ++++++++++
 .../src/motion/motionStateMachine.h           |  34 ++
 .../dual-hbridge/src/motion/stepperDriver.cpp | 147 +++++++
 .../dual-hbridge/src/motion/stepperDriver.h   |  35 ++
 .../dual-hbridge/src/motion/stepperLUT.h      |  76 ++++
 .../firmware/dual-hbridge/src/osap/.gitignore |   1 +
 .../firmware/dual-hbridge/src/osap/LICENSE.md |  19 +
 .../firmware/dual-hbridge/src/osap/README.md  |   7 +
 .../dual-hbridge/src/osap/library.properties  |  10 +
 .../dual-hbridge/src/osap/src/LICENSE.md      |  19 +
 .../src/osap/src/discovery/netresponder.cpp   | 182 ++++++++
 .../src/osap/src/discovery/netresponder.h     |  15 +
 .../link_uart_cobs_crc16.h                    | 152 +++++++
 .../gateway_integrations/link_usb_cdc_cobs.h  | 112 +++++
 .../gateway_integrations/link_utils}/cobs.cpp |   0
 .../gateway_integrations/link_utils}/cobs.h   |   0
 .../link_utils/crc16_ccitt.cpp                |  32 ++
 .../link_utils/crc16_ccitt.h                  |   9 +
 .../firmware/dual-hbridge/src/osap/src/osap.h |  61 +++
 .../dual-hbridge/src/osap/src/osap_config.h   |  59 +++
 .../src/osap/src/packets/packets.cpp          | 290 +++++++++++++
 .../src/osap/src/packets/packets.h            | 102 +++++
 .../src/osap/src/packets/routes.cpp           | 103 +++++
 .../src/osap/src/packets/routes.h             |  64 +++
 .../src/presentation/mothballed/port_bare.cpp |  32 ++
 .../src/presentation/mothballed/port_bare.h   |  35 ++
 .../mothballed/port_deviceNames.cpp           | 104 +++++
 .../mothballed/port_deviceNames.h             |  35 ++
 .../mothballed/port_messageEscape.cpp         |  58 +++
 .../mothballed/port_messageEscape.h           |  31 ++
 .../src/presentation/mothballed/port_pipe.cpp |  45 ++
 .../src/presentation/mothballed/port_pipe.h   |  24 +
 .../src/osap/src/presentation/port_rpc.h      | 177 ++++++++
 .../osap/src/presentation/port_rpc_helpers.h  | 120 +++++
 .../src/osap/src/runtime/runtime.cpp          | 409 ++++++++++++++++++
 .../src/osap/src/runtime/runtime.h            | 148 +++++++
 .../src/osap/src/structure/links.cpp          |  56 +++
 .../src/osap/src/structure/links.h            |  53 +++
 .../src/osap/src/structure/ports.cpp          |  64 +++
 .../src/osap/src/structure/ports.h            |  49 +++
 .../src/transport/sequential_receiver.cpp     |  27 ++
 .../osap/src/transport/sequential_receiver.h  |  84 ++++
 .../dual-hbridge/src/osap/src/utils/debug.h   |  23 +
 .../src/osap/src/utils/fp_clock_utils.cpp     |  50 +++
 .../src/osap/src/utils/fp_clock_utils.h       |  16 +
 .../dual-hbridge/src/osap/src/utils/keys.h    |  70 +++
 .../src/osap/src/utils/micros_64.cpp          |  19 +
 .../src/osap/src/utils/micros_64.h            |   8 +
 .../src/osap/src/utils/platform_flash.cpp     |  51 +++
 .../src/osap/src/utils/platform_flash.h       |  13 +
 .../osap/src/utils/random_sequence_gen.cpp    |  17 +
 .../src/osap/src/utils/random_sequence_gen.h  |   8 +
 .../dual-hbridge/src/osap/src/utils/serdes.h  | 356 +++++++++++++++
 .../src/osap/src/utils/serdes_keys.h          | 198 +++++++++
 .../firmware/dual-hbridge/test/README         |  11 +
 .../firmware/maxl-stepper/src/main.cpp        |  20 -
 new_shit/python/boilerplate/main.py           |   7 -
 .../maxl/__pycache__/core.cpython-312.pyc     | Bin 14188 -> 14319 bytes
 new_shit/python/maxl/core.py                  |  15 +-
 .../__pycache__/dual_h_bridge.cpython-312.pyc | Bin 0 -> 3545 bytes
 .../__pycache__/maxl_stepper.cpython-312.pyc  | Bin 4430 -> 4460 bytes
 .../sketchy_machine_motion.cpython-312.pyc    | Bin 8965 -> 9443 bytes
 new_shit/python/modules/dual_h_bridge.py      |  44 ++
 new_shit/python/modules/maxl_stepper.py       |   8 +-
 .../python/modules/sketchy_machine_motion.py  |  17 +-
 .../__pycache__/module_author.cpython-312.pyc | Bin 6579 -> 6526 bytes
 new_shit/python/sketchy.py                    |  64 +--
 .../svg/__pycache__/svg_tools.cpython-312.pyc | Bin 5610 -> 5610 bytes
 87 files changed, 4793 insertions(+), 367 deletions(-)
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/.gitignore
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/.vscode/extensions.json
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/.vscode/settings.json
 delete mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/COBSUSBSerial.cpp
 delete mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/COBSUSBSerial.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/include/README
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/lib/README
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/platformio.ini
 delete mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/serializationUtes.cpp
 delete mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/serializationUtes.h
 delete mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/simple-hbridge.ino
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/main.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/fxp.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/fxp.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/maxl.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/maxl.h
 rename new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/{ => src/motion}/fixedPointUtes.cpp (100%)
 rename new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/{ => src/motion}/fixedPointUtes.h (100%)
 rename new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/{ => src/motion}/lutgen.js (100%)
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/motionStateMachine.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/motionStateMachine.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/stepperDriver.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/stepperDriver.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/stepperLUT.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/.gitignore
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/LICENSE.md
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/README.md
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/library.properties
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/LICENSE.md
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/discovery/netresponder.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/discovery/netresponder.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_uart_cobs_crc16.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_usb_cdc_cobs.h
 rename new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/{ => src/osap/src/gateway_integrations/link_utils}/cobs.cpp (100%)
 rename new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/{ => src/osap/src/gateway_integrations/link_utils}/cobs.h (100%)
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_utils/crc16_ccitt.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_utils/crc16_ccitt.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/osap.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/osap_config.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/packets.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/packets.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/routes.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/routes.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_bare.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_bare.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_deviceNames.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_deviceNames.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_messageEscape.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_messageEscape.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_pipe.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_pipe.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/port_rpc.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/port_rpc_helpers.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/runtime/runtime.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/runtime/runtime.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/links.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/links.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/ports.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/ports.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/transport/sequential_receiver.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/transport/sequential_receiver.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/debug.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/fp_clock_utils.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/fp_clock_utils.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/keys.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/micros_64.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/micros_64.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/platform_flash.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/platform_flash.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/random_sequence_gen.cpp
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/random_sequence_gen.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/serdes.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/serdes_keys.h
 create mode 100644 new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/test/README
 create mode 100644 new_shit/python/modules/__pycache__/dual_h_bridge.cpython-312.pyc
 create mode 100644 new_shit/python/modules/dual_h_bridge.py

diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/.gitignore b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/.gitignore
new file mode 100644
index 0000000..89cc49c
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/.gitignore
@@ -0,0 +1,5 @@
+.pio
+.vscode/.browse.c_cpp.db*
+.vscode/c_cpp_properties.json
+.vscode/launch.json
+.vscode/ipch
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/.vscode/extensions.json b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/.vscode/extensions.json
new file mode 100644
index 0000000..080e70d
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/.vscode/extensions.json
@@ -0,0 +1,10 @@
+{
+    // See http://go.microsoft.com/fwlink/?LinkId=827846
+    // for the documentation about the extensions.json format
+    "recommendations": [
+        "platformio.platformio-ide"
+    ],
+    "unwantedRecommendations": [
+        "ms-vscode.cpptools-extension-pack"
+    ]
+}
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/.vscode/settings.json b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/.vscode/settings.json
new file mode 100644
index 0000000..1428c38
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/.vscode/settings.json
@@ -0,0 +1,5 @@
+{
+    "files.associations": {
+        "random": "cpp"
+    }
+}
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/COBSUSBSerial.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/COBSUSBSerial.cpp
deleted file mode 100644
index 03939cc..0000000
--- a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/COBSUSBSerial.cpp
+++ /dev/null
@@ -1,89 +0,0 @@
-// link ! 
-// TODO: pls use nanocobs, for encode- and decode-in-place, to save big (!) memory 
-// on new link layer... to fit into D11s... 
-
-#include "COBSUSBSerial.h"
-#include "cobs.h"
-
-
-#if defined(ARDUINO_ARCH_RP2040) || defined(ARDUINO_ARCH_RP2040)
-COBSUSBSerial::COBSUSBSerial(SerialUSB* _usbcdc){
-  usbcdc = _usbcdc;
-}
-#else 
-COBSUSBSerial::COBSUSBSerial(Serial_* _usbcdc){
-  usbcdc = _usbcdc;
-}
-#endif 
-
-void COBSUSBSerial::begin(void){
-  usbcdc->begin(9600);
-}
-
-void COBSUSBSerial::loop(void){
-  // check RX side:
-  // while data & not-full, 
-  while(usbcdc->available() && rxBufferLen == 0){
-    rxBuffer[rxBufferWp ++] = usbcdc->read();
-    if(rxBuffer[rxBufferWp - 1] == 0){
-      // decoding in place should always work: COBS doesn't revisit bytes 
-      // encoding in place would be a different trick, and would require the use of 
-      // nanocobs from this lad: https://github.com/charlesnicholson/nanocobs 
-      size_t len = cobsDecode(rxBuffer, 255, rxBuffer);
-      // now we are with-packet, set length and reset write pointer 
-      // len includes the trailing 0, rm that... 
-      rxBufferLen = len - 1; 
-      rxBufferWp = 0;
-    }
-  }
-
-  // check tx side, 
-  while(txBufferLen && usbcdc->availableForWrite()){
-    // ship a byte, 
-    usbcdc->write(txBuffer[txBufferRp ++]);
-    // if done, mark empty
-    if(txBufferRp >= txBufferLen){
-      txBufferLen = 0;
-      txBufferRp = 0;
-    }
-  }
-}
-
-size_t COBSUSBSerial::getPacket(uint8_t* dest){
-  if(rxBufferLen > 0){
-    memcpy(dest, rxBuffer, rxBufferLen);
-    size_t len = rxBufferLen;
-    rxBufferLen = 0;
-    return len;
-  } else {
-    return 0;
-  }
-}
-
-boolean COBSUSBSerial::clearToRead(void){
-  return (rxBufferLen > 0);
-}
-
-void COBSUSBSerial::send(uint8_t* packet, size_t len){
-  // ship it! blind! 
-  size_t encodedLen = cobsEncode(packet, len, txBuffer);
-  // stuff 0 byte, 
-  txBuffer[encodedLen] = 0;
-  txBufferLen = encodedLen + 1;
-  txBufferRp = 0;
-}
-
-boolean COBSUSBSerial::clearToSend(void){
-  // we're CTS if we have nothing in the outbuffer, 
-  return (txBufferLen == 0);
-}
-
-// we should do some... work with this, i.e. 
-// keepalives, to detect if other-end is open or not... 
-boolean COBSUSBSerial::isOpen(void){
-  if(usbcdc){
-    return true;
-  } else {
-    return false; 
-  }
-}
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/COBSUSBSerial.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/COBSUSBSerial.h
deleted file mode 100644
index 4c87ab9..0000000
--- a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/COBSUSBSerial.h
+++ /dev/null
@@ -1,37 +0,0 @@
-// example cobs-encoded usb-serial link 
-
-#include <Arduino.h>
-
-class COBSUSBSerial {
-  public: 
-    #if defined(ARDUINO_ARCH_RP2040) || defined(ARDUINO_ARCH_RP2040)
-    COBSUSBSerial(SerialUSB* _usbcdc);
-    #else 
-    COBSUSBSerial(Serial_* _usbcdc);
-    #endif 
-    void begin(void);
-    void loop(void);
-    // check & read,
-    boolean clearToRead(void);
-    size_t getPacket(uint8_t* dest);
-    // clear ahead?
-    boolean clearToSend(void);
-    // open at all?
-    boolean isOpen(void);
-    // transmit a packet of this length 
-    void send(uint8_t* packet, size_t len);
-  private: 
-    #if defined(ARDUINO_ARCH_RP2040) || defined(ARDUINO_ARCH_RP2040)
-    SerialUSB* usbcdc = nullptr;
-    #else 
-    Serial_* usbcdc = nullptr;
-    #endif 
-    // buffer, write pointer, length, 
-    uint8_t rxBuffer[255];
-    uint8_t rxBufferWp = 0;
-    uint8_t rxBufferLen = 0;
-    // ibid, 
-    uint8_t txBuffer[255];
-    uint8_t txBufferRp = 0;
-    uint8_t txBufferLen = 0;
-};
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/include/README b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/include/README
new file mode 100644
index 0000000..194dcd4
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/include/README
@@ -0,0 +1,39 @@
+
+This directory is intended for project header files.
+
+A header file is a file containing C declarations and macro definitions
+to be shared between several project source files. You request the use of a
+header file in your project source file (C, C++, etc) located in `src` folder
+by including it, with the C preprocessing directive `#include'.
+
+```src/main.c
+
+#include "header.h"
+
+int main (void)
+{
+ ...
+}
+```
+
+Including a header file produces the same results as copying the header file
+into each source file that needs it. Such copying would be time-consuming
+and error-prone. With a header file, the related declarations appear
+in only one place. If they need to be changed, they can be changed in one
+place, and programs that include the header file will automatically use the
+new version when next recompiled. The header file eliminates the labor of
+finding and changing all the copies as well as the risk that a failure to
+find one copy will result in inconsistencies within a program.
+
+In C, the usual convention is to give header files names that end with `.h'.
+It is most portable to use only letters, digits, dashes, and underscores in
+header file names, and at most one dot.
+
+Read more about using header files in official GCC documentation:
+
+* Include Syntax
+* Include Operation
+* Once-Only Headers
+* Computed Includes
+
+https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/lib/README b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/lib/README
new file mode 100644
index 0000000..6debab1
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/lib/README
@@ -0,0 +1,46 @@
+
+This directory is intended for project specific (private) libraries.
+PlatformIO will compile them to static libraries and link into executable file.
+
+The source code of each library should be placed in a an own separate directory
+("lib/your_library_name/[here are source files]").
+
+For example, see a structure of the following two libraries `Foo` and `Bar`:
+
+|--lib
+|  |
+|  |--Bar
+|  |  |--docs
+|  |  |--examples
+|  |  |--src
+|  |     |- Bar.c
+|  |     |- Bar.h
+|  |  |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
+|  |
+|  |--Foo
+|  |  |- Foo.c
+|  |  |- Foo.h
+|  |
+|  |- README --> THIS FILE
+|
+|- platformio.ini
+|--src
+   |- main.c
+
+and a contents of `src/main.c`:
+```
+#include <Foo.h>
+#include <Bar.h>
+
+int main (void)
+{
+  ...
+}
+
+```
+
+PlatformIO Library Dependency Finder will find automatically dependent
+libraries scanning project source files.
+
+More information about PlatformIO Library Dependency Finder
+- https://docs.platformio.org/page/librarymanager/ldf.html
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/platformio.ini b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/platformio.ini
new file mode 100644
index 0000000..9a9c2a8
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/platformio.ini
@@ -0,0 +1,22 @@
+; PlatformIO Project Configuration File
+;
+;   Build options: build flags, source filter
+;   Upload options: custom upload port, speed and extra flags
+;   Library options: dependencies, extra library storages
+;   Advanced options: extra scripting
+;
+; Please visit documentation for the other options and examples
+; https://docs.platformio.org/page/projectconf.html
+
+; [env:pico]
+; platform = raspberrypi
+; board = pico
+; framework = arduino
+
+[env:pico]
+platform = https://github.com/maxgerhardt/platform-raspberrypi.git
+board = seeed_xiao_rp2040
+framework = arduino
+
+board_build.core = earlephilhower
+board_build.f_cpu = 200000000L
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/serializationUtes.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/serializationUtes.cpp
deleted file mode 100644
index d40cd21..0000000
--- a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/serializationUtes.cpp
+++ /dev/null
@@ -1,14 +0,0 @@
-#include "serializationUtes.h"
-
-float ts_readFloat32(unsigned char* buf, uint16_t* ptr){
-  chunk_float32 chunk = { .bytes = { buf[(*ptr)], buf[(*ptr) + 1], buf[(*ptr) + 2], buf[(*ptr) + 3] } };
-  (*ptr) += 4;
-  return chunk.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) + 1] = chunk.bytes[1]; buf[(*ptr) + 2] = chunk.bytes[2]; buf[(*ptr) + 3] = chunk.bytes[3];
-  (*ptr) += 4;
-}
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/serializationUtes.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/serializationUtes.h
deleted file mode 100644
index 5549f09..0000000
--- a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/serializationUtes.h
+++ /dev/null
@@ -1,15 +0,0 @@
-#ifndef SERIALIZATION_UTES_H_
-#define SERIALIZATION_UTES_H_
-
-#include <Arduino.h>
-
-union chunk_float32 {
-  uint8_t bytes[4];
-  float f;
-};
-
-float ts_readFloat32(unsigned char* buf, uint16_t* ptr);
-
-void ts_writeFloat32(float val, volatile unsigned char* buf, uint16_t* ptr);
-
-#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/simple-hbridge.ino b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/simple-hbridge.ino
deleted file mode 100644
index 312a604..0000000
--- a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/simple-hbridge.ino
+++ /dev/null
@@ -1,129 +0,0 @@
-#include "COBSUSBSerial.h"
-#include "serializationUtes.h"
-
-// no-transport-layer dual H-Bridge
-// using the RP2040 at 200MHz 
-// using https://modular-things.github.io/modular-things/things/stepper-hbridge-xiao/
-
-#define MSG_GET_ID        7
-#define MSG_ECHO_TEST     11 
-#define MSG_SET_POWER     20
-#define MSG_GET_STATES    25
-#define MSG_ACK           31 
-#define MSG_NACK          32
-
-#define AIN1_PIN 6      // on D4
-#define AIN2_PIN 7      // on D5 
-#define BIN1_PIN 28     // on D2
-#define BIN2_PIN 4      // on D9 
-#define APWM_PIN 27     // on D1
-#define BPWM_PIN 29     // on D3 
-
-// y_motor: 1, x_bottom_motor: 2, x_top_motor: 3 
-#define MOTOR_ID 4
-
-COBSUSBSerial cobs(&Serial);
-
-float power_A = 0.f;
-float power_B = 0.f;
-
-void setPower(uint8_t* data, size_t len){
-  // should do maxAccel, maxVel, and (optionally) setPosition
-  // upstream should've though of this, so,
-  uint16_t rptr = 0;
-  float power = ts_readFloat32(data, &rptr);
-  uint8_t i = data[rptr];
-
-  if (power < 0.f) {
-    power = 0.f;
-  }
-  if (power > 1.f) {
-    power = 1.f;
-  }
-
-  if (i==0) {
-    power_A = power;
-  } else {
-    power_B = power;
-  }
-  
-  updateOutputs();
-}
-
-
-void updateOutputs() {
-  if (power_A == 0.f) {
-    digitalWrite(AIN1_PIN, LOW);
-    digitalWrite(AIN2_PIN, LOW);
-  } else {
-    digitalWrite(AIN1_PIN, HIGH);
-    digitalWrite(AIN2_PIN, LOW);
-    analogWrite(APWM_PIN, int(255*power_A));
-  }
-  if (power_B == 0.f) {
-    digitalWrite(BIN1_PIN, LOW);
-    digitalWrite(BIN2_PIN, LOW);
-  } else {
-    digitalWrite(BIN1_PIN, HIGH);
-    digitalWrite(BIN2_PIN, LOW);
-    analogWrite(BPWM_PIN, int(255*power_B));
-  }
-}
-
-
-size_t getStates(uint8_t* data, size_t len, uint8_t* reply){
-  uint16_t wptr = 0;
-  // in-fill current posn, velocity, and acceleration
-  ts_writeFloat32(power_A, reply, &wptr);
-  ts_writeFloat32(power_B, reply, &wptr);
-  // return the data length 
-  return wptr;
-}
-
-void setup() {
-  pinMode(AIN1_PIN, OUTPUT);
-  pinMode(AIN2_PIN, OUTPUT);
-  pinMode(BIN1_PIN, OUTPUT);
-  pinMode(BIN2_PIN, OUTPUT);
-  pinMode(APWM_PIN, OUTPUT);
-  pinMode(BPWM_PIN, OUTPUT);
-  // and our comms
-  cobs.begin();
-}
-
-uint8_t msg[256];
-uint8_t reply[256];
-
-void loop() {
-  // run comms
-  cobs.loop();
-  // and check for paquiats: condition is if we can 
-  // get a packet, and tx the reply
-  if(cobs.clearToRead() && cobs.clearToSend()){
-    size_t len = cobs.getPacket(msg);
-    // start a reply, 
-    size_t wptr = 0;
-    reply[wptr ++] = MSG_ACK;
-    // switch on grams,
-    switch(msg[0]){
-      case MSG_GET_ID:
-        reply[wptr ++] = MOTOR_ID;
-        break;
-      case MSG_ECHO_TEST:
-        memcpy(reply, msg, len);
-        wptr = len;
-        break;
-      case MSG_SET_POWER:
-        setPower(msg + 1, len - 1);
-        break;
-      case MSG_GET_STATES:
-        wptr += getStates(msg + 1, len - 1, reply + 1);
-        break;
-      default:
-        reply[0] = MSG_NACK;
-        break;
-    }
-    // send the reply, 
-    cobs.send(reply, wptr);
-  }
-}
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/main.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/main.cpp
new file mode 100644
index 0000000..64fcd75
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/main.cpp
@@ -0,0 +1,142 @@
+#include "osap/src/osap.h"
+#include "motion/stepperDriver.h"
+#include "maxl/maxl.h"
+
+#define PIN_ABTRANS D8
+#define PIN_YZTRANS D10
+#define PIN_LED_WD PIN_LED_G 
+#define PIN_LIMIT D0 
+
+#define AIN1_PIN 6      // on D4
+#define AIN2_PIN 7      // on D5 
+#define BIN1_PIN 28     // on D2
+#define BIN2_PIN 4      // on D9 
+#define APWM_PIN 27     // on D1
+#define BPWM_PIN 29     // on D3 
+
+void setupHBridges(void){
+  pinMode(AIN1_PIN, OUTPUT);
+  pinMode(AIN2_PIN, OUTPUT);
+  pinMode(BIN1_PIN, OUTPUT);
+  pinMode(BIN2_PIN, OUTPUT);
+  pinMode(APWM_PIN, OUTPUT);
+  pinMode(BPWM_PIN, OUTPUT);
+}
+
+void writeHBridgeOutputs(float coil_a, float coil_b){
+  if(coil_a == 0.0F){
+    digitalWrite(AIN1_PIN, LOW);
+    digitalWrite(AIN2_PIN, LOW);
+  } else if (coil_a > 0.0F){
+    digitalWrite(AIN1_PIN, HIGH);
+    digitalWrite(AIN2_PIN, LOW);
+  } else {
+    digitalWrite(AIN1_PIN, LOW);
+    digitalWrite(AIN2_PIN, HIGH);
+  }
+  analogWrite(APWM_PIN, int(255 * abs(coil_a)));
+
+  if(coil_b == 0.0F){
+    digitalWrite(BIN1_PIN, LOW);
+    digitalWrite(BIN2_PIN, LOW);
+  } else if (coil_b > 0.0F){
+    digitalWrite(BIN1_PIN, HIGH);
+    digitalWrite(BIN2_PIN, LOW);
+  } else {
+    digitalWrite(BIN1_PIN, LOW);
+    digitalWrite(BIN2_PIN, HIGH);
+  }
+  analogWrite(BPWM_PIN, int(255 * abs(coil_b)));
+}
+
+
+OSAP_Runtime osap("DualHBridge", "dual_thwapper");
+OSAP_Gateway_USBCDC_COBS<decltype(Serial)> serLink(&Serial, "usb");
+// OSAP_Gateway_UART_COBS_CRC16<decltype(Serial1)> mudLink(&Serial1, 1000000, 
+//   "backpack_mudl",
+//   PIN_YZTRANS, PIN_ABTRANS
+// );
+
+BUILD_RPC(writeHBridgeOutputs, "coil_a, coil_b", "");
+
+MAXL maxl;
+
+// maxl's api... or should we just make it a port ? 
+void maxl_setInterval(uint8_t interval){
+  maxl.setInterval(interval);
+}
+
+void maxl_addControlPoint(uint64_t timestamp, float pt, uint8_t flags){
+  maxlFlags_t _flags = { .byte = flags };
+  maxl.addControlPoint(timestamp, fxp32_16_fromFloat(pt), _flags);
+}
+
+auto maxl_getPosition(void){
+  return std::make_tuple(osap.getSystemMicroseconds(), maxl.getPosition());
+}
+
+String maxl_getErrorMessage(void){
+  return maxl.getErrorMessage();
+}
+
+BUILD_RPC(maxl_setInterval, "intervalNumBits", "");
+BUILD_RPC(maxl_addControlPoint, "time, point, flags", "");
+BUILD_RPC(maxl_getErrorMessage, "", "");
+
+BUILD_RPC(maxl_getPosition, "", "time, position");
+
+
+#define ALARM_DT_NUM 1
+#define ALARM_DT_IRQ TIMER_IRQ_1
+
+// 1khz aught to be enough for these 
+const uint32_t _delT_us = 1000;
+
+// let's get our tight loop, 
+void alarm_handler(void){
+  // the ISR 
+  hw_clear_bits(&timer_hw->intr, 1u << ALARM_DT_NUM);
+  timer_hw->alarm[ALARM_DT_NUM] = (uint32_t) (timer_hw->timerawl + _delT_us);
+
+  // get the target posn, 
+  maxl_eval_t eval = maxl.evaluate(osap.getSystemMicroseconds());
+
+  // posn is basically current value 
+  if(eval.isValid){
+    float posAsFloat = fxp32_16_toFloat(eval.pos);
+    writeHBridgeOutputs(posAsFloat, posAsFloat);
+  }
+}
+
+void alarm_begin(void){
+  // setup the hardware timer 
+  hw_set_bits(&timer_hw->inte, 1u << ALARM_DT_NUM);
+  irq_set_exclusive_handler(ALARM_DT_IRQ, alarm_handler);
+  irq_set_enabled(ALARM_DT_IRQ, true);
+  timer_hw->alarm[ALARM_DT_NUM] = (uint32_t) (timer_hw->timerawl + _delT_us);
+}
+
+
+void setup() {
+  osap.begin();
+  maxl.begin();
+  stepper_init();
+  alarm_begin();
+  pinMode(PIN_LIMIT, INPUT_PULLUP);
+  // pinMode(PIN_LIMIT, OUTPUT);
+  pinMode(PIN_LED_WD, OUTPUT);
+}
+
+
+uint32_t wdBlinkInterval = 50;
+uint32_t wdBlinkLast = 0; 
+
+void loop() {
+  osap.loop(); 
+
+  if(wdBlinkLast + wdBlinkInterval < millis()){
+    wdBlinkLast = millis();
+    digitalWrite(PIN_LED_WD, !digitalRead(PIN_LED_WD));
+  }
+}
+
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/fxp.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/fxp.cpp
new file mode 100644
index 0000000..da1211a
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/fxp.cpp
@@ -0,0 +1,30 @@
+#include "fxp.h"
+
+const int32_t fxp_scale = 16;
+const float fxp32_16_floatMax = 32000.0F;
+const float fxp32_16_floatMin = -32000.0F;
+
+// foiled again it seems, perhaps we can do decimal-part,
+// integer-parts... 
+fxp32_16_t fxp32_16_mult(fxp32_16_t a, fxp32_16_t b){
+    return ((int64_t)((int64_t)a * (int64_t)b)) >> fxp_scale;
+}
+
+fxp32_16_t fxp32_16_fromFloat(float a){
+    if(a > fxp32_16_floatMax) a = fxp32_16_floatMin;
+    if(a < fxp32_16_floatMin) a = fxp32_16_floatMin;
+    return (a * (float)(1 << fxp_scale));
+}
+
+
+float fxp32_16_toFloat(fxp32_16_t a){
+    return (float)a / (float)(1 << fxp_scale);
+}
+
+fxp32_16_t fxp32_16_fromUInt32(uint32_t a){
+    return a << fxp_scale;
+}
+
+fxp32_16_t fxp32_16_fromInt32(int32_t a){
+    return a << fxp_scale;
+}
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/fxp.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/fxp.h
new file mode 100644
index 0000000..6a88f6e
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/fxp.h
@@ -0,0 +1,16 @@
+#ifndef FXP_H_
+#define FXP_H_
+
+#include <Arduino.h>
+
+typedef int32_t fxp32_16_t;
+
+fxp32_16_t fxp32_16_mult(fxp32_16_t a, fxp32_16_t b);
+
+fxp32_16_t fxp32_16_fromFloat(float a);
+float fxp32_16_toFloat(fxp32_16_t a);
+
+fxp32_16_t fxp32_16_fromUInt32(uint32_t a);
+fxp32_16_t fxp32_16_fromInt32(int32_t a);
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/maxl.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/maxl.cpp
new file mode 100644
index 0000000..ed79b1c
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/maxl.cpp
@@ -0,0 +1,172 @@
+#include "maxl.h"
+
+void MAXL::begin(void){
+  // -------------------------------------------- queue needs some setup, 
+  for(uint8_t i = 0; i < MAXL_QUEUE_SIZE; i ++){
+    // and we link this -> next, prev <- this 
+    if(i != MAXL_QUEUE_SIZE - 1) queue[i].next = &(queue[i+1]);
+    if(i != 0) queue[i].prev = &(queue[i-1]);
+  }
+  // and the wraparound cases, 
+  queue[0].prev = &(queue[MAXL_QUEUE_SIZE - 1]);
+  queue[MAXL_QUEUE_SIZE - 1].next = &(queue[0]);
+  head = &(queue[0]);  // where to write-in, 
+  tail = &(queue[0]);  // which is ticking along... 
+}
+
+void MAXL::setInterval(uint8_t interval){
+  // would we need to update anything ?
+  intervalBitWidth = interval;
+}
+
+size_t MAXL::getQueueLength(void){
+  size_t len = 0; 
+  splinePt_t* ptr = tail;
+  for(uint8_t i = 0; i < MAXL_QUEUE_SIZE; i ++){
+    if(ptr == head) return len;
+    len ++;
+    ptr = ptr->next;
+  }
+  return len; 
+}
+
+void MAXL::addControlPoint(uint64_t timestamp, fxp32_16_t pt, maxlFlags_t flags){
+  if (getQueueLength() + 2 > MAXL_QUEUE_SIZE){
+    postErrorMessage("overfull");
+    return; 
+  } else if(flags.bits.isStreamStart) {
+    // reset queue on start, 
+    tail = &(queue[0]);
+    head = &(queue[0]);
+    streamActive = true; 
+    postErrorMessage("startup");
+  } else if(head->prev->time + (1 << intervalBitWidth) != timestamp){
+    // sequences need to be continuous ! 
+    postErrorMessage("missed segment, " + String((uint32_t)(head->prev->time)) + " " + String((uint32_t)(timestamp)));
+    return;
+  }
+
+  // stash it, 
+  head->time = timestamp;
+  head->pt = pt;
+  head->isLastPt = flags.bits.isStreamEnd;
+
+  // advance the head pointer, 
+  head = head->next;
+}
+
+static const fxp32_16_t one_sixth = fxp32_16_fromFloat(1.0F / 6.0F);
+static const fxp32_16_t one_half = fxp32_16_fromFloat(1.0F / 2.0F);
+static const fxp32_16_t two_thirds = fxp32_16_fromFloat(2.0F / 3.0F);
+
+maxl_eval_t MAXL::evaluate(uint64_t timestamp){
+  // noop if we're not running, 
+  if(!streamActive) return { .pos = lastPtEvaluated, .isValid = false }; 
+
+  // is queue-tail in the future?
+  if(tail->time > timestamp) return { .pos = lastPtEvaluated, .isValid = false }; 
+
+  // ok, goddamn, firstly, we flush the tail until it is one stamp's worth of time in the past, 
+  for(uint8_t i = 0; i < MAXL_QUEUE_SIZE; i ++){
+    if(getQueueLength() <= 4){
+      // this is buffer starvation, 
+      postErrorMessage("STARVED @ " + String((uint32_t)timestamp));
+      return { .pos = lastPtEvaluated, .isValid = false };
+    } else if (tail->time <= timestamp && tail->next->time <= timestamp){
+      // increment and continue fwds, 
+      tail = tail->next; 
+    } else if (tail->time <= timestamp && tail->next->time > timestamp){
+      // tail in correct position, carry on:
+      break; 
+    } else {
+      postErrorMessage("oddball time state ... "); 
+      // + String(getQueueLength()) + ", " + String((uint32_t)timestamp) + ", " + String((uint32_t)tail->time) + ", " + String((uint32_t)tail->next->time));
+      return { .pos = lastPtEvaluated, .isValid = false }; 
+    }
+  }
+
+  // handling end-of-streams, 
+  if(tail->isLastPt){
+    streamActive = false;
+    return { .pos = lastPtEvaluated, .isValid = false }; 
+  }
+
+  splinePt_t * qp0 = tail->prev;
+  splinePt_t * qp1 = tail;
+  splinePt_t * qp2 = tail->next;
+  splinePt_t * qp3 = tail->next->next;
+
+  // what of our time base ? 
+  // we have timestamp - qp1->time = microseconds-into-segment, 
+  // and 0-1 being our time-base: 10...16 bit, 
+  // if we have time-base of '10' we do no conversion, 
+  // otherwise we have to upscale (?) 
+  fxp32_16_t t = (timestamp - qp1->time) << (16 - intervalBitWidth); //fxp32_16_fromUInt32((timestamp - qp1->time) << (intervalBitWidth - 10));
+  fxp32_16_t tt = fxp32_16_mult(t, t);
+  fxp32_16_t ttt = fxp32_16_mult(tt, t);
+  // lol step one is to get the params !
+  // we do need some queue'en 
+  fxp32_16_t p0 = qp0->pt;
+  fxp32_16_t p1 = qp1->pt;
+  fxp32_16_t p2 = qp2->pt;
+  fxp32_16_t p3 = qp3->pt;
+
+  // TODO: a ... d could be evaluated just once, before we start each chunk - then we just do the last multiplications... 
+  fxp32_16_t a = fxp32_16_mult(one_sixth, p0) + fxp32_16_mult(two_thirds, p1) + fxp32_16_mult(one_sixth, p2);
+  fxp32_16_t b = - fxp32_16_mult(one_half, p0) + fxp32_16_mult(one_half, p2);
+  fxp32_16_t c = fxp32_16_mult(one_half, p0) - p1 + fxp32_16_mult(one_half, p2);
+  fxp32_16_t d = - fxp32_16_mult(one_sixth, p0) + fxp32_16_mult(one_half, p1) - fxp32_16_mult(one_half, p2) + fxp32_16_mult(one_sixth, p3);
+
+  // ... t, tt, ttt 
+  lastPtEvaluated = a + fxp32_16_mult(b, t) + fxp32_16_mult(c, tt) + fxp32_16_mult(d, ttt);
+  // postErrorMessage("t: " + String(fxp32_16_toFloat(t), 4)
+  //             + ", p0: " + String(fxp32_16_toFloat(p0)) + ", p1: " + String(fxp32_16_toFloat(p1))  + ", p2: " + String(fxp32_16_toFloat(p2)) 
+  //             + ", a: " + String(fxp32_16_toFloat(a)) // + ", b: " + String(fxp32_16_toFloat(b))
+  //             );
+
+  // postErrorMessage("t: " + String(fxp32_16_toFloat(t), 4)
+  //             + ", p0: " + String(fxp32_16_toFloat(p0)) + ", 1/6, p1: " + String(fxp32_16_toFloat(fxp32_16_mult(one_sixth, p0)), 5)
+  //             );
+
+  return { .pos = lastPtEvaluated, .isValid = true }; 
+}
+
+float MAXL::getPosition(void){
+  return fxp32_16_toFloat(lastPtEvaluated);
+}
+
+/*
+def cubic_basis(t, params):
+    p0, p1, p2, p3 = params 
+
+    tt = t * t 
+    ttt = tt * t 
+
+    a = p0 + 4 * p1 + p2 
+    b = - 3 * p0 + 3 * p2
+    c = 3 * p0 - 6 * p1 + 3 * p2
+    d = - p0 + 3 * p1 - 3 * p2 + p3
+
+    return 1/6 * (a + b * t + c * tt + d * ttt)
+
+# when we expand the 1/6 within (for less overflowey intermediate vals)
+
+a = 1/6 * p0 + 2/3 * p1 + 1/6 * p2 
+b = - 1/2 * p0 + 1/2 * p2
+c = 1/2 * p0 - p1 + 1/2 * p2
+d = - 1/6 * p0 + 1/2 * p1 - 1/2 * p2 + 1/6 * p3
+*/
+
+void MAXL::postErrorMessage(String msg){
+  _errorMessage = msg;
+  _errorFlag = true;
+}
+
+String MAXL::getErrorMessage(void){
+  if(_errorFlag){
+    _errorFlag = false;
+    return _errorMessage;
+  } else {
+    return "";
+  }
+}
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/maxl.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/maxl.h
new file mode 100644
index 0000000..fc8771c
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/maxl/maxl.h
@@ -0,0 +1,57 @@
+#ifndef MAXL_H_
+#define MAXL_H_
+
+#include <Arduino.h>
+#include "fxp.h"
+
+#define MAXL_QUEUE_SIZE 128
+
+typedef struct splinePt_t {
+  fxp32_16_t pt;
+  // microseconds 
+  uint64_t time;
+  bool isLastPt = false; 
+  splinePt_t* next;
+  splinePt_t* prev;
+} splinePt_t;
+
+union maxlFlags_t {
+    struct {
+        unsigned int isStreamStart : 1;
+        unsigned int isStreamEnd : 1;
+    } bits;
+    unsigned char byte;
+};
+
+typedef struct maxl_eval_t {
+  fxp32_16_t pos;
+  bool isValid; 
+} maxl_eval_t;
+
+class MAXL {
+  public:
+    void begin(void);
+    void setInterval(uint8_t interval);
+    void addControlPoint(uint64_t timestamp, fxp32_16_t pt, maxlFlags_t flags = { .byte = 0 });
+    maxl_eval_t evaluate(uint64_t timestamp);
+    float getPosition(void);
+    String getErrorMessage(void);
+
+  private:
+    // is num. bits for the interval period, microseconds, 
+    uint8_t intervalBitWidth = 0;
+    // streaming-or-not, and last eval'd 
+    bool streamActive = false; 
+    fxp32_16_t lastPtEvaluated = 0;
+    void postErrorMessage(String msg);
+    String _errorMessage;
+    bool _errorFlag = false; 
+    // will we need to stash pts-times ? 
+    splinePt_t queue[MAXL_QUEUE_SIZE];
+    splinePt_t* head = 0;
+    splinePt_t* tail = 0; 
+    // queue mgmt 
+    size_t getQueueLength(void);
+};  
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/fixedPointUtes.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/fixedPointUtes.cpp
similarity index 100%
rename from new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/fixedPointUtes.cpp
rename to new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/fixedPointUtes.cpp
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/fixedPointUtes.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/fixedPointUtes.h
similarity index 100%
rename from new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/fixedPointUtes.h
rename to new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/fixedPointUtes.h
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/lutgen.js b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/lutgen.js
similarity index 100%
rename from new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/lutgen.js
rename to new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/lutgen.js
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/motionStateMachine.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/motionStateMachine.cpp
new file mode 100644
index 0000000..77d6c65
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/motionStateMachine.cpp
@@ -0,0 +1,237 @@
+#include "motionStateMachine.h"
+#include "fixedPointUtes.h"
+#include "stepperDriver.h"
+
+// overlapping with the limit pin ! 
+#define PIN_DEBUG 26 
+
+#define ALARM_DT_NUM 1
+#define ALARM_DT_IRQ TIMER_IRQ_1
+
+// _delT is re-calculated when we init w/ a new microsecondsPerIntegration 
+fpint32_t           _delT = 0;
+uint32_t            _delT_us = 0;
+
+// core states (units are full steps) 
+volatile uint8_t    _mode = MOTION_MODE_VEL;    // operative _mode 
+volatile fpint64_t  _pos = 0;                   // current position (big 64)
+volatile int16_t    _phaseOffset = 0;           // related to setting posns, see _setPos() 
+volatile fpint32_t  _vel = 0;                   // current velocity 
+volatile fpint32_t  _accel = 0;                 // current acceleration 
+
+// init-once values we'll use in the integrator 
+volatile fpint32_t  _delta = 0;
+volatile fpint64_t  _posTarget = 0;             // for position control, 
+volatile fpint64_t  _dist = 0;                  // for position control, 
+volatile fpint64_t  _stopDistance = 0;          // for position control, 
+
+// and settings 
+fpint32_t           _maxAccel = 0;              // maximum acceleration
+fpint32_t           _maxVelocity = 0;
+
+// nasty ! 
+fpint32_t           _velEpsilon = 0; 
+
+void motion_init(uint32_t microsecondsPerIntegration){
+  // here's our delta-tee for each integration step 
+  _delT = fp_floatToFixed32((float)(microsecondsPerIntegration) / 1000000.0F);
+  // and (for resetting our timer) the _delta directly in us 
+  _delT_us = microsecondsPerIntegration;
+
+  // setup the hardware timer 
+  hw_set_bits(&timer_hw->inte, 1u << ALARM_DT_NUM);
+  irq_set_exclusive_handler(ALARM_DT_IRQ, alarm_dt_handler);
+  irq_set_enabled(ALARM_DT_IRQ, true);
+  timer_hw->alarm[ALARM_DT_NUM] = (uint32_t) (timer_hw->timerawl + _delT_us);
+
+  // (optionally) use a debug pin to perf test 
+  // pinMode(PIN_DEBUG, OUTPUT);
+  _velEpsilon = fp_floatToFixed32(1.0F);
+}
+
+void alarm_dt_handler(void){
+  // setup next call right away
+  hw_clear_bits(&timer_hw->intr, 1u << ALARM_DT_NUM);
+  timer_hw->alarm[ALARM_DT_NUM] = (uint32_t) (timer_hw->timerawl + _delT_us);
+  // do the motion system integration, 
+  // sio_hw->gpio_set = (uint32_t)(1 << PIN_DEBUG);
+  motion_integrate(); 
+  // sio_hw->gpio_clr = (uint32_t)(1 << PIN_DEBUG);
+}
+
+// ------------------------------------ integrator codes 
+
+fpint64_t motion_calc_stopping_distance(fpint32_t vel, fpint32_t accel){
+  // our num / denum, 
+  fpint64_t velSqrd = fp_mult32x32_64(vel, vel); 
+  fpint64_t twoAccel = fp_mult32x32_64(fp_int32ToFixed32(2), accel);
+  // now we div that out, 
+  return fp_div64x64(velSqrd, twoAccel);
+}
+
+void motion_calc_mode_velocity(void){
+  // go fast, or go slo; 
+  if(_vel < _maxVelocity){
+    _accel = _maxAccel; 
+  } else if (_vel > _maxVelocity){
+    _accel = -_maxAccel;
+  }
+  
+  // using our chosen accel, integrate velocity from previous: 
+  _vel += fp_mult32x32(_accel, _delT); 
+
+  // and check against targets 
+  // TODO: hack-ey velocity-at-target thing (1st if here)
+  // should dead-reckon step intervals, checking a delta, 
+  // but requires that we check which direction we are going (towards velocity) 
+  if( _maxVelocity < _velEpsilon && _maxVelocity > -_velEpsilon &&   // if we are near-zero target velocity, 
+      _vel < _velEpsilon && _vel > -_velEpsilon                     // and we are also ... near that velocity, 
+      ){
+    _accel = 0;
+    _vel = 0;
+  } else if(_vel > 0 && _maxVelocity > 0 && _vel > _maxVelocity){
+    _accel = 0;
+    _vel = _maxVelocity;
+  } else if(_vel < 0 && _maxVelocity < 0 && _vel < _maxVelocity){
+    _accel = 0;
+    _vel = _maxVelocity;
+  }
+}
+
+void motion_calc_mode_position(void){
+  // figure whence we would need to start stopping, and our current dist  
+  _stopDistance = motion_calc_stopping_distance(_vel, _maxAccel);
+  _dist = _posTarget - _pos;
+
+  // check if we're about to make it... bonk if so, 
+  // units are steps, so epsilon is tiny ! 
+  if(abs(_dist - _delta) < fp_floatToFixed32(0.001F)){
+    _vel = 0;
+    _accel = 0;
+    return;
+  }
+
+  // now we do a buncha cheques 
+  if(_stopDistance >= abs(_dist)){  // we're going to overshoot, 
+    if(_vel <= 0){                  // when -ve vel, 
+      _accel = _maxAccel;           // do +ve accel 
+    } else {                        // when +ve vel, 
+      _accel = -_maxAccel;          // do -ve accel 
+    }
+  } else {                          // we're not overshooting, 
+    if(_dist > 0){                  // if delta is positive,
+      _accel = _maxAccel;           // go forwards, 
+    } else {                        // if it's negative 
+      _accel = -_maxAccel;          // go backwards... 
+    }
+  }
+
+  // using our chosen accel, integrate velocity from previous: 
+  _vel += fp_mult32x32(_accel, _delT); 
+
+  // cap our _vel based on maximum rates: 
+  if(_vel >= _maxVelocity){
+    _accel = 0;
+    _vel = _maxVelocity;
+  } else if (_vel <= -_maxVelocity){
+    _accel = 0;
+    _vel = -_maxVelocity;
+  }
+}
+
+void motion_integrate(void){
+  // set our _accel based on modal requests, 
+  switch(_mode){
+    case MOTION_MODE_POS:
+      motion_calc_mode_position();
+      break;
+    case MOTION_MODE_VEL:
+      motion_calc_mode_velocity();
+      break;
+  }
+
+  // grab a delta and integrate, 
+  _delta = fp_mult32x32(_vel, _delT);
+  _pos += _delta;
+
+  // position is base 16, we can just shift our way to relative electrical phase 
+  // 0-2048 (11 bits) per electrical phase, is
+  // 0-512 (9 bits) per step, 
+  // 0b XXXXXXXXXXXXXXXX.XXXXXXXXXXXXXXXX
+  // 0b               XX.XXXXXXXXX
+  //                  FS.MicroStep
+  uint16_t phaseAngle = ((_pos >> 7) & 0b11111111111) - _phaseOffset;
+  stepper_point(phaseAngle);
+} 
+
+// ------------------------------------ end integrator 
+
+void motion_setVelocityTarget(float target, float maxAccel){
+  noInterrupts();
+  _maxAccel = fp_floatToFixed32(abs(maxAccel));
+  _maxVelocity = fp_floatToFixed32(target);
+  _mode = MOTION_MODE_VEL;
+  interrupts();
+}
+
+uint16_t oldPhase = 0;
+uint16_t newPhase = 0;
+
+// was just debuggen, we could rm this... 
+// but maybe useful! 
+String motion_getErrorMessage(void){
+  uint16_t phaseAngle = ((_pos >> 7) & 0b11111111111) - _phaseOffset;
+  return "oldPhase: " + String(oldPhase) + 
+         ", newPhase: " + String(newPhase) + 
+         ", phaseAngle - recalc: " + String(phaseAngle); 
+}
+
+void motion_setPosition(float pos){
+  noInterrupts();
+  fpint64_t oldPos = _pos;
+  _pos = fp_floatToFixed64(pos);
+  // we have the trouble that the electrical machine uses the 11 bits
+  // straight outta _pos, like this:
+  oldPhase = ((oldPos >> 7) & 0b11111111111) - _phaseOffset;
+  newPhase = ((_pos >> 7) & 0b11111111111);
+  // so if we just write it direct, next update cycle will basically 
+  // increment the motor to whatever new phase, 
+  // so we need an offset... 
+  _phaseOffset = newPhase - oldPhase;
+  interrupts();
+}
+
+void motion_getCurrentStates(motionState_t* statePtr){
+  noInterrupts();
+  statePtr->pos = fp_fixed64ToFloat(_pos);
+  statePtr->vel = fp_fixed32ToFloat(_vel);
+  statePtr->accel = fp_fixed32ToFloat(_accel);
+  interrupts();
+}
+
+void motion_setPositionTarget(float target, float maxVel, float maxAccel){
+  noInterrupts();
+  _posTarget = fp_floatToFixed64(target);
+  _maxVelocity = fp_floatToFixed32(abs(maxVel));
+  _maxAccel = fp_floatToFixed32(abs(maxAccel));
+  _mode = MOTION_MODE_POS;
+  interrupts();
+}
+
+// void motion_debug(void){
+//   // ... we could / should snapshot, if this is chunky ? 
+//   noInterrupts();
+//   Serial.println(String(millis())
+//       // + "\t_delT: \t" + String(fp_fixed32ToFloat(_delT), 6)
+//       + "\tm: " + String(_mode) 
+//       + "\tptrg: " + String(fp_fixed64ToFloat(_posTarget), 1)
+//       + "\tvtrg: " + String(fp_fixed64ToFloat(_maxVelocity), 1)
+//       + "\tpos: " + String(fp_fixed64ToFloat(_pos), 1)
+//       + "\tdst: " + String(fp_fixed64ToFloat(_dist), 1)
+//       + "\tstp: " + String(fp_fixed64ToFloat(_stopDistance), 1)
+//       + "\tacc: " + String(fp_fixed32ToFloat(_accel), 1)
+//       + "\tvel: " + String(fp_fixed32ToFloat(_vel), 1)
+//       // + "\tvtrg: \t" + String(fp_fixed32ToFloat(_maxVelocity), 4)
+//     );
+//   interrupts();
+// }
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/motionStateMachine.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/motionStateMachine.h
new file mode 100644
index 0000000..25cc05e
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/motionStateMachine.h
@@ -0,0 +1,34 @@
+#ifndef MOTION_STATE_MACHINE_H_
+#define MOTION_STATE_MACHINE_H_
+
+#include <Arduino.h>
+#include <hardware/timer.h>
+#include <hardware/irq.h>
+
+#define MOTION_MODE_POS           0
+#define MOTION_MODE_VEL           1
+
+// units here area always full steps, 
+// i.e. 200 steps per revolution (for a typical stepper) 
+// but we effectively do 512 microsteps internally
+// (one full electrical phase is 2048 ticks of a LUT) 
+
+typedef struct motionState_t {
+  float pos;
+  float vel;
+  float accel;
+} motionState_t;
+
+void motion_init(uint32_t microsecondsPerIntegration);
+
+void motion_integrate(void);
+void alarm_dt_handler(void);
+
+void motion_setPositionTarget(float target, float maxVel, float maxAccel);
+void motion_setVelocityTarget(float target, float maxAccel);
+void motion_setPosition(float pos);
+
+void motion_getCurrentStates(motionState_t* statePtr);
+String motion_getErrorMessage(void);
+
+#endif 
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/stepperDriver.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/stepperDriver.cpp
new file mode 100644
index 0000000..d21f341
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/stepperDriver.cpp
@@ -0,0 +1,147 @@
+/*
+stepperDriver.cpp
+
+stepper code for two A4950s or TB67... w/ VREF via TC -> RC Filters 
+for the RP2040 XIAO ! 
+
+Jake Read at the Center for Bits and Atoms
+(c) Massachusetts Institute of Technology 2022
+
+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 "stepperDriver.h"
+#include "stepperLUT.h"
+
+#define AIN1_PIN 6      // on D4
+#define AIN2_PIN 7      // on D5 
+#define BIN1_PIN 28     // on D2
+#define BIN2_PIN 4      // on D9 
+#define APWM_PIN 27     // on D1
+#define BPWM_PIN 29     // on D3 
+
+// macros to set h-bridge dir pins 
+
+#define AIN1_HI sio_hw->gpio_set = (uint32_t)(1 << AIN1_PIN)
+#define AIN1_LO sio_hw->gpio_clr = (uint32_t)(1 << AIN1_PIN)
+
+#define AIN2_HI sio_hw->gpio_set = (uint32_t)(1 << AIN2_PIN)
+#define AIN2_LO sio_hw->gpio_clr = (uint32_t)(1 << AIN2_PIN)
+
+#define BIN1_HI sio_hw->gpio_set = (uint32_t)(1 << BIN1_PIN)
+#define BIN1_LO sio_hw->gpio_clr = (uint32_t)(1 << BIN1_PIN)
+
+#define BIN2_HI sio_hw->gpio_set = (uint32_t)(1 << BIN2_PIN)
+#define BIN2_LO sio_hw->gpio_clr = (uint32_t)(1 << BIN2_PIN)
+
+// macros to set h-bridge dir states 
+
+#define A_UP    AIN2_LO; AIN1_HI
+#define B_UP    BIN2_LO; BIN1_HI 
+
+#define A_OFF   AIN2_LO; AIN1_LO
+#define B_OFF   BIN2_LO; BIN1_LO
+
+#define A_DOWN  AIN1_LO; AIN2_HI
+#define B_DOWN  BIN1_LO; BIN2_HI
+
+// hardware pwm vals 
+
+uint16_t sliceNumA;
+uint16_t sliceNumB;
+uint16_t channelA;
+uint16_t channelB;
+
+void stepper_init(void){
+  // -------------------------------------------- DIR PINS 
+  // all of 'em, outputs 
+  pinMode(AIN1_PIN, OUTPUT);
+  pinMode(AIN2_PIN, OUTPUT);
+  pinMode(BIN1_PIN, OUTPUT);
+  pinMode(BIN2_PIN, OUTPUT);
+
+  gpio_set_function(APWM_PIN, GPIO_FUNC_PWM);
+  gpio_set_function(BPWM_PIN, GPIO_FUNC_PWM);
+  sliceNumA = pwm_gpio_to_slice_num(APWM_PIN);
+  sliceNumB = pwm_gpio_to_slice_num(BPWM_PIN);
+  channelA = pwm_gpio_to_channel(APWM_PIN);
+  channelB = pwm_gpio_to_channel(BPWM_PIN);
+
+  // TODO: check about the old code, with Q ? 
+  // or fk it, go full beans always ? 
+  // uint32_t f_sys = clock_get_hz(clk_sys);
+  float divider = 1.0F; //(float)f_sys / (PWM_PERIOD * 10000UL);  
+
+  pwm_set_clkdiv(sliceNumA, divider);
+  pwm_set_clkdiv(sliceNumB, divider);
+
+  // pwm period
+  pwm_set_wrap(sliceNumA, PWM_PERIOD);
+  pwm_set_wrap(sliceNumB, PWM_PERIOD);
+
+  // set a start-up value of 1 / PWM_PERIOD 
+  pwm_set_chan_level(sliceNumA, channelA, 1);
+  pwm_set_chan_level(sliceNumB, channelB, 1);
+
+  // Set the PWM running
+  pwm_set_enabled(sliceNumA, true);
+  pwm_set_enabled(sliceNumB, true);
+}
+
+volatile uint16_t _lastPhaseAngle = 0;
+
+void stepper_point(uint16_t phaseAngle, uint16_t amplitude){
+  _lastPhaseAngle = phaseAngle;
+  // wrap phaseAngle to 2048, and get a / b components 
+  uint16_t coilAPhase = phaseAngle                    & 0b0000011111111111;
+  uint16_t coilBPhase = (phaseAngle + LUT_LENGTH / 2) & 0b0000011111111111;
+
+  // clamp amplitude, 
+  amplitude = amplitude & 0b0000001111111111;
+
+  // a coil dir 
+  if (coilAPhase > LUT_LENGTH){
+    A_DOWN;
+  } else if (coilAPhase < LUT_LENGTH){
+    A_UP;
+  } else {
+    A_OFF;
+  }
+  // b coil dir 
+  if (coilBPhase > LUT_LENGTH){
+    B_DOWN;
+  } else if (coilBPhase < LUT_LENGTH){
+    B_UP;
+  } else {
+    B_OFF;
+  }
+
+  // now we rectify each to the positive half wave, 
+  coilAPhase = coilAPhase & 0b0000001111111111;
+  coilBPhase = coilBPhase & 0b0000001111111111;
+
+  // expand to 32 for multiply overflow, 
+  // then do fixed-point where 0-1.0 == 0-1024, using 2^10 bit divide 
+  uint32_t coilAMag = (LUT[coilAPhase] * amplitude) >> 10;
+  uint32_t coilBMag = (LUT[coilBPhase] * amplitude) >> 10;
+
+  // and set amplitudes...
+  pwm_set_chan_level(sliceNumA, channelA, coilAMag);
+  pwm_set_chan_level(sliceNumB, channelB, coilBMag);
+}
+
+uint16_t _amplitude = 0;
+
+void stepper_point(uint16_t phaseAngle){
+  stepper_point(phaseAngle, _amplitude);
+}
+
+void stepper_setAmplitude(uint16_t amplitude){
+  if(amplitude > 1024) amplitude = 1024;
+  if(amplitude < 0) amplitude = 0;
+  _amplitude = amplitude;
+  stepper_point(_lastPhaseAngle);
+}
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/stepperDriver.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/stepperDriver.h
new file mode 100644
index 0000000..084502f
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/stepperDriver.h
@@ -0,0 +1,35 @@
+/*
+stepperDriver.h
+
+stepper code for two A4950s w/ VREF via TC -> RC Filters
+with RP2040 support
+
+Jake Read & Quentin Bolsee at the Center for Bits and Atoms
+(c) Massachusetts Institute of Technology 2023
+
+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 STEPPER_DRIVER_H_
+#define STEPPER_DRIVER_H_
+
+#include <Arduino.h>
+#include "pico/stdlib.h"
+#include "hardware/pwm.h"
+
+// startup stepper hardware 
+void stepper_init(void);
+
+// mapping 0-2PI is 0-2048 and 0-1 is 0-1024 
+void stepper_point(uint16_t phaseAngle, uint16_t amplitude);
+
+// or, omitting amplitude... 
+void stepper_point(uint16_t phaseAngle);
+
+// with 0-1024 
+void stepper_setAmplitude(uint16_t amplitude);
+
+#endif 
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/stepperLUT.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/stepperLUT.h
new file mode 100644
index 0000000..82b338c
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/motion/stepperLUT.h
@@ -0,0 +1,76 @@
+#ifndef STEPPER_LUT_H_
+#define STEPPER_LUT_H_
+
+#include <Arduino.h>
+
+#define LUT_LENGTH 1024 
+#define PWM_PERIOD 2048
+
+const uint16_t LUT[LUT_LENGTH] = {
+  0, 6, 13, 19, 25, 31, 38, 44, 50, 57, 63, 69, 75, 82, 88, 94, 
+  101, 107, 113, 119, 126, 132, 138, 145, 151, 157, 163, 170, 176, 182, 188, 195, 
+  201, 207, 213, 220, 226, 232, 238, 245, 251, 257, 263, 270, 276, 282, 288, 295, 
+  301, 307, 313, 319, 326, 332, 338, 344, 350, 357, 363, 369, 375, 381, 388, 394, 
+  400, 406, 412, 418, 425, 431, 437, 443, 449, 455, 461, 468, 474, 480, 486, 492, 
+  498, 504, 510, 516, 522, 529, 535, 541, 547, 553, 559, 565, 571, 577, 583, 589, 
+  595, 601, 607, 613, 619, 625, 631, 637, 643, 649, 655, 661, 667, 673, 679, 685, 
+  691, 697, 702, 708, 714, 720, 726, 732, 738, 744, 749, 755, 761, 767, 773, 779, 
+  784, 790, 796, 802, 808, 813, 819, 825, 831, 836, 842, 848, 854, 859, 865, 871, 
+  876, 882, 888, 893, 899, 905, 910, 916, 922, 927, 933, 938, 944, 950, 955, 961, 
+  966, 972, 977, 983, 988, 994, 999, 1005, 1010, 1016, 1021, 1027, 1032, 1038, 1043, 1048, 
+  1054, 1059, 1065, 1070, 1075, 1081, 1086, 1091, 1097, 1102, 1107, 1113, 1118, 1123, 1128, 1134, 
+  1139, 1144, 1149, 1154, 1160, 1165, 1170, 1175, 1180, 1185, 1191, 1196, 1201, 1206, 1211, 1216, 
+  1221, 1226, 1231, 1236, 1241, 1246, 1251, 1256, 1261, 1266, 1271, 1276, 1281, 1286, 1291, 1295, 
+  1300, 1305, 1310, 1315, 1320, 1324, 1329, 1334, 1339, 1344, 1348, 1353, 1358, 1362, 1367, 1372, 
+  1376, 1381, 1386, 1390, 1395, 1400, 1404, 1409, 1413, 1418, 1422, 1427, 1431, 1436, 1440, 1445, 
+  1449, 1454, 1458, 1463, 1467, 1471, 1476, 1480, 1484, 1489, 1493, 1497, 1502, 1506, 1510, 1514, 
+  1519, 1523, 1527, 1531, 1535, 1540, 1544, 1548, 1552, 1556, 1560, 1564, 1568, 1572, 1576, 1580, 
+  1584, 1588, 1592, 1596, 1600, 1604, 1608, 1612, 1616, 1620, 1623, 1627, 1631, 1635, 1639, 1642, 
+  1646, 1650, 1654, 1657, 1661, 1665, 1668, 1672, 1676, 1679, 1683, 1686, 1690, 1693, 1697, 1700, 
+  1704, 1707, 1711, 1714, 1718, 1721, 1725, 1728, 1731, 1735, 1738, 1741, 1745, 1748, 1751, 1754, 
+  1758, 1761, 1764, 1767, 1770, 1774, 1777, 1780, 1783, 1786, 1789, 1792, 1795, 1798, 1801, 1804, 
+  1807, 1810, 1813, 1816, 1819, 1822, 1825, 1827, 1830, 1833, 1836, 1839, 1841, 1844, 1847, 1850, 
+  1852, 1855, 1858, 1860, 1863, 1866, 1868, 1871, 1873, 1876, 1878, 1881, 1883, 1886, 1888, 1891, 
+  1893, 1895, 1898, 1900, 1902, 1905, 1907, 1909, 1912, 1914, 1916, 1918, 1921, 1923, 1925, 1927, 
+  1929, 1931, 1933, 1935, 1937, 1939, 1941, 1943, 1945, 1947, 1949, 1951, 1953, 1955, 1957, 1959, 
+  1961, 1962, 1964, 1966, 1968, 1969, 1971, 1973, 1975, 1976, 1978, 1979, 1981, 1983, 1984, 1986, 
+  1987, 1989, 1990, 1992, 1993, 1995, 1996, 1997, 1999, 2000, 2002, 2003, 2004, 2005, 2007, 2008, 
+  2009, 2010, 2012, 2013, 2014, 2015, 2016, 2017, 2018, 2019, 2020, 2021, 2022, 2023, 2024, 2025, 
+  2026, 2027, 2028, 2029, 2030, 2031, 2031, 2032, 2033, 2034, 2034, 2035, 2036, 2037, 2037, 2038, 
+  2038, 2039, 2040, 2040, 2041, 2041, 2042, 2042, 2043, 2043, 2044, 2044, 2044, 2045, 2045, 2045, 
+  2046, 2046, 2046, 2046, 2047, 2047, 2047, 2047, 2047, 2048, 2048, 2048, 2048, 2048, 2048, 2048, 
+  2048, 2048, 2048, 2048, 2048, 2048, 2048, 2047, 2047, 2047, 2047, 2047, 2046, 2046, 2046, 2046, 
+  2045, 2045, 2045, 2044, 2044, 2044, 2043, 2043, 2042, 2042, 2041, 2041, 2040, 2040, 2039, 2038, 
+  2038, 2037, 2037, 2036, 2035, 2034, 2034, 2033, 2032, 2031, 2031, 2030, 2029, 2028, 2027, 2026, 
+  2025, 2024, 2023, 2022, 2021, 2020, 2019, 2018, 2017, 2016, 2015, 2014, 2013, 2012, 2010, 2009, 
+  2008, 2007, 2005, 2004, 2003, 2002, 2000, 1999, 1997, 1996, 1995, 1993, 1992, 1990, 1989, 1987, 
+  1986, 1984, 1983, 1981, 1979, 1978, 1976, 1975, 1973, 1971, 1969, 1968, 1966, 1964, 1962, 1961, 
+  1959, 1957, 1955, 1953, 1951, 1949, 1947, 1945, 1943, 1941, 1939, 1937, 1935, 1933, 1931, 1929, 
+  1927, 1925, 1923, 1921, 1918, 1916, 1914, 1912, 1909, 1907, 1905, 1902, 1900, 1898, 1895, 1893, 
+  1891, 1888, 1886, 1883, 1881, 1878, 1876, 1873, 1871, 1868, 1866, 1863, 1860, 1858, 1855, 1852, 
+  1850, 1847, 1844, 1841, 1839, 1836, 1833, 1830, 1827, 1825, 1822, 1819, 1816, 1813, 1810, 1807, 
+  1804, 1801, 1798, 1795, 1792, 1789, 1786, 1783, 1780, 1777, 1774, 1770, 1767, 1764, 1761, 1758, 
+  1754, 1751, 1748, 1745, 1741, 1738, 1735, 1731, 1728, 1725, 1721, 1718, 1714, 1711, 1707, 1704, 
+  1700, 1697, 1693, 1690, 1686, 1683, 1679, 1676, 1672, 1668, 1665, 1661, 1657, 1654, 1650, 1646, 
+  1642, 1639, 1635, 1631, 1627, 1623, 1620, 1616, 1612, 1608, 1604, 1600, 1596, 1592, 1588, 1584, 
+  1580, 1576, 1572, 1568, 1564, 1560, 1556, 1552, 1548, 1544, 1540, 1535, 1531, 1527, 1523, 1519, 
+  1514, 1510, 1506, 1502, 1497, 1493, 1489, 1484, 1480, 1476, 1471, 1467, 1463, 1458, 1454, 1449, 
+  1445, 1440, 1436, 1431, 1427, 1422, 1418, 1413, 1409, 1404, 1400, 1395, 1390, 1386, 1381, 1376, 
+  1372, 1367, 1362, 1358, 1353, 1348, 1344, 1339, 1334, 1329, 1324, 1320, 1315, 1310, 1305, 1300, 
+  1295, 1291, 1286, 1281, 1276, 1271, 1266, 1261, 1256, 1251, 1246, 1241, 1236, 1231, 1226, 1221, 
+  1216, 1211, 1206, 1201, 1196, 1191, 1185, 1180, 1175, 1170, 1165, 1160, 1154, 1149, 1144, 1139, 
+  1134, 1128, 1123, 1118, 1113, 1107, 1102, 1097, 1091, 1086, 1081, 1075, 1070, 1065, 1059, 1054, 
+  1048, 1043, 1038, 1032, 1027, 1021, 1016, 1010, 1005, 999, 994, 988, 983, 977, 972, 966, 
+  961, 955, 950, 944, 938, 933, 927, 922, 916, 910, 905, 899, 893, 888, 882, 876, 
+  871, 865, 859, 854, 848, 842, 836, 831, 825, 819, 813, 808, 802, 796, 790, 784, 
+  779, 773, 767, 761, 755, 749, 744, 738, 732, 726, 720, 714, 708, 702, 697, 691, 
+  685, 679, 673, 667, 661, 655, 649, 643, 637, 631, 625, 619, 613, 607, 601, 595, 
+  589, 583, 577, 571, 565, 559, 553, 547, 541, 535, 529, 522, 516, 510, 504, 498, 
+  492, 486, 480, 474, 468, 461, 455, 449, 443, 437, 431, 425, 418, 412, 406, 400, 
+  394, 388, 381, 375, 369, 363, 357, 350, 344, 338, 332, 326, 319, 313, 307, 301, 
+  295, 288, 282, 276, 270, 263, 257, 251, 245, 238, 232, 226, 220, 213, 207, 201, 
+  195, 188, 182, 176, 170, 163, 157, 151, 145, 138, 132, 126, 119, 113, 107, 101, 
+  94, 88, 82, 75, 69, 63, 57, 50, 44, 38, 31, 25, 19, 13, 6, 0, 
+};
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/.gitignore b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/.gitignore
new file mode 100644
index 0000000..ae8ee57
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/.gitignore
@@ -0,0 +1 @@
+.vscode*
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/LICENSE.md b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/LICENSE.md
new file mode 100644
index 0000000..fcba268
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/LICENSE.md
@@ -0,0 +1,19 @@
+Copyright (c) 2024 Jake Robert Read
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/README.md b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/README.md
new file mode 100644
index 0000000..616190d
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/README.md
@@ -0,0 +1,7 @@
+## OSAP for Arduino
+
+The [Open Systems Assembly Protocol (OSAP!)](http://osap.tools/) is a new approach for the generation and integration of modular, interoperable hardware systems, and a love letter to computer plumbing and hardware heterogeneity.
+
+This is the arduino library, that speaks to javascript and python (in the works) partners. See [osap.tools](http://osap.tools) for more detail.
+
+The [modular-things](https://github.com/modular-things/modular-things) project is the most stable instantiation of an OSAP-based project. 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/library.properties b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/library.properties
new file mode 100644
index 0000000..c69a444
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/library.properties
@@ -0,0 +1,10 @@
+name=osap
+version=0.6.1
+author=Jake Robert Read
+maintainer=Jake Robert Read <jakeread@mit.edu>
+sentence=Multi-microcontroller plumbing, etc.
+paragraph=TBD.
+category=Networking
+url=http://osap.tools/
+architectures=*
+depends=FlashStorage_SAMD
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/LICENSE.md b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/LICENSE.md
new file mode 100644
index 0000000..a8a3d93
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/LICENSE.md
@@ -0,0 +1,19 @@
+Copyright (c) 2020 Jake Robert Read
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/discovery/netresponder.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/discovery/netresponder.cpp
new file mode 100644
index 0000000..8358679
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/discovery/netresponder.cpp
@@ -0,0 +1,182 @@
+
+#include "netresponder.h"
+#include "../runtime/runtime.h"
+#include "../structure/links.h"
+#include "../utils/serdes.h"
+#include "../utils/micros_64.h"
+#include "../utils/platform_flash.h"
+#include "../utils/debug.h"
+
+NetResponder::NetResponder(void) : OSAP_Sequential_Receiver("netresponder", "netresponder"){
+  rt = OSAP_Runtime::getInstance();
+}
+
+size_t NetResponder::onData(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort, uint8_t* reply){
+  switch(data[0] & 0b00011111){
+    // -------------------- Discovery Service 
+    case SKEY_RTINFO_REQ:
+      {
+        // response key w/ matching message id, 
+        reply[0] = 0 | PKEY_SMSG << 6 | SKEY_RTINFO_RES;
+        // handoff thet traverse id, bytes 2,3,4,5
+        memcpy(reply + 1, rt->previousTraverseID, 4);
+        memcpy(rt->previousTraverseID, data + 1, 4);
+        // report our build type and version, 
+        reply[5] = BUILDTYPEKEY_EMBEDDED_CPP;
+        reply[6] = OSAP_VERSION_MAJOR;
+        reply[7] = OSAP_VERSION_MID;
+        reply[8] = OSAP_VERSION_MINOR;
+        // report the instruction of arrival, 
+        memcpy(reply + 9, sourceRoute->encodedPath, 2);
+        // if this was a self-scan, we will have zero route, so need to stuff
+        // a meaningless 'smsg' key in here... 
+        if(sourceRoute->encodedPathLen == 0){
+          reply[9] = PKEY_SMSG << 6;
+          reply[10] = 0;
+        }
+        // point link count B12[3:7], bus link count B13[0:5], and port count B13[6:7],B14[0:7]
+        reply[11] = 0b00011111 & rt->linkCount;
+        // ... no busses here, so just carry on  
+        reply[12] = 0b00000011 & (rt->portCount >> 8);
+        reply[13] = rt->portCount & 0b11111111;
+        // that's all, ship it inline 
+        return 14;
+      }
+    // -------------------- Requesting the module's type name 
+    case SKEY_MTYPEGET_REQ:
+      {
+        reply[0] = 0 | PKEY_SMSG << 6 | SKEY_MTYPEGET_RES;
+        // reporting *module's* version nums, but basically a protocol placeholder, so:
+        reply[1] = 0; 
+        reply[2] = 0; 
+        reply[3] = 0;
+        // stuff the typename 
+        size_t wptr = 4;
+        serializeTight<char*>(rt->typeName, reply, &wptr);
+        return wptr;
+      }
+    // -------------------- Requesting the module's own name 
+    case SKEY_MNAMEGET_REQ:
+      {
+        reply[0] = 0 | PKEY_SMSG << 6 | SKEY_MNAMEGET_RES;
+        // stuff the module's name, 
+        size_t wptr = 1;
+        serializeTight<char*>(rt->moduleName, reply, &wptr);
+        return wptr;
+      }
+    // -------------------- Requesting to change the module's own name 
+    case SKEY_MNAMESET_REQ:
+      {
+        reply[0] = 0 | PKEY_SMSG << 6 | SKEY_MNAMESET_RES;
+        // we're going to read straight from the packet into the name-field, 
+        size_t rptr = 1;
+        deserializeTightInto<char*>(rt->moduleName, data, &rptr, OSAP_PROPERNAMES_MAX_CHAR); 
+        // and then commit that to flash (TODO)
+        flashSaveName(rt->moduleName);
+        // and reply w/ an OK (if we have flash capability, elsewise reply as ungovernable)
+        size_t wptr = 1;
+        serializeTight<bool>(true, reply, &wptr);
+        return wptr; 
+      }
+    // -------------------- Requesting info on a particular link 
+    case SKEY_LINKINFO_REQ:
+      {
+        reply[0] = 0 | PKEY_SMSG << 6 | SKEY_LINKINFO_RES;
+        // collect the index, 
+        uint8_t index = 0b00011111 & data[1];
+        if(index < rt->linkCount && rt->links[index] != nullptr){
+          size_t wptr = 1;
+          serializeTight<char*>(rt->links[index]->typeName, reply, &wptr);
+          serializeTight<char*>(rt->links[index]->name, reply, &wptr);
+          // B1 also contains state info, 
+          reply[1] |= (rt->links[index]->isOpen() ? 1 : 0) << 5;
+          // that's all, 
+          return wptr;
+        } else {
+          reply[1] = 0;
+          return 2;
+        }
+      }
+    // -------------------- Requesting info on a particular bus 
+    case SKEY_BUSINFO_REQ:
+      // TODO: busses, lol 
+      OSAP_DEBUG("bus-fwds key in the runtime...");
+      return 0;
+    // -------------------- Requesting info on a particular port 
+    case SKEY_PORTINFO_REQ:
+      {
+        reply[0] = 0 | PKEY_SMSG << 6 | SKEY_LINKINFO_RES;
+        // collect the index, 
+        uint16_t index = (uint16_t)(0b00000011 & data[1]) << 8 | data[2];
+        if(index < rt->portCount && rt->ports[index] != nullptr){
+          size_t wptr = 1;
+          serializeTight<char*>(rt->ports[index]->typeName, reply, &wptr);
+          serializeTight<char*>(rt->ports[index]->name, reply, &wptr);
+          // OSAP_DEBUG(String("port type, name: \n" + String(ports[index]->typeName) + " \n" + String(ports[index]->name)));
+          return wptr;
+        } else {
+          reply[1] = 0;
+          return 2;
+        }
+      }
+    // -------------------- Time service 
+    case SKEY_TIME_CONFIG_GET_REQ:
+      {
+        reply[0] = 0 | PKEY_SMSG << 6 | SKEY_TIME_CONFIG_GET_RES; 
+        // let's get underlying, system, and skew 
+        uint64_t underlying = micros64();
+        uint64_t system = rt->getSystemMicroseconds();
+        fpint64_t skew = rt->clockSkew;
+        size_t wptr = 1;
+        serializeTight<uint64_t>(underlying, reply, &wptr);
+        serializeTight<uint64_t>(system, reply, &wptr);
+        // this serialization should be OK since it will not be -ve ? 
+        serializeTight<uint64_t>(skew, reply, &wptr);
+        return wptr;
+      }
+    case SKEY_TIME_CONFIG_SET_REQ:
+      {
+        reply[0] = 0 | PKEY_SMSG << 6 | SKEY_TIME_CONFIG_SET_RES;
+        // 
+        size_t rptr = 1; 
+        // in here we have, 
+        uint64_t setBaseUpdate = deserializeTight<uint64_t>(data, &rptr);
+        float setSkew = deserializeTight<float>(data, &rptr);
+        float setFilterAlpha = deserializeTight<float>(data, &rptr);
+        float setPTerm = deserializeTight<float>(data, &rptr);
+        bool setUseJumps = deserializeTight<bool>(data, &rptr);
+        // now we do a little bit of logic / conversion, 
+        // TODO: we should be able to update these selectively ... 
+        if(setBaseUpdate != 0){
+          rt->setSystemMicroseconds(setBaseUpdate);
+          rt->lastHardReset = micros64();
+        }
+        if(setSkew != 0.0F){
+          rt->clockSkew = fp_float32ToFixed64(setSkew);
+        }
+        rt->propFilterAlpha = fp_float32ToFixed64(setFilterAlpha);
+        rt->propFilterOneMinusAlpha = fp_int64ToFixed64(1) - rt->propFilterAlpha;
+        rt->clockSkewProportionalTerm = fp_float32ToFixed64(setPTerm);
+        rt->useHardOffsetJumps = setUseJumps; 
+        // let's also reset our (filtered) prop term:
+        rt->propTerm = fp_int64ToFixed64(0);
+        return 2;
+      }
+      break; 
+
+    // -------------------- Results - not handled in embedded at the moment 
+    case SKEY_RTINFO_RES:
+    case SKEY_MTYPEGET_RES:
+    case SKEY_MNAMEGET_RES:
+    case SKEY_MNAMESET_RES:
+    case SKEY_LINKINFO_RES:
+    case SKEY_BUSINFO_RES:
+    case SKEY_PORTINFO_RES:
+      OSAP_ERROR("SMSG_RES in the embedded runtime, tf?");
+      return 0;
+    // -------------------- Mistakes 
+    default:
+      OSAP_ERROR("unknown key in the smsg switch " + String(data[0] & 0b00011111));
+      return 0;
+  }
+}
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/discovery/netresponder.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/discovery/netresponder.h
new file mode 100644
index 0000000..bc5cd9f
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/discovery/netresponder.h
@@ -0,0 +1,15 @@
+#ifndef NET_RESPONDER_H_
+#define NET_RESPONDER_H_ 
+
+#include "../transport/sequential_receiver.h"
+
+class NetResponder : public OSAP_Sequential_Receiver {
+  public:
+    NetResponder(void);
+    size_t onData(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort, uint8_t* reply) override;
+
+  private:
+    OSAP_Runtime* rt;
+};
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_uart_cobs_crc16.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_uart_cobs_crc16.h
new file mode 100644
index 0000000..6e6b951
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_uart_cobs_crc16.h
@@ -0,0 +1,152 @@
+#ifndef LINK_UART_COBS_CRC16_H_
+#define LINK_UART_COBS_CRC16_H_
+
+#include "../structure/links.h"
+#include "../packets/packets.h"
+#include "link_utils/cobs.h"
+#include "link_utils/crc16_ccitt.h"
+
+#define LINK_UART_CC_BUFFER_SIZE 255
+
+template <typename SerialImplementation> 
+class OSAP_Gateway_UART_COBS_CRC16 : public LinkGateway {
+  public:
+    OSAP_Gateway_UART_COBS_CRC16(SerialImplementation* _impl, uint32_t _baudrate, const char* _name, uint32_t _pinYZTransciever, uint32_t _pinABTransciever):
+    LinkGateway(OSAP_Runtime::getInstance(), "uart_cobs_crc", _name){
+      impl = _impl; 
+      baudrate = _baudrate;
+      hasTrancievers = true;
+      pinYZTransciever = _pinYZTransciever;
+      pinABTransciever = _pinABTransciever;
+    }
+
+    OSAP_Gateway_UART_COBS_CRC16(SerialImplementation* _impl, uint32_t _baudrate, const char* _name):
+    LinkGateway(OSAP_Runtime::getInstance(), "uart_cobs_crc", _name){
+      impl = _impl; 
+      baudrate = _baudrate;
+      hasTrancievers = false;
+    }
+
+    void begin(void) override {
+      if(hasTrancievers){
+        pinMode(pinYZTransciever, OUTPUT);
+        pinMode(pinABTransciever, OUTPUT);
+        digitalWrite(pinYZTransciever, HIGH);
+        digitalWrite(pinABTransciever, LOW);
+      }
+      impl->begin(baudrate);
+      crc16_generate_table();
+    }
+
+    void loop(void) override {
+      // rx while-available, 
+      // NOTE: currently, we are waiting for app before rx'ing again, 
+      // but we could at least buffer one extra... properly, we should have 
+      // a buffer of some configured depth ....
+      while(impl->available() && rxAwaitingLen == 0){
+        rxBuffer[rxBufferWp ++] = impl->read();
+        if(rxBufferWp >= LINK_UART_CC_BUFFER_SIZE) rxBufferWp = 0;
+        if(rxBuffer[rxBufferWp - 1] == 0){
+          // nicely, we can decode COBS in place, 
+          size_t len = cobsDecode(rxBuffer, 255, rxBuffer);
+          // rm'ing the trailing zero, 
+          rxBufferLen = len - 1;
+          // calculate the crc on the packet (less the crc itself), and compare to the crc reported: 
+          uint16_t crc = crc16_ccitt(rxBuffer, rxBufferLen - 2);
+          uint16_t tx_crc = ((uint16_t)(rxBuffer[rxBufferLen - 2]) << 8) | rxBuffer[rxBufferLen - 1];
+          // pass / fail based on crc, 
+          if(crc == tx_crc){
+            numSuccessRx ++;
+            // (removing the crc tail) 
+            rxAwaitingLen = rxBufferLen - 2;
+            memcpy(rxAwaiting, rxBuffer, rxAwaitingLen);
+          } else {
+            numFailedRx ++;
+          }
+          // every time we hit the zero, we reset these
+          rxBufferLen = 0; 
+          rxBufferWp = 0; 
+        }
+      } // end while-available rx 
+
+      // tx while-available, 
+      if(txBufferLen){
+        noInterrupts();
+        size_t fifoAvail = impl->availableForWrite();
+        for(size_t i = 0; i < fifoAvail; i ++){
+          impl->write(txBuffer[txBufferRp ++]);
+          if(txBufferRp >= txBufferLen){
+            // tx'ing is done, this all resets, 
+            txBufferRp = 0;
+            txBufferLen = 0;
+            numTx ++;
+            break;
+          }
+        }
+        interrupts();
+      }
+
+      // relay to OSAP 
+      if(claimPacketCheck(this) && rxAwaitingLen > 0){
+        // claim a buffer, 
+        VPacket* pck = claimPacketFromStack(this);
+        // write into it and set length, 
+        memcpy(pck->data, rxAwaiting, rxAwaitingLen);
+        pck->len = rxAwaitingLen;
+        // from links.cpp, apply pointer and time ops etc 
+        ingestPacket(pck);
+        // and clear it on our side, 
+        rxAwaitingLen = 0;
+      }
+    }
+
+    boolean clearToSend(void) override {
+      return (txBufferLen == 0);
+    }
+
+    boolean isOpen(void) override {
+      // a TODO 
+      return true; 
+    }
+
+    void send(uint8_t* data, size_t len) override {
+      if (!clearToSend()) return;
+      // calculate crc of the data in-place, 
+      uint16_t crc = crc16_ccitt(data, len);
+      // stick that in the tail: OK since we know OSAP has the packet locked out 
+      data[len] = crc >> 8;
+      data[len + 1] = crc & 255;
+      txBufferLen = cobsEncode(data, len + 2, txBuffer);
+      txBuffer[txBufferLen] = 0;
+      txBufferLen += 1;
+      txBufferRp = 0;
+    }
+
+    // and some stats, 
+    uint32_t numSuccessRx = 0;
+    uint32_t numFailedRx = 0; 
+    uint32_t numTx = 0; 
+
+
+  private: 
+    // "hardware" lol 
+    SerialImplementation* impl; 
+    uint32_t baudrate; 
+    // transcievers (if promoted to RS485...)
+    bool hasTrancievers = false;
+    uint32_t pinYZTransciever;
+    uint32_t pinABTransciever; 
+    // buffers, write/read-pointers, lengths 
+    uint8_t rxAwaiting[LINK_UART_CC_BUFFER_SIZE];
+    uint8_t rxAwaitingLen = 0;
+    // hot-and-incoming 
+    uint8_t rxBuffer[LINK_UART_CC_BUFFER_SIZE];
+    uint8_t rxBufferWp = 0;
+    uint8_t rxBufferLen = 0;
+    // and tx, 
+    uint8_t txBuffer[LINK_UART_CC_BUFFER_SIZE];
+    uint8_t txBufferRp = 0;
+    uint8_t txBufferLen = 0;
+};
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_usb_cdc_cobs.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_usb_cdc_cobs.h
new file mode 100644
index 0000000..52ee8e6
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_usb_cdc_cobs.h
@@ -0,0 +1,112 @@
+#ifndef LINK_USB_CDC_COBS_H_
+#define LINK_USB_CDC_COBS_H_
+
+#include "../structure/links.h"
+#include "../packets/packets.h"
+#include "link_utils/cobs.h"
+
+#define LINK_USB_BUFFER_SIZE 255
+
+template <typename USBSerialImplementation> 
+class OSAP_Gateway_USBCDC_COBS : public LinkGateway {
+  public:
+    OSAP_Gateway_USBCDC_COBS(USBSerialImplementation* _impl, const char* _name):
+    LinkGateway(OSAP_Runtime::getInstance(), "usb_cdc_cobs", _name){
+      impl = _impl; 
+    }
+
+    void begin(void) override {
+      impl->begin(9600);
+    }
+
+    void loop(void) override {
+      // rx while-available, 
+      // NOTE: currently, we are waiting for app before rx'ing again, 
+      // but we could at least buffer one extra... properly, we should have 
+      // a buffer of some configured depth ....
+      while(impl->available() && rxAwaitingLen == 0){
+        rxBuffer[rxBufferWp ++] = impl->read();
+        if(rxBufferWp >= LINK_USB_BUFFER_SIZE) rxBufferWp = 0;
+        if(rxBuffer[rxBufferWp - 1] == 0){
+          // nicely, we can decode COBS in place, 
+          size_t len = cobsDecode(rxBuffer, 255, rxBuffer);
+          // rm'ing the trailing zero, stuffing, 
+          rxAwaitingLen = len - 1;
+          memcpy(rxAwaiting, rxBuffer, rxAwaitingLen);
+          // stat track 
+          numRx ++;
+          // every time we hit the zero, we reset these
+          rxBufferLen = 0; 
+          rxBufferWp = 0; 
+        }
+      } // end while-available rx 
+
+      // tx while-available, 
+      if(txBufferLen){
+        noInterrupts();
+        size_t fifoAvail = impl->availableForWrite();
+        for(size_t i = 0; i < fifoAvail; i ++){
+          impl->write(txBuffer[txBufferRp ++]);
+          if(txBufferRp >= txBufferLen){
+            // tx'ing is done, this all resets, 
+            txBufferRp = 0;
+            txBufferLen = 0;
+            numTx ++;
+            break;
+          }
+        }
+        interrupts();
+      }
+
+      // relay to OSAP 
+      if(claimPacketCheck(this) && rxAwaitingLen > 0){
+        // claim a buffer, 
+        VPacket* pck = claimPacketFromStack(this);
+        // write into it and set length, 
+        memcpy(pck->data, rxAwaiting, rxAwaitingLen);
+        pck->len = rxAwaitingLen;
+        // from links.cpp, apply pointer and time ops etc 
+        ingestPacket(pck);
+        // and clear it on our side, 
+        rxAwaitingLen = 0;
+      }
+    }
+
+    boolean clearToSend(void) override {
+      return (txBufferLen == 0);
+    }
+
+    boolean isOpen(void) override {
+      // a TODO 
+      return true; 
+    }
+
+    void send(uint8_t* data, size_t len) override {
+      if (!clearToSend()) return;
+      txBufferLen = cobsEncode(data, len, txBuffer);
+      txBuffer[txBufferLen] = 0;
+      txBufferLen += 1;
+      txBufferRp = 0;
+    }
+
+    // and some stats, 
+    uint32_t numRx = 0;
+    uint32_t numTx = 0; 
+
+  private: 
+    // "hardware" lol 
+    USBSerialImplementation* impl; 
+    // buffers, write/read-pointers, lengths 
+    uint8_t rxAwaiting[LINK_USB_BUFFER_SIZE];
+    uint8_t rxAwaitingLen = 0;
+    // hot-and-incoming 
+    uint8_t rxBuffer[LINK_USB_BUFFER_SIZE];
+    uint8_t rxBufferWp = 0;
+    uint8_t rxBufferLen = 0;
+    // and tx, 
+    uint8_t txBuffer[LINK_USB_BUFFER_SIZE];
+    uint8_t txBufferRp = 0;
+    uint8_t txBufferLen = 0;
+};
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/cobs.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_utils/cobs.cpp
similarity index 100%
rename from new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/cobs.cpp
rename to new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_utils/cobs.cpp
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/cobs.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_utils/cobs.h
similarity index 100%
rename from new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/cobs.h
rename to new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_utils/cobs.h
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_utils/crc16_ccitt.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_utils/crc16_ccitt.cpp
new file mode 100644
index 0000000..bfed6d4
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_utils/crc16_ccitt.cpp
@@ -0,0 +1,32 @@
+#include "crc16_ccitt.h"
+
+const uint16_t polynomial = 0x1021;
+uint16_t crcTable[256];
+bool tableGenerated = false;
+
+void crc16_generate_table() {
+  if(tableGenerated) return;
+  tableGenerated = true; 
+  for (int i = 0; i < 256; i++) {
+    uint16_t crc = i << 8;
+    for (int j = 0; j < 8; j++) {
+      if (crc & 0x8000)
+        crc = (crc << 1) ^ polynomial;
+      else
+        crc <<= 1;
+    }
+    crcTable[i] = crc;
+  }
+}
+
+const uint16_t initialValue = 0xFFFF;
+
+uint16_t crc16_ccitt(uint8_t* data, size_t len) {
+  uint16_t crc = initialValue;
+  for (size_t i = 0; i < len; i++) {
+    // Use XOR to find index into crc table and combine with the rest of the CRC.
+    uint8_t index = (crc >> 8) ^ data[i]; // Find the index into the table
+    crc = crcTable[index] ^ (crc << 8);   // Look up in the table and combine with the rest
+  }
+  return crc;
+}
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_utils/crc16_ccitt.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_utils/crc16_ccitt.h
new file mode 100644
index 0000000..af5b746
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/gateway_integrations/link_utils/crc16_ccitt.h
@@ -0,0 +1,9 @@
+#ifndef CRC16_CCITT_H_
+#define CRC16_CCITT_H_
+
+#include <Arduino.h>
+
+void crc16_generate_table(void);
+uint16_t crc16_ccitt(uint8_t* data, size_t len);
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/osap.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/osap.h
new file mode 100644
index 0000000..2bb86c9
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/osap.h
@@ -0,0 +1,61 @@
+/*
+osap/osap.h
+
+osap root / vport factory
+
+Jake Read at the Center for Bits and Atoms
+(c) Massachusetts Institute of Technology 2021
+
+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_
+
+// our osap.h include is ~ just a pointer to whatever 
+// components we are going to present at a "high level" 
+
+#include "runtime/runtime.h"
+#include "utils/debug.h"
+
+// we could also do config-dependent include of various links...
+#include "gateway_integrations/link_usb_cdc_cobs.h"
+#include "gateway_integrations/link_uart_cobs_crc16.h"
+
+// and of port types...
+#include "presentation/port_rpc.h"
+
+#define BUILD_RPC(func, args, returns)\
+    OSAP_Port_RPC<decltype(&func)> func##_rpc(&func, #func, args, returns)
+
+// to use auto-dispatched macro: 
+
+/*
+#define BUILD_RPC_3(func, args, returns)\
+    OSAP_Port_RPC<decltype(&func)> func##_rpc(&func, #func, args, returns)
+
+#define BUILD_RPC_2(func, args)\
+    OSAP_Port_RPC<decltype(&func)> func##_rpc(&func, #func, args, "")
+
+#define BUILD_RPC_1(func)\
+    OSAP_Port_RPC<decltype(&func)> func##_rpc(&func, #func, "", "")
+
+// dispatcher macros 
+#define GET_MACRO(_1,_2,_3,NAME,...) NAME
+
+// ARGS: function, "argument_names", "return_names"
+#define BUILD_RPC(...)\
+    GET_MACRO(__VA_ARGS__, BUILD_RPC_3, BUILD_RPC_2, BUILD_RPC_1)(__VA_ARGS__)
+*/
+
+// #include "presentation/port_bare.h"
+// #include "presentation/port_pipe.h"
+
+// #include "presentation/port_deviceNames.h"
+// #include "presentation/port_messageEscape.h"
+
+
+#endif
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/osap_config.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/osap_config.h
new file mode 100644
index 0000000..de0e18c
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/osap_config.h
@@ -0,0 +1,59 @@
+/*
+osap_config.h
+
+config options for an osap-embedded build
+
+Jake Read at the Center for Bits and Atoms
+(c) Massachusetts Institute of Technology 2022
+
+This work may be reproduced, modified, distributed, performed, and
+displayed for any purpose, but must acknowledge the osap project.
+Copyright is retained and must be preserved. The work is provided as is;
+no warranty is provided, and users accept all liability.
+*/
+
+#ifndef OSAP_CONFIG_H_
+#define OSAP_CONFIG_H_
+
+// -------------------------------- Track Version - Num 
+
+// i.e. 0.1.2 
+// MAJOR: 0, 
+// MID: 1,
+// MINOR: 2
+
+#define OSAP_VERSION_MAJOR 0 
+#define OSAP_VERSION_MID 7
+#define OSAP_VERSION_MINOR 1
+
+// -------------------------------- Stack / Build Sizes
+
+// TODO: we have from i.e. COBSUSBSerial.cpp examples of `if defined(ARDUINO_ARCH...)
+// - we should use those to set relative stack sizes for typical RAM avail
+// and should also watch out to perhaps set compiler flags for RP2040 to allocate 
+// these buffers in RAM rather than slow-af SRAM  
+
+#define OSAP_CONFIG_STACK_SIZE 6
+#define OSAP_CONFIG_PACKET_MAX_SIZE 256
+
+#define OSAP_CONFIG_MAX_PORTS 32
+#define OSAP_CONFIG_MAX_LGATEWAYS 16
+#define OSAP_CONFIG_MAX_BGATEWAYS 8
+
+#define OSAP_CONFIG_ROUTE_MAX_LENGTH 64 
+
+#define OSAP_CONFIG_DEFAULT_SERVICE_DEADLINE 20000
+
+// -------------------------------- Name Lengths
+
+// more of a protocol feature: typenames need to be < 32 char, names < 64 ! 
+
+#define OSAP_TYPENAMES_MAX_CHAR 32 
+#define OSAP_PROPERNAMES_MAX_CHAR 64 
+
+// -------------------------------- Error / Debug Build Options 
+
+#define OSAP_CONFIG_INCLUDE_DEBUG_MSGS
+#define OSAP_CONFIG_INCLUDE_ERROR_MSGS
+
+#endif
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/packets.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/packets.cpp
new file mode 100644
index 0000000..9c0c8bd
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/packets.cpp
@@ -0,0 +1,290 @@
+/*
+osap/packets.cpp
+
+common routines
+
+Jake Read at the Center for Bits and Atoms
+(c) Massachusetts Institute of Technology 2021
+
+This work may be reproduced, modified, distributed, performed, and
+displayed for any purpose, but must acknowledge the osap project.
+Copyright is retained and must be preserved. The work is provided as is;
+no warranty is provided, and users accept all liability.
+*/
+
+#include "packets.h"
+#include "../utils/serdes.h"
+#include "../utils/keys.h"
+#include "../utils/debug.h"
+
+// we have some file-scoped pointers, 
+VPacket* queueStart;
+VPacket* firstFree;
+
+// ---------------------------------------------- Stack Utilities 
+
+void stackReset(VPacket* stack, size_t stackSize){
+  // reset each individual, 
+  for(uint16_t p = 0; p < stackSize; p ++){
+    stack[p].len = 0;
+    stack[p].vport = nullptr;
+    stack[p].linkGateway = nullptr;
+    stack[p].runtime = nullptr;
+    stack[p].serviceDeadline = 0;
+    stack[p].timeOfEntry = 0;
+  }
+  // set next ptrs, forwards pass
+  for(uint16_t p = 0; p < stackSize - 1; p ++){
+    stack[p].next = &(stack[p+1]);
+  }
+  stack[stackSize - 1].next = &(stack[0]);
+  // set previous ptrs, reverse pass
+  for(uint16_t p = 1; p < stackSize; p ++){
+    stack[p].previous = &(stack[p-1]);
+  }
+  stack[0].previous = &(stack[stackSize - 1]);
+  // queueStart element is [0], as is the firstFree, at startup,
+  queueStart = &(stack[0]);
+  firstFree = &(stack[0]);
+}
+
+size_t stackGetPacketsToService(VPacket** packets, size_t maxPackets){
+  // this is the zero-packets case;
+  if(firstFree == queueStart) return 0;
+  // this is how many max we can possibly list,
+  uint16_t iters = maxPackets < OSAP_CONFIG_STACK_SIZE ? maxPackets : OSAP_CONFIG_STACK_SIZE;
+  // otherwise do...
+  VPacket* pck = queueStart;
+  uint16_t count = 0;
+  for(uint16_t p = 0; p < iters; p ++){
+    // stash it in the callers' list, 
+    packets[p] = pck;
+    // increment, 
+    count ++;
+    // check next-fullness, 
+    // (if packet is allocated to a vport or a linkGateway they would be linked)
+    if(pck->next->vport == nullptr && pck->next->linkGateway == nullptr && pck->next->runtime == nullptr){
+      // if next is empty, this is final count:
+      return count;
+    } else {
+      // if it ain't, collect next and continue stuffing
+      pck = pck->next;
+    }
+  }
+  // TODO: we could have an additional step here of sorting the list 
+  // in decending deadline-time order... to manage priorities. we could *also*
+  // sort-in-place, i.e. when a call is made to stuff-a-packet, check deadline, 
+  // and sort into the linked list there... not a huge lift, just a little linked-list-tricky 
+  // for the time being, we're just returning 'em 
+  // end-of-loop thru all possible, none free, so:
+  return count;
+}
+
+// ---------------------------------------------- Stack Allocators 
+// TODO: templates would eliminate need for manually overloading each of these, 
+// but would need to be careful w/ compiler versions, non ? 
+
+boolean claimPacketCheck(VPort* vport){
+  if( firstFree->vport == nullptr && 
+      firstFree->linkGateway == nullptr && 
+      firstFree->runtime == nullptr && 
+      vport->currentPacketHold < vport->maxPacketHold
+  ){
+    return true;
+  } else {
+    return false;
+  }
+}
+
+boolean claimPacketCheck(LinkGateway* linkGateway){
+  if( firstFree->vport == nullptr && 
+      firstFree->linkGateway == nullptr && 
+      firstFree->runtime == nullptr && 
+      linkGateway->currentPacketHold < linkGateway->maxPacketHold
+  ){
+    return true;
+  } else {
+    return false;
+  }
+}
+
+boolean claimPacketCheck(OSAP_Runtime* runtime){
+  if( firstFree->vport == nullptr && 
+      firstFree->linkGateway == nullptr && 
+      firstFree->runtime == nullptr && 
+      runtime->currentPacketHold < runtime->maxPacketHold
+  ){
+    return true;
+  } else {
+    return false;
+  }
+}
+
+VPacket* claimPacketFromStack(VPort* vport){
+  if(claimPacketCheck(vport)){
+    // allocate the firstFree in the queue to the requester, 
+    VPacket* pck = firstFree;
+    pck->vport = vport;
+    vport->currentPacketHold ++;
+    // increment, 
+    firstFree = firstFree->next;
+    // hand it over, 
+    return pck;
+  } else {
+    return nullptr;
+  }
+}
+
+VPacket* claimPacketFromStack(LinkGateway* linkGateway){
+  if(claimPacketCheck(linkGateway)){
+    VPacket* pck = firstFree;
+    pck->linkGateway = linkGateway;
+    linkGateway->currentPacketHold ++;
+    // increment, 
+    firstFree = firstFree->next;
+    // hand it over, 
+    return pck;
+  } else {
+    return nullptr;
+  }
+}
+
+VPacket* claimPacketFromStack(OSAP_Runtime* runtime){
+  if(claimPacketCheck(runtime)){
+    VPacket* pck = firstFree;
+    pck->runtime = runtime;
+    runtime->currentPacketHold ++;
+    // increment, 
+    firstFree = firstFree->next;
+    // hand it over, 
+    return pck;
+  } else {
+    return nullptr;
+  }
+}
+
+void relinquishPacketToStack(VPacket* pck){
+  // decriment-count per-point maximums 
+  if(pck->vport){
+    pck->vport->currentPacketHold --;
+  } else if (pck->linkGateway){
+    pck->linkGateway->currentPacketHold --;
+  } else if (pck->runtime){
+    pck->runtime->currentPacketHold --;
+  }
+  // zero the packet out,
+  pck->vport = nullptr;
+  pck->linkGateway = nullptr;
+  pck->runtime = nullptr;
+  // and these, just in case... 
+  pck->len = 0;
+  pck->serviceDeadline = 0;
+  pck->timeOfEntry = 0;
+
+  // now we can handle the stack free-ness, 
+  // if it was at the start of the queue, that now 
+  // begins at the next packet: 
+  if(queueStart == pck){
+    queueStart = pck->next;
+  } else {
+    // otherwise we un-stick it from the middle:
+    pck->previous->next = pck->next;
+    pck->next->previous = pck->previous;
+    // now, insert this where the old firstFree was
+    firstFree->previous->next = pck;
+    pck->previous = firstFree->previous;
+    pck->next = firstFree;
+    firstFree->previous = pck;
+    // and the item is the new firstFree element,
+    firstFree = pck;
+  }
+}
+
+// ---------------------------------------------- Route Retrieval 
+
+// local ute, this figures where the last byte in the route is 
+// in the new scheme, end-of-route is either a SMSG or a DGRM, right ? 
+uint8_t routeEndScan(uint8_t* data, size_t maxLen){
+  // 1st instruction is at pck[5] since we have | PTR | PHTTL:2 | MSS:2 | 
+  uint8_t end = 5;
+  uint8_t increment = 0;
+  while(true){
+    // protocol is such that PKEY == size of that instruction
+    increment = data[end] >> 6;
+    if(!increment) return end;
+    if(increment == 3) return end;
+    end += increment;
+    if(end > maxLen) return maxLen;
+  }
+}
+
+void getRouteFromPacket(VPacket* pck, Route* route){
+  // ttl, segsize come out of the packet head, 
+  // | PTR:1 | SDL:2 | MSS:2 | 
+  size_t rptr = 1;
+  route->timeToLive = deserializeTight<uint16_t>(pck->data, &rptr);
+  route->maxSegmentSize = deserializeTight<uint16_t>(pck->data, &rptr);
+  // get end-of-route location 
+  uint16_t routeEndLocation = routeEndScan(pck->data, pck->len);
+  // now we can memcpy the route's encoded-path section over, 
+  memcpy(route->encodedPath, &(pck->data[5]), routeEndLocation - 5);
+  // and the length, 
+  route->encodedPathLen = routeEndLocation - 5;
+}
+
+// ---------------------------------------------- Packet Authorship 
+
+uint16_t stuffPacketRoute(VPacket* pck, Route* route){
+  // the pointer is always initialized at 5, 
+  //                          V
+  // | PTR | SDL:2 | MSS: 2 | 1ST_INSTRUCT 
+  pck->data[0] = 5;
+  size_t wptr = 1;
+  serializeTight<uint16_t>(route->timeToLive, pck->data, &wptr);
+  serializeTight<uint16_t>(route->maxSegmentSize, pck->data, &wptr);  
+  // and the route, 
+  memcpy(pck->data + 5, route->encodedPath, route->encodedPathLen);
+  // stuffPacketRoute is called when we mint new packets, effectively 
+  // when they are created in our system: 
+  pck->timeOfEntry = micros();
+  // and a service deadline, sometime in the future: 
+  pck->serviceDeadline = pck->timeOfEntry + route->timeToLive;
+  // return the end of this chunk, 
+  return route->encodedPathLen + 5;
+}
+
+// stuffing into allocated packet, 
+void stuffPacketRaw(VPacket* pck, Route* route, uint8_t* data, size_t len){
+  // write pointer and route-writing, 
+  uint16_t wptr = stuffPacketRoute(pck, route);
+  // no bigguns... 
+  if(len + wptr > route->maxSegmentSize){ 
+    OSAP_ERROR("oversize raw-write" + String(wptr + len)); 
+    len = 1; 
+  }
+  // now stuff the data, 
+  memcpy(&(pck->data[wptr]), data, len);
+  // service deadline was calc'd in stuffPacketRoute, 
+  // that'd be it then, 
+  pck->len = wptr + len;
+  // OSAP_DEBUG(OSAP_DEBUG_PRINT_PACKET(pck));
+}
+
+// stuffing from:to port,
+void stuffPacketPortToPort(VPacket* pck, Route* route, uint16_t sourcePort, uint16_t destinationPort, uint8_t* data, size_t len){
+  // pretty similar to above, 
+  uint16_t wptr = stuffPacketRoute(pck, route);
+  // guard largess
+  if(len + wptr + 5 > route->maxSegmentSize){ 
+    OSAP_ERROR("oversize port-write" + String(wptr + len)); 
+    len = 1; 
+  }
+  // author port-key-stuff, 
+  pck->data[wptr ++] = PKEY_DGRM << 6 | sourcePort >> 6;
+  pck->data[wptr ++] = sourcePort << 2 | destinationPort >> 8;
+  pck->data[wptr ++] = destinationPort & 255;
+  // and stuff the payload ! 
+  memcpy(&(pck->data[wptr]), data, len);
+  // aaaaand we're done here... 
+  pck->len = len + wptr;
+}
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/packets.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/packets.h
new file mode 100644
index 0000000..f88f232
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/packets.h
@@ -0,0 +1,102 @@
+/*
+osap/packets.h
+
+reading and writing from packet buffers in the transport layer 
+
+Jake Read at the Center for Bits and Atoms
+(c) Massachusetts Institute of Technology 2021
+
+This work may be reproduced, modified, distributed, performed, and
+displayed for any purpose, but must acknowledge the osap project.
+Copyright is retained and must be preserved. The work is provided as is;
+no warranty is provided, and users accept all liability.
+*/
+
+#ifndef OSAP_PACKETS_H_
+#define OSAP_PACKETS_H_
+
+#include <Arduino.h>
+#include "routes.h"
+#include "../structure/ports.h"
+#include "../structure/links.h"
+
+// ---------------------------------------------- The Packet Structure 
+
+// the vpacket structure is where we stash messages as they make their 
+// way through the transvport / routing layer, 
+typedef struct VPacket {
+  // the packet's underlying buffer 
+  uint8_t data[OSAP_CONFIG_PACKET_MAX_SIZE];
+  // the underlying buffer's current size 
+  size_t len = 0;
+  // given the packet's `timeToLive`, we can calculate a deadline
+  // for the packet: if the current time is beyond this, we can time it out 
+  // TODO: uint32_t microsecond timers overflow around 90 minutes, that's not long enough 
+  uint32_t serviceDeadline = 0;
+  uint32_t timeOfEntry = 0;
+
+  // packets also stash info w/r/t their whereabouts in the stack and in the system 
+  // this is the vport where the packet is currently allocated
+  // when vport == nullptr, the packet is unallocated 
+  VPort* vport = nullptr;
+  LinkGateway* linkGateway = nullptr;
+  // seems like we should be able to rm this, 
+  // if we put query-asking under a port...  
+  OSAP_Runtime* runtime = nullptr;
+
+  // next packet in the linked ringbuffer
+  VPacket* next = nullptr;
+  // previous packet in the ringbuffer 
+  VPacket* previous = nullptr;
+} VPacket;
+
+// - packets.h should be the main interface to packet-handling, 
+// - `pck* = claimPacketFromStack(this)` to see if we can allocate one to write into, 
+//   - overload for runtime, link, port... simple enough 
+// - `relinquishPacketToStack(pck*)` to free it up 
+// - `stuffPacket(pck*, route*, data*)` for transport-layer work, 
+// - `stuffPacket(pck*, route*, sourcePort, destPort)` for port-to-port work... 
+
+// ---------------------------------------------- Stack Utils 
+
+// reset the stack at startup (note: a list of vpackets, not a single vpacket)
+void stackReset(VPacket* stack, size_t stackSize);
+
+// api for the runtime to collect a list 
+size_t stackGetPacketsToService(VPacket** packets, size_t maxPackets);
+
+// ---------------------------------------------- Get / Relinquish Packets from / to the Stack 
+
+// these are overloaded for various packet-accessors 
+VPacket* claimPacketFromStack(VPort* vport);
+VPacket* claimPacketFromStack(LinkGateway* linkGateway);
+VPacket* claimPacketFromStack(OSAP_Runtime* runtime);
+
+// vports .clearToSend() requires that they check w/o actually allocating
+boolean claimPacketCheck(VPort* vport);
+boolean claimPacketCheck(LinkGateway* linkGateway);
+boolean claimPacketCheck(OSAP_Runtime* runtime);
+
+// giving it up, 
+void relinquishPacketToStack(VPacket* pck);
+
+// ---------------------------------------------- Route Retrieval 
+
+// copies route data from a packet into a (provided) route object 
+void getRouteFromPacket(VPacket* pck, Route* route);
+
+// ---------------------------------------------- Packet Stuffing 
+
+// stuffing into allocated packet, 
+void stuffPacketRaw(VPacket* pck, Route* route, uint8_t* data, size_t len);
+
+// stuffing from:to port,
+void stuffPacketPortToPort(VPacket* pck, Route* route, uint16_t sourcePort, uint16_t destinationPort, uint8_t* data, size_t len);
+
+// stuff a packet with a route & data, 
+// size_t pk_stuffPacket(VPacket* pck, uint8_t key, uint8_t* payload, size_t payloadLen, Route* route);
+
+// we should replace this w/ the stuff-packet and the reverse-route call, 
+// uint16_t pk_writeReply_plsReplace(uint8_t* ogGram, uint8_t* gram, uint16_t maxGramLength, uint8_t* payload, uint16_t payloadLen);
+
+#endif
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/routes.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/routes.cpp
new file mode 100644
index 0000000..f469600
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/routes.cpp
@@ -0,0 +1,103 @@
+/*
+osap/routes.cpp
+
+directions
+
+Jake Read at the Center for Bits and Atoms
+(c) Massachusetts Institute of Technology 2021
+
+This work may be reproduced, modified, distributed, performed, and
+displayed for any purpose, but must acknowledge the osap project.
+Copyright is retained and must be preserved. The work is provided as is;
+no warranty is provided, and users accept all liability.
+*/
+
+#include "routes.h"
+#include "../utils/keys.h"
+// #include "../utils/serdes.h"
+#include "../utils/debug.h"
+
+// Route::Route(void){
+
+// }
+
+// direct constructor, 
+// although TODO: it's unclear if this is a useful or used semantic, 
+// since string-masking... so I will delete until we are testing 
+/*
+Route::Route(uint8_t* _encodedPath, uint16_t _encodedPathLen, uint16_t _timeToLive, uint16_t _maxSegmentSize){
+// guard, should do better to stash / report errors, idk 
+  if(_encodedPathLen > 64){
+    _encodedPathLen = 64;
+  }
+  // copy-in 
+  timeToLive = _timeToLive;
+  maxSegmentSize = _maxSegmentSize;
+  encodedPathLen = _encodedPathLen;
+  // memcpy-in 
+  memcpy(encodedPath, _encodedPath, encodedPathLen);
+}
+
+// empty constructor for chaining, 
+Route::Route(void){}
+
+Route* Route::linkf(uint8_t txIndex){
+  encodedPath[encodedPathLen ++] = PKEY_LFWD << 6 | (txIndex & 0b00011111);
+  return this;
+}
+
+Route* Route::busf(uint8_t txIndex, uint8_t txAddress){
+  encodedPath[encodedPathLen ++] = PKEY_BFWD << 6 | (txIndex & 0b00011111);
+  encodedPath[encodedPathLen ++] = txAddress;
+  return this;
+}
+
+Route* Route::end(uint16_t _timeToLive, uint16_t _maxSegmentSize){
+  timeToLive = _timeToLive;
+  maxSegmentSize = _maxSegmentSize;
+  return this;
+}
+*/
+
+// TODO: it seems like (?) we could shave this chunk of RAM 
+// by using some other temporary buffer, like the Port::payload or Port::datagram 
+// but would need to analyze whether / not those are likely to be mid-write 
+// when this is called (which actually seems fairly likely) 
+uint8_t oldPathStash[OSAP_CONFIG_ROUTE_MAX_LENGTH];
+
+void Route::reverse(void){
+  // pull a copy of the path out, 
+  memcpy(oldPathStash, encodedPath, encodedPathLen);
+  // reading from 1st-key in old, writing from back-to-front into new, 
+  uint8_t rptr = 0;
+  uint8_t wptr = encodedPathLen; 
+  while(wptr > 0){
+    // protocol is such that PKEY == size of that instruction
+    uint8_t increment = oldPathStash[rptr] >> 6;
+    if(!increment || increment == 3){
+      OSAP_ERROR("route-reversal key badness");
+      increment = 2;
+    }
+    wptr -= increment;
+    for(uint8_t i = 0; i < increment; i ++){
+      encodedPath[wptr + i] = oldPathStash[rptr + i];
+    }
+    rptr += increment;
+  }
+}
+
+void Route::reset(void){
+  encodedPathLen = 0;
+}
+
+void Route::addLink(uint8_t index){
+  encodedPath[encodedPathLen ++] = PKEY_LFWD << 6 | (index & 0b00011111);
+}
+
+void Route::setTimeToLive(uint16_t microseconds){
+  timeToLive = microseconds;
+}
+
+void Route::setMaxSegmentSize(uint16_t byteCount){
+  maxSegmentSize = byteCount; 
+}
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/routes.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/routes.h
new file mode 100644
index 0000000..76106b3
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/packets/routes.h
@@ -0,0 +1,64 @@
+/*
+osap/routes.h
+
+directions
+
+Jake Read at the Center for Bits and Atoms
+(c) Massachusetts Institute of Technology 2021
+
+This work may be reproduced, modified, distributed, performed, and
+displayed for any purpose, but must acknowledge the osap project.
+Copyright is retained and must be preserved. The work is provided as is;
+no warranty is provided, and users accept all liability.
+*/
+
+#ifndef OSAP_ROUTES_H_
+#define OSAP_ROUTES_H_
+
+#include <Arduino.h>
+#include "../osap_config.h"
+
+// a route type, more of a struct innit ? 
+class Route {
+  public:
+    // the actual underlying path, with PK_PTR in [0]
+    uint8_t encodedPath[OSAP_CONFIG_ROUTE_MAX_LENGTH];
+    // the size of the path, 
+    uint16_t encodedPathLen = 0;
+    // service deadline: microseconds until the packet needs to be serviced,
+    // from time of creation, counting down until deletion (probably in another system) 
+    // defaults to 20ms here 
+    uint16_t timeToLive = OSAP_CONFIG_DEFAULT_SERVICE_DEADLINE;
+    // given memory constraints, transmitters need to know how 
+    // much data can be packed in a given route, as do rx'ers
+    // who are liable to flip a route and reply to something, 
+    // this is that size 
+    uint16_t maxSegmentSize = OSAP_CONFIG_PACKET_MAX_SIZE;
+
+    // write-direct constructor,
+    // not going to build this until testing it, I think it can be rm'd 
+    // Route(uint8_t* _encodedPath, uint16_t _encodedPathLen, uint16_t _timeToLive, uint16_t _maxSegmentSize);
+
+    // reverse the route in-place
+    void reverse(void);
+
+    // to write routes from embedded this API lets us wipe, add links / endpoints, etc:
+    void reset(void);
+    void addLink(uint8_t index);
+    void setTimeToLive(uint16_t microseconds);
+    void setMaxSegmentSize(uint16_t byteCount);
+
+    // pass-thru initialize constructors;
+    // Route(void);
+
+    /*
+    // write a link-forwarding instruction into the route 
+    Route* linkf(uint8_t txIndex);
+    // append a bus-forwarding instruction to the route 
+    Route* busf(uint8_t txIndex, uint8_t txAddress);
+    // finish the route ?
+    Route* end(uint16_t timeToLive = OSAP_CONFIG_DEFAULT_SERVICE_DEADLINE, uint16_t maxSegmentSize = OSAP_CONFIG_PACKET_MAX_SIZE);
+    */
+};
+
+#endif
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_bare.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_bare.cpp
new file mode 100644
index 0000000..6d2c7d1
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_bare.cpp
@@ -0,0 +1,32 @@
+// integration of a simple port that ingests raw-byte type packet handlers 
+/*
+#include "port_bare.h"
+
+OSAP_Port::OSAP_Port(
+  const char* _name, 
+  size_t (*_onMsgFunction)(uint8_t* data, size_t len, uint8_t* reply)
+  ) : VPort(OSAP_Runtime::getInstance(), "bareWithAck", _name)
+{
+  onMsgFunctionWithReply = _onMsgFunction;
+}
+
+OSAP_Port::OSAP_Port(
+  const char* _name, 
+  void (*_onMsgFunction)(uint8_t* data, size_t len)
+  ) : VPort(OSAP_Runtime::getInstance(), "bare", _name)
+{
+  onMsgFunctionWithoutReply = _onMsgFunction;
+}
+
+void OSAP_Port::onPacket(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort){
+  // hand the data str8 to the handler, 
+  if(onMsgFunctionWithReply != nullptr){
+    // when given a reply mechanic, we send bytes back to the transmitter, 
+    size_t replyLen = onMsgFunctionWithReply(data, len, _payload);
+    send(_payload, replyLen, sourceRoute, sourcePort);
+  } else {
+    // otherwise we just absorb and bail 
+    onMsgFunctionWithoutReply(data, len);
+  }
+}
+*/
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_bare.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_bare.h
new file mode 100644
index 0000000..c9b9830
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_bare.h
@@ -0,0 +1,35 @@
+// integration of a simple port that ingests raw-byte type packet handlers 
+/*
+#ifndef PORT_BARE_H_
+#define PORT_BARE_H_
+
+#include "../structure/ports.h"
+
+#define PNAMED_NAME_MAX_CHARS 32
+
+// keys for this layer 
+#define PNAMED_NAMEREQ 1
+#define PNAMED_NAMERES 2 
+#define PNAMED_MSG 3 
+#define PNAMED_ACK 4 
+
+class OSAP_Port : public VPort {
+  public:
+    // -------------------------------- Constructors
+    // with a func-that-has-reply-mechanic
+    OSAP_Port(const char* _name, size_t (*_onMsgFunction)(uint8_t* data, size_t len, uint8_t* reply));
+    // with a dummy func that has no reply 
+    OSAP_Port(const char* _name, void (*_onMsgFunction)(uint8_t* data, size_t len));
+
+    // -------------------------------- Port-Facing API
+    // we override the onPacket handler, 
+    void onPacket(uint8_t* data, size_t len, Route* route, uint16_t sourcePort) override;
+
+  private:
+    // the user-provided name and callback
+    size_t (*onMsgFunctionWithReply)(uint8_t* data, size_t len, uint8_t* reply) = nullptr;
+    void (*onMsgFunctionWithoutReply)(uint8_t* data, size_t len) = nullptr;
+};
+
+#endif 
+*/
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_deviceNames.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_deviceNames.cpp
new file mode 100644
index 0000000..2b8eab0
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_deviceNames.cpp
@@ -0,0 +1,104 @@
+// named thing
+/*
+#include "port_deviceNames.h"
+#include "../utils/serializers.h"
+
+#include "../utils/debug.h"
+
+// ... we would also want to include our micro-specific NVM libraries here ... 
+
+OSAP_Port_DeviceNames::OSAP_Port_DeviceNames(
+  const char* _typeName
+  ) : VPort(OSAP_Runtime::getInstance())
+{
+  // copy the name in, 
+  strncpy(typeName, _typeName, PDNAMES_NAME_MAX_CHARS);
+  // strncpy *does* guard against over-writing, 
+  // but if src is too long it doesn't insert the tailing 0...
+  // so we do it, just-in-case, 
+  typeName[PDNAMES_NAME_MAX_CHARS - 1] = '\0';
+  // and set our type 
+  typeKey = PTYPEKEY_DEVICENAMES;
+}
+
+// ------------------------------------ Platform Dependent Codes
+
+#if defined(ARDUINO_ARCH_MBED_RP2040) || defined(ARDUINO_ARCH_RP2040)
+#include <EEPROM.h>
+#else
+#include <FlashStorage_SAMD.h>
+#endif
+
+const int WRITTEN_SIGGY = 0xBEEFDEED;
+const int STORAGE_ADDR = 0;
+char tempStr[PDNAMES_NAME_MAX_CHARS];
+
+void OSAP_Port_DeviceNames::begin(void){
+  int signature;
+  
+  #if defined(ARDUINO_ARCH_MBED_RP2040) || defined(ARDUINO_ARCH_RP2040)
+  EEPROM.begin(4096);
+  #endif 
+
+  EEPROM.get(STORAGE_ADDR, signature);
+  if(signature == WRITTEN_SIGGY){
+    // has-been written in the past... 
+    EEPROM.get(STORAGE_ADDR + sizeof(signature), tempStr);
+    // stash it into our current... and safe-t cheque delimiting zero
+    strncpy(uniqueName, tempStr, PDNAMES_NAME_MAX_CHARS);
+    uniqueName[PDNAMES_NAME_MAX_CHARS - 1] = '\0';
+  }
+}
+
+void OSAP_Port_DeviceNames::setUniqueName(const char* _uniqueName){
+  strncpy(uniqueName, _uniqueName, PDNAMES_NAME_MAX_CHARS);
+  uniqueName[PDNAMES_NAME_MAX_CHARS - 1] = '\0';
+  // report! 
+  OSAP_DEBUG("cmt: " + String(uniqueName));
+  // and we'll want to write that to memory:
+  // IDK if the intermediary `tempStr` is necessary, but it works, so am leaving it 
+  strncpy(tempStr, uniqueName, PDNAMES_NAME_MAX_CHARS);
+  EEPROM.put(STORAGE_ADDR, WRITTEN_SIGGY);
+  EEPROM.put(STORAGE_ADDR + sizeof(WRITTEN_SIGGY), tempStr);
+  EEPROM.commit();
+}
+
+// ------------------------------------ End Platform Dependent Codes
+
+void OSAP_Port_DeviceNames::onPacket(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort){
+  switch(data[0]){
+    case PDNAMEKEY_NAMEGET_REQ:
+      {
+        // formulate our reply... 
+        uint16_t wptr = 0;
+        _payload[wptr ++] = PDNAMEKEY_NAMEGET_RES;
+        _payload[wptr ++] = data[1];
+        // implicit here is that... we'll have to use another port on the other 
+        // side, to send these msgs, or just do it one-at-a-time at most, 
+        // I think that's chill though 
+        serializers_writeString(_payload, &wptr, typeName);
+        serializers_writeString(_payload, &wptr, uniqueName);
+        // and ship it back... 
+        send(_payload, wptr, sourceRoute, sourcePort);
+      }
+      break;
+    case PDNAMEKEY_NAMESET_REQ:
+      {
+        // write-in to unique,
+        uint16_t wptr = 0;
+        _payload[wptr ++] = PDNAMEKEY_NAMESET_RES;
+        _payload[wptr ++] = data[1];
+        // 1 to ack-ok, 0 if we (i.e.) have no flash and can't do this 
+        _payload[wptr ++] = 1; 
+        // erp, get a string ? and let's pack the length back, 
+        // this is useful largely for debugging / check-summing... 
+        _payload[wptr ++] = serializers_readString(data, 2, tempStr, PDNAMES_NAME_MAX_CHARS);
+        // ... set that
+        setUniqueName(tempStr);
+        // e's ackin:
+        send(_payload, wptr, sourceRoute, sourcePort);
+      }
+      break;
+  }
+}
+*/
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_deviceNames.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_deviceNames.h
new file mode 100644
index 0000000..516cfd9
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_deviceNames.h
@@ -0,0 +1,35 @@
+// to give devices type- and unique- names 
+/*
+#ifndef PORT_DEVICENAMES_H_
+#define PORT_DEVICENAMES_H_
+
+#include "../structure/ports.h"
+
+#define PDNAMES_NAME_MAX_CHARS 32
+
+#define PDNAMEKEY_NAMEGET_REQ 1
+#define PDNAMEKEY_NAMEGET_RES 2
+#define PDNAMEKEY_NAMESET_REQ 3
+#define PDNAMEKEY_NAMESET_RES 4
+
+class OSAP_Port_DeviceNames : public VPort {
+  public:
+    // -------------------------------- Constructors
+    OSAP_Port_DeviceNames(const char* _typeName);
+
+    // override the begin func, so that we can check flash etc 
+    void begin(void) override;
+
+    // override-this,
+    void onPacket(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort) override;
+
+    // optional, settable unique-name:
+    void setUniqueName(const char* _uniqueName);
+
+  private:
+    char typeName[PDNAMES_NAME_MAX_CHARS] = "defaultDeviceName";
+    char uniqueName[PDNAMES_NAME_MAX_CHARS] = "dfltName";
+};
+
+#endif
+*/
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_messageEscape.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_messageEscape.cpp
new file mode 100644
index 0000000..7ee71fd
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_messageEscape.cpp
@@ -0,0 +1,58 @@
+// message escape-er 
+// mothballing this as of 0p6
+/*
+
+#include "port_messageEscape.h"
+#include "../utils/serdes.h"
+
+OSAP_Port_MessageEscape* OSAP_Port_MessageEscape::instance = nullptr;
+
+OSAP_Port_MessageEscape* OSAP_Port_MessageEscape::getInstance(void){
+  return instance;
+}
+
+OSAP_Port_MessageEscape::OSAP_Port_MessageEscape(void) : VPort(){
+  typeKey = PTYPEKEY_MESSAGE_ESCAPE;
+  if(instance == nullptr){
+    instance = this;
+  }
+};
+
+void OSAP_Port_MessageEscape::onPacket(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort){
+  // make ahn readpointer
+  uint16_t rptr = 0;
+  switch(data[rptr ++]){
+    // remote can ask us to update our outgoing route / port: 
+    case PESCAPE_ROUTESET:
+      // we're going to reply to these... always, 
+      escapePort = sourcePort;
+      // we should stash the flipped route, 
+      escapePath.encodedPathLen = sourceRoute->encodedPathLen;
+      escapePath.timeToLive = sourceRoute->timeToLive;
+      escapePath.maxSegmentSize = sourceRoute->maxSegmentSize;
+      // then the actual... (no memory guards lol good luck)
+      memcpy(escapePath.encodedPath, &(sourceRoute->encodedPath), escapePath.encodedPathLen);
+      // then we done baby, 
+      break;
+  };
+}
+
+uint8_t outBuffer[OSAP_CONFIG_PACKET_MAX_SIZE];
+
+void OSAP_Port_MessageEscape::escape(String msg){
+  // some chance we call this w/o initializing, so: 
+  if(instance == nullptr) return;
+  // and these would prevent us from tx'ing as well, 
+  if(!instance->clearToSend()) return;
+  if(instance->escapePath.encodedPathLen == 0) return;
+  // no bigboys, but arbitrary size (should use msg route length)
+  if(msg.length() + 1 > 128) return;
+  // so, carry on:
+  uint16_t wptr = 0;
+  outBuffer[wptr ++] = PESCAPE_MSG;
+  // and... IDK one-hundo about this char* cast, but we're not editing it so... 
+  serializers_writeString(outBuffer, &wptr, (char*)(msg.c_str()));
+  // that's it, 
+  instance->send(outBuffer, wptr, &(instance->escapePath), instance->escapePort);
+}
+*/
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_messageEscape.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_messageEscape.h
new file mode 100644
index 0000000..1e0f1a8
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_messageEscape.h
@@ -0,0 +1,31 @@
+// message escape-er, 
+// essentially a debug tool that lets us easily pipe 
+// string-encoded messages someplace else 
+// mothballing this as of 0p6
+/*
+
+#ifndef PORT_MESSAGE_ESCAPE_H_
+#define PORT_MESSAGE_ESCAPE_H_
+
+#include "../structure/ports.h"
+
+#define PESCAPE_ROUTESET 44
+#define PESCAPE_MSG 77
+
+class OSAP_Port_MessageEscape : public VPort {
+  public: 
+    // -------------------------------- Constructor
+    OSAP_Port_MessageEscape(void);
+    // we have to override this rx'er, 
+    void onPacket(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort) override;
+    // simple API, right ? and should be singleton, so:
+    static void escape(String msg);
+    static OSAP_Port_MessageEscape* getInstance(void);  
+  private: 
+    uint16_t escapePort = 0;
+    Route escapePath;
+    static OSAP_Port_MessageEscape* instance;
+};
+
+#endif 
+*/
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_pipe.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_pipe.cpp
new file mode 100644
index 0000000..90d42ed
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_pipe.cpp
@@ -0,0 +1,45 @@
+// pipe-er 
+/*
+#include "port_pipe.h"
+
+OSAP_Port_Pipe::OSAP_Port_Pipe(const char* _name)
+  :VPort(OSAP_Runtime::getInstance(), "pipe", _name){}
+
+void OSAP_Port_Pipe::onPacket(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort){
+  // readptr 
+  uint16_t rptr = 0;
+  switch(data[rptr ++]){
+    case PONEPIPE_SETUP:
+      {
+        // we've rx'd a message from our partner port, wherence we will be sending 
+        // msgs to in the future 
+        portNumberAtReciever = sourcePort;
+        // and stash flipped route, 
+        routeToReciever.encodedPathLen = sourceRoute->encodedPathLen;
+        routeToReciever.timeToLive = sourceRoute->timeToLive;
+        routeToReciever.maxSegmentSize = sourceRoute->maxSegmentSize;
+        // then the actual... route (no memory guards lol good luck)
+        memcpy(routeToReciever.encodedPath, &(sourceRoute->encodedPath), routeToReciever.encodedPathLen);
+        // then reply w/ an ack... 
+        outBuffer[0] = PONEPIPE_SETUP_RES;
+        send(outBuffer, 1, sourceRoute, sourcePort);
+      }
+      // then we done baby, 
+      break;
+  }
+}
+
+void OSAP_Port_Pipe::write(uint8_t* data, size_t len){
+  // blind failure, beware !
+  // could do...if not clear, stuff sample into datagram until are clear 
+  if(!clearToSend()) return;
+  // stuff it and... 
+  uint16_t wptr = 0;
+  outBuffer[wptr ++] = PONEPIPE_MSG;
+  if(len > 128) len = 128;
+  memcpy(outBuffer + 1, data, len);
+  wptr += len; 
+  send(outBuffer, wptr, &routeToReciever, portNumberAtReciever);
+  // we're done, lol ? x
+}
+*/
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_pipe.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_pipe.h
new file mode 100644
index 0000000..62f9aa9
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/mothballed/port_pipe.h
@@ -0,0 +1,24 @@
+// data send-er, one-sided, one-channeled 
+/*
+#ifndef PORT_PIPE_H_
+#define PORT_PIPE_H_
+
+#include "../structure/ports.h"
+
+#define PONEPIPE_SETUP 44
+#define PONEPIPE_SETUP_RES 45 
+#define PONEPIPE_MSG 77 
+
+class OSAP_Port_Pipe : public VPort {
+  public:
+    OSAP_Port_Pipe(const char* _name);
+    void onPacket(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort) override;
+    void write(uint8_t* data, size_t len);
+  private:
+    uint16_t portNumberAtReciever = 0;
+    Route routeToReciever;
+    uint8_t outBuffer[OSAP_CONFIG_PACKET_MAX_SIZE];
+};
+
+#endif 
+*/
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/port_rpc.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/port_rpc.h
new file mode 100644
index 0000000..1b3e417
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/port_rpc.h
@@ -0,0 +1,177 @@
+// auto-rpc-rollup port 
+
+#ifndef PORT_RPC_H_
+#define PORT_RPC_H_
+
+#include "../transport/sequential_receiver.h"
+#include "../utils/serdes.h"
+#include "./port_rpc_helpers.h"
+#include <tuple>
+
+#define PRPC_KEY_SIGREQ 1
+#define PRPC_KEY_SIGRES 2
+#define PRPC_KEY_FUNCCALL 3
+#define PRPC_KEY_FUNCRETURN 4
+
+// see osap.h for macro definition BUILD_RPC()
+
+// see ./port_rpc_helpers.h for much of the wizardry required, 
+// ------------------------------------ the actual class 
+template <typename Func>
+class OSAP_Port_RPC;
+
+template <typename Ret, typename... Args>
+class OSAP_Port_RPC<Ret(*)(Args...)> : public OSAP_Sequential_Receiver {
+  public:
+    // to diff void-returners, 
+    using ResultType = typename ReturnType<Ret>::Type;
+
+    // -------------------------------- Constructors 
+    // base constructor 
+    OSAP_Port_RPC(
+      Ret(*funcPtr)(Args...), const char* functionName, const char* argNames, const char* retNames
+    ) : OSAP_Sequential_Receiver("rpc_implementer", functionName)
+    {
+      // stash names and the functo 
+      _funcPtr = funcPtr;
+      strncpy(_functionName, functionName, PRPC_FUNCNAME_MAX_CHAR);
+      // count args using ... pattern; this is odd to me:
+      // I think that the sizeof(Args) has no effect *but* causes the thing to increment, 
+      // ((_numArgs ++, sizeof(Args)), ...);
+      _numArgs = sizeof...(Args);
+      // count return values as well (if returning tuples !) 
+      if constexpr(is_tuple<Ret>::value){
+        _numRets = std::tuple_size<Ret>::value;
+      } else {
+        // if we have just one value, 
+        _numRets = 1;
+      }
+      // and then read-while-copying, and throw some error if we don't have 
+      // the right count of args... 
+      argSplitter(argNames, _argNames);
+      argSplitter(retNames, _retNames);
+    }
+    // deferring constructor for whence we have args only, 
+    OSAP_Port_RPC(
+      Ret(*funcPtr)(Args...), const char* functionName, const char* argNames
+    ) : OSAP_Port_RPC(funcPtr, functionName, argNames, "") {}
+    // deferring constructor for whence we have no args or return names 
+    OSAP_Port_RPC(
+      Ret(*funcPtr)(Args...), const char* functionName
+    ) : OSAP_Port_RPC(funcPtr, functionName, "", "") {}
+  
+    // -------------------------------- OSAP-Facing API
+    // override the packet handler, 
+    size_t onData(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort, uint8_t* reply) override {
+      switch(data[0]){
+        case PRPC_KEY_SIGREQ:
+          {
+            // write response key and msg id 
+            size_t wptr = 0;
+            reply[wptr ++] = PRPC_KEY_SIGRES;
+
+            // write the function name 
+            serializeTight<char*>(_functionName, reply, &wptr);
+
+            // write return-values count, and type: 
+            if constexpr(is_tuple<Ret>::value){
+              // serialize using recursive rollup, 
+              reply[wptr ++] = _numRets;
+              // TODO: should be writeTupleSignatures 
+              writeTupleKeys(resultStorage.result, reply, &wptr);
+            } else {
+              // if we have just one value, 
+              reply[wptr ++] = _numRets;
+              reply[wptr ++] = getTypeKey<Ret>();
+            }
+
+            // write args count, type and names 
+            reply[wptr ++] = _numArgs;
+            // add a type key to the payload for each arg in Args...
+            // this is a "fold expression" ... which is not available until c++17 
+            // instead, we could use recursive template expansions 
+            (..., (reply[wptr++] = getTypeKey<Args>())); 
+
+            // write in return names, 
+            for(uint8_t a = 0; a < _numRets; a ++){
+              serializeTight<char*>(_retNames[a], reply, &wptr);
+            }
+
+            // finally arg names, 
+            for(uint8_t a = 0; a < _numArgs; a ++){
+              serializeTight<char*>(_argNames[a], reply, &wptr);
+            }
+
+            // we are done, ship it back: 
+            return wptr; 
+          }
+        case PRPC_KEY_FUNCCALL:
+          {
+            // response key and msg id 
+            size_t wptr = 0;
+            reply[wptr ++] = PRPC_KEY_FUNCRETURN;
+            // we'll be reading starting at [1] in the packet (after the key) 
+            size_t rptr = 1;
+            // we have four cases to deal with: void-void, void-args, ret-void, ret-args, 
+            // another note on the compiler availability: `constexpr` is only available since c++17, 
+            // so it might be that we need to specialize templates for each case void-void...ret-args etc 
+            if constexpr (sizeof...(Args) == 0){
+              if constexpr (std::is_same<Ret, void>::value){
+                // we are void-void, 
+                _funcPtr();
+              } else {
+                // ret-void, 
+                resultStorage.result = _funcPtr();
+              }
+            } else {
+              // each of the following conditions has args, so deserialize those:
+              argStorage.tuple = deserializeArgs<Args...>(data, &rptr);
+              if constexpr (std::is_same<Ret, void>::value) {
+                // this is void-args, we use 'apply' but there is no storage of the return type
+                // note that std::apply is only available since c++17, so this would also require 
+                // rework, although (since tuples are available since c++14), it should be possible 
+                // again using recursive template expansion... 
+                std::apply(_funcPtr, argStorage.tuple);
+              } else {
+                // this is ret-args, we use 'apply' and stash the result, 
+                resultStorage.result = std::apply(_funcPtr, argStorage.tuple);
+              }               
+            }
+            // in both cases where we have some result, we serialize:
+            if constexpr (!(std::is_same<Ret, void>::value)){
+              // if we have a return tuple... 
+              if constexpr(is_tuple<Ret>::value){
+                // serialize using recursive rollup, 
+                // OSAP_DEBUG("hello tuple serdes");
+                serializeTuple(resultStorage.result, reply, &wptr);
+              } else {
+                // if we have just one value, 
+                serializeTight<Ret>(resultStorage.result, reply, &wptr);
+              }
+            }
+            // currently void returners simply donot serialize anything on the way up,  
+            // so that'd be it, we can sendy:
+            return wptr;
+          }
+        default:
+          OSAP_Runtime::error("bad onPacket key \nto PRPC");
+          return 0;
+      }
+    }
+
+  private: 
+    // the pointer, etc... 
+    Ret(*_funcPtr)(Args...) = nullptr;
+    uint8_t _numArgs = 0;
+    uint8_t _numRets = 0; 
+    char _functionName[PRPC_FUNCNAME_MAX_CHAR];
+    char _argNames[PRPC_MAX_ARGS][PRPC_ARGNAME_MAX_CHAR];
+    char _retNames[PRPC_MAX_ARGS][PRPC_ARGNAME_MAX_CHAR]; // 33.0 21.4 
+    // we allocate storage for the function results and args here to avoid stack overflow, 
+    // and these both use template helpers that simply store nothing when no args or no return type is present 
+    ResultStorage<Ret, std::is_same<Ret, void>::value> resultStorage;
+    ArgStorage<Args...> argStorage;
+};
+
+
+#endif 
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/port_rpc_helpers.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/port_rpc_helpers.h
new file mode 100644
index 0000000..6661b02
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/presentation/port_rpc_helpers.h
@@ -0,0 +1,120 @@
+// template oddities, b-sides and remixes for the auto rpc class 
+#ifndef PORT_RPC_HELPER_H_
+#define PORT_RPC_HELPER_H_
+
+#include <Arduino.h>
+#include "../utils/serdes.h"
+#include <tuple>
+#include <type_traits>
+
+#define PRPC_FUNCNAME_MAX_CHAR 32
+#define PRPC_MAX_ARGS 8
+#define PRPC_ARGNAME_MAX_CHAR 16
+
+// ------------------------------------ 
+// A helper type trait to check if a type is void and provide a suitable return type
+template<typename T>
+struct ReturnType {
+    using Type = T;
+};
+
+template<>
+struct ReturnType<void> {
+    using Type = Unit;
+};
+
+// ------------------------------------ 
+// a utility to check if return values are tuples or not 
+// basically... these specialize into false_type or true_type depending on their 
+// specialization 
+template<typename T>
+struct is_tuple : std::false_type {};
+
+template<typename... Args>
+struct is_tuple<std::tuple<Args...>> : std::true_type {};
+
+
+// ------------------------------------ 
+// Storage for non-void return types
+template<typename Ret, bool isVoid>
+struct ResultStorage {
+    Ret result;
+};
+
+// Specialization for void return types that does not have a 'result' member
+template<typename Ret>
+struct ResultStorage<Ret, true> { };
+
+
+// ------------------------------------ 
+// one last trick for args storage ? 
+template<typename... Args>
+struct ArgStorage {
+  std::tuple<Args...> tuple;
+};
+
+// specialization for funcs with no args, 
+template<>
+struct ArgStorage<>{ };
+
+
+// ------------------------------------ recursive serializer 
+template<typename ...Types, std::size_t... I>
+void serializeTupleImpl(uint8_t* buffer, size_t* wptr, const std::tuple<Types...>& t, std::index_sequence<I...>){
+  (serializeTight<Types>(std::get<I>(t), buffer, wptr), ...);
+}
+
+template<typename... Types>
+void serializeTuple(const std::tuple<Types...>& t, uint8_t* buffer, size_t* wptr){
+  return serializeTupleImpl<Types...>(buffer, wptr, t, std::index_sequence_for<Types...>{});
+}
+
+
+// ------------------------------------ recursive keys-writer 
+template <typename... Types>
+void writeTupleKeys(const std::tuple<Types...>& t, uint8_t* buffer, size_t* wptr) {
+  // writeTuple(buffer, wptr, t, std::index_sequence_for<Types...>{});
+  (..., (buffer[(*wptr) ++] = getTypeKey<Types>()));
+}
+
+
+// ------------------------------------ recursive deserializer for Args... pack 
+template<typename... Args, std::size_t... I>
+auto deserializeArgsImpl(uint8_t* data, size_t* rptr, std::index_sequence<I...>) {
+    return std::make_tuple(deserializeTight<Args>(data, rptr)...);
+}
+
+template<typename... Args>
+auto deserializeArgs(uint8_t* data, size_t* rptr) {
+    return deserializeArgsImpl<Args...>(data, rptr, std::index_sequence_for<Args...>{});
+}
+
+
+// ------------------------------------ 
+// copies from comma-delimited char[] into char[][], 
+void argSplitter(const char* input, char output[PRPC_MAX_ARGS][PRPC_ARGNAME_MAX_CHAR]){
+  int itemIndex = 0, charIndex = 0;
+  const char* p = input;
+
+  while (*p && itemIndex < PRPC_MAX_ARGS) {
+    if (*p == ',' || *p == ' ') {
+      if (*p == ',' && charIndex > 0) { // End of an item
+        output[itemIndex][charIndex] = '\0'; // Null-terminate the current item
+        itemIndex++;
+        charIndex = 0;
+      }
+      p++; // Skip the comma or space
+    } else {
+      if (charIndex < PRPC_ARGNAME_MAX_CHAR - 1) { // Check for max char limit
+        output[itemIndex][charIndex++] = *p; // Copy character
+      }
+      p++; // Move to the next character
+    }
+  }
+
+  if (charIndex > 0) { // Handle the last item if there's no trailing comma
+    output[itemIndex][charIndex] = '\0';
+  }
+}
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/runtime/runtime.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/runtime/runtime.cpp
new file mode 100644
index 0000000..a6869d9
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/runtime/runtime.cpp
@@ -0,0 +1,409 @@
+// runtime !
+
+#include "runtime.h"
+#include "../packets/packets.h"
+#include "../utils/serdes.h"
+#include "../utils/random_sequence_gen.h"
+#include "../utils/platform_flash.h"
+#include "../utils/micros_64.h"
+#include "../utils/debug.h"
+#include "../osap_config.h"
+
+#include "../discovery/netresponder.h"
+
+// ---------------------------------------------- Singleton
+
+OSAP_Runtime* OSAP_Runtime::instance = nullptr;
+
+OSAP_Runtime* OSAP_Runtime::getInstance(void){
+  return instance;
+}
+
+// and a coupl'a static-stashes 
+
+void (*OSAP_Runtime::printFuncPtr)(String) = nullptr;
+
+Route OSAP_Runtime::_route;
+
+uint8_t OSAP_Runtime::_payload[OSAP_CONFIG_PACKET_MAX_SIZE];
+
+// ---------------------------------------------- Message Stack and Constructor
+
+// stack size modifies how much memory the device sucks, 
+// it should be configured per-micro-platform (?) or sth, 
+// we need some arduino help... other options are to expose 
+// memory allocation to the user, but it's a little awkward 
+
+VPacket _stack[OSAP_CONFIG_STACK_SIZE];
+
+OSAP_Runtime::OSAP_Runtime(const char* _typeName, const char* _name){
+  // we're the one & only, unless we aren't, 
+  if(instance != nullptr) return; 
+  instance = this;
+  
+  // collect stack from the file scope,
+  stack = _stack;
+  stackSize = OSAP_CONFIG_STACK_SIZE;
+
+  // copy and check names, 
+  strncpy(typeName, _typeName, OSAP_PROPERNAMES_MAX_CHAR);
+  typeName[OSAP_PROPERNAMES_MAX_CHAR - 1] = '\0';
+
+  // startup the platform flash (req'd for next steps) 
+  flashBegin();
+
+  // now we have a few cases for the module's name:
+  if(strcmp(_name, "anon") == 0){
+    if(flashNameStorageCheck()){
+      // pull from flash to name, 
+      flashCopySavedNameInto(moduleName);
+    } else {
+      // generate a randy five-chars after the given typeName_ 
+      strncpy(moduleName, typeName, OSAP_PROPERNAMES_MAX_CHAR);
+      randomGenAddChars(moduleName, OSAP_PROPERNAMES_MAX_CHAR);
+    }
+  } else {
+    // when osap(typeName, properName) is used, always start-up with 
+    // the given proper name: these are manually-configured systems 
+    strncpy(moduleName, _name, OSAP_PROPERNAMES_MAX_CHAR);
+    moduleName[OSAP_PROPERNAMES_MAX_CHAR - 1] = '\0';    
+  }
+
+  // and we build our responder on port-zero by default, 
+  responder = new NetResponder();
+
+} // end cnstructor 
+
+OSAP_Runtime::OSAP_Runtime(const char* _typeName):OSAP_Runtime(_typeName, "anon"){};
+
+void OSAP_Runtime::begin(void){
+  // startup linked-list, 
+  stackReset(stack, stackSize);
+  // for each link in list, do link->begin();
+  for(uint16_t l = 0; l < linkCount; l ++){
+    links[l]->begin();
+  }
+  // for each port, do port->begin();
+  for(uint16_t p = 0; p < portCount; p ++){
+    ports[p]->begin();
+  }
+}
+
+// ---------------------------------------------- Time Service
+
+uint64_t OSAP_Runtime::calculateSystemMicroseconds(bool interval = false){
+  // get current stamp w/ underlying clock and stash that pt for long integral 
+  uint64_t underlyingStamp = micros64();
+  uint64_t underlyingInterval = underlyingStamp - underlyingStampPrevious;
+  // TODO: can we avoid having 'underlyingStampPrevious' ? 
+  if(interval) underlyingStampPrevious = underlyingStamp;
+  // return timeBaseAtLastCalculation + underlyingInterval; 
+  // we can shim that interval... 
+  fpint64_t shimmedInterval = fp_mult64x64_bigLittle(fp_int64ToFixed64(underlyingInterval), clockSkew);
+  return timeBaseAtLastCalculation + fp_fixed64ToInt64(shimmedInterval);
+  // return fp_fixed64ToInt64(shimmedInterval);
+}
+
+uint64_t OSAP_Runtime::getSystemMicroseconds(void){
+  return calculateSystemMicroseconds(false);
+}
+
+void OSAP_Runtime::setSystemMicroseconds(uint64_t _us){
+  timeBaseAtLastCalculation = _us; 
+  underlyingStampPrevious = micros64();
+}
+
+float OSAP_Runtime::getClockSkewAsFloat(void){
+  return fp_fixed64ToFloat32(clockSkew);
+}
+
+void OSAP_Runtime::timeLoop(void){
+  // occasionally accumulate the interval 
+  if(underlyingStampPrevious + timeCalcInterval < micros64()){
+    timeBaseAtLastCalculation = calculateSystemMicroseconds(true);
+  }
+  // occasionally ping others for time measurements 
+  if(timeQueryLastTime + timeQueryInterval < micros64()){
+    if(!claimPacketCheck(this)) return;
+    timeQueryLastTime = micros64();
+    // rollover whomst we will poll, 
+    timeQueryRecipient ++;
+    if(timeQueryRecipient >= linkCount) timeQueryRecipient = 0;
+    // author a new outgoing packet (will need to modify this for us...)
+    VPacket* pck = claimPacketFromStack(this);
+    // it'll go along such-and-such a route: 
+    _route.reset();
+    _route.addLink(timeQueryRecipient);
+    _route.setTimeToLive(32000);
+    _route.setMaxSegmentSize(64);
+    // assemble a datagram, 
+    size_t wptr = 0;
+    _payload[wptr ++] = 0 | PKEY_SMSG << 6 | SKEY_TIME_STAMP_REQ;
+    // we use this time *just* to calculate an RTT, so we can use the underlying, 
+    // although in high-skew scenarios this may be non optimal (?) the noise floor is 
+    // much higher than clock shim digits 
+    serializeTight<uint64_t>(micros64(), _payload, &wptr);
+    // ship-it 
+    stuffPacketRaw(pck, &_route, _payload, wptr);
+  }
+}
+
+void OSAP_Runtime::timeOnStampReturn(uint8_t link, uint8_t tier, uint64_t txTime, uint64_t stamp){
+  // now we can do rtt, which is based on our underlying clock 
+  // and use that to estimate their current time 
+  uint32_t rtt = micros64() - txTime; 
+  uint64_t senderTime = stamp + rtt / 2;
+  int64_t offset = senderTime - getSystemMicroseconds();
+
+  // we'll store each link's measured offset and reported tier 
+  perLinkTimeStats[link].offset = offset; 
+  perLinkTimeStats[link].tier = tier;
+
+  // then we should recalculate: using our first reference to the highest tier
+  uint8_t maxTier = 255;
+  uint8_t tierCount = 0; 
+  for(uint8_t l = 0; l < linkCount; l ++){
+    if(perLinkTimeStats[l].tier < maxTier) {
+      maxTier = perLinkTimeStats[l].tier;
+      if(maxTier != 255) ourTimeTier = maxTier + 1;
+    }
+  }
+  for(uint8_t l = 0; l < linkCount; l ++){
+    if(perLinkTimeStats[l].tier == maxTier) tierCount ++;
+  }
+
+  // we should only bother updating our own parameters if we have just rx'd new info 
+  // from the max tier:
+  if(maxTier != tier) return;
+
+  // TODO would be to add an average when we have multiple counts at the max tier... 
+  // as would probably be the case in big autonomous meshes, for now we just take the first: 
+  if(!tierCount) return; 
+  int64_t targetOffset = 0;
+  for(uint8_t l = 0; l < linkCount; l ++){
+    if(perLinkTimeStats[l].tier == maxTier){
+      targetOffset = perLinkTimeStats[l].offset;
+      break; 
+    }
+  }
+
+  // then we run our olden algo:   
+  // if their clock is ahead by more than 100ms, we should use it as a baseline:
+  // but only if their tier out-strips ours 
+  if((useHardOffsetJumps && targetOffset > clockOffsetHardTrigger) || (targetOffset < -clockOffsetHardTrigger && maxTier < ourTimeTier)){
+    setSystemMicroseconds(timeBaseAtLastCalculation + targetOffset);
+    clockSkew = fp_int64ToFixed64(1);
+    lastHardReset = micros64();
+  } else if(useHardOffsetJumps && targetOffset > clockOffsetHardTrigger){
+    setSystemMicroseconds(timeBaseAtLastCalculation + targetOffset);
+    clockSkew = fp_int64ToFixed64(1);
+    lastHardReset = micros64();
+  } else if (targetOffset < - clockOffsetHardTrigger){
+    // an important do-nothing step, lest we chase tails 
+  } else {
+    // before we update the skew, we need to accumulate using the most recent skew, 
+    // otherwise we risk shifting the current time into the past, or jumping to the future, etc 
+    timeBaseAtLastCalculation = calculateSystemMicroseconds(true);
+    // now we can set, basically 1.0 +/- some tiny skew, 
+    // which is just proportional to the offset 
+    uint64_t propNow = fp_mult64x64_bigLittle(fp_int64ToFixed64(targetOffset), clockSkewProportionalTerm);
+    // and which is filtered, 
+    propTerm = 
+      fp_mult64x64_bigLittle(propTerm, propFilterAlpha) + 
+      fp_mult64x64_bigLittle(propNow, propFilterOneMinusAlpha);
+    // let's clamp it, 
+    if(propTerm > fp_float32ToFixed64(0.00015F)) propTerm = fp_float32ToFixed64(0.00015F);
+    if(propTerm < fp_float32ToFixed64(-0.00015F)) propTerm = fp_float32ToFixed64(-0.00015F);
+    // then term +/- 1 is the skew... 
+    clockSkew = fp_int64ToFixed64(1) + propTerm;
+  }
+}
+
+
+// ---------------------------------------------- Core Runtime Loop 
+
+// at most we can handle every single packet in 
+// the system during one loop, so here's the ordered list of 'em
+VPacket* packets[OSAP_CONFIG_STACK_SIZE];
+
+void OSAP_Runtime::loop(void){
+  // (00) run time service 
+  timeLoop();
+
+  // (0) check the time... this should use system time eventually
+  uint32_t now = micros();
+
+  // (1) run each links' loop code:
+  for(uint16_t l = 0; l < linkCount; l ++){
+    if(links[l] != nullptr) links[l]->loop();
+  }
+
+  // (2) collect paquiats from the staquiat,
+  size_t count = stackGetPacketsToService(packets, OSAP_CONFIG_STACK_SIZE);
+  if(count > debug_stackServiceHighWaterMark) debug_stackServiceHighWaterMark = count;
+
+  // (2.5 TODO) packets are sorted insertion-order already, in the future we can 
+  // re-sort by timeToLive, 
+
+  // (3) operate per-packet, 
+  for(uint8_t p = 0; p < count; p ++){
+
+    // (3:1) time out deadies, 
+    #warning TODO: TIME TO LIVE
+    if(packets[p]->serviceDeadline < now){
+      OSAP_DEBUG("packet t/o: " + String(packets[p]->data[packets[p]->data[0]]));
+      debug_totalPacketsTimedOut ++;
+      relinquishPacketToStack(packets[p]);
+      continue;
+    }
+
+    // (3:2) service the packet's instruction, 
+    // ... pck[0] is a pointer to the active instruction, 
+    // so pck[pck[0]] == OPCODE, basically 
+    VPacket* pck = packets[p];
+    uint8_t ptr = pck->data[0];
+    switch(pck->data[ptr] >> 6){
+      // -------------------- Packets destined for a port in this runtime:
+      case PKEY_DGRM:
+        {
+          // ... haven't tested this bitwise logic yet !
+          uint16_t sourceIndex = (uint16_t)(pck->data[ptr] & 0b00001111) << 6 | (pck->data[ptr + 1] & 0b11111100) >> 2;
+          uint16_t destinationIndex = (uint16_t)(pck->data[ptr + 1] & 0b00000011) << 2 | pck->data[ptr + 2];
+          if(destinationIndex < portCount && ports[destinationIndex] != nullptr){
+            // we want to hand the recipient the route *back to* the sender, 
+            getRouteFromPacket(pck, &_route);
+            _route.reverse();
+            // copying the data out, since pck is potentially re-allocated during next steps 
+            size_t payloadLen = pck->len - (ptr + 3);
+            memcpy(_payload, &(pck->data[ptr + 3]), payloadLen);
+            // now we can de-allocate this pck and hand the datagram off, 
+            relinquishPacketToStack(pck);
+            ports[destinationIndex]->onPacket(_payload, payloadLen, &_route, sourceIndex);
+          } else {
+            OSAP_ERROR("dgrm for non-existent port: " + String(destinationIndex));
+            relinquishPacketToStack(pck);
+          }
+        }
+        break;
+      // -------------------- Packet to forwards along a point link 
+      case PKEY_LFWD:
+        {
+          uint8_t index = pck->data[ptr] & 0b00011111;
+          if(index < linkCount && links[index] != nullptr){
+            if(links[index]->clearToSend()){
+              // TODO: need to decriment the packet's time-to-live (!) 
+              links[index]->send(pck->data, pck->len);
+              relinquishPacketToStack(pck);
+            }
+          } else {
+            OSAP_ERROR("pfwd for non-existent link: " + String(index));
+            relinquishPacketToStack(pck);
+          }
+        }
+        break;
+      // -------------------- Packet to forwards along a bus link
+      case PKEY_BFWD:
+        // TODO: busses, lol 
+        OSAP_DEBUG("bus-fwds key in the runtime...");
+        relinquishPacketToStack(pck);
+        break;
+      // -------------------- System Messages (mostly for discovery)
+      case PKEY_SMSG:
+        handleSystemMessage(pck);
+        break;
+    } // end switch 
+  } // end for-p-in-packets 
+} // end loop 
+
+void OSAP_Runtime::handleSystemMessage(VPacket* pck){
+  uint8_t ptr = pck->data[0];
+  switch(pck->data[ptr] & 0b00011111){
+      // -------------------- Time Service  
+    case SKEY_TIME_STAMP_REQ:
+      {
+        // stuff a stamp *trailing* the sender's own, which is at [1] (8 byte)
+        _payload[0] = 0 | PKEY_SMSG << 6 | SKEY_TIME_STAMP_RES;
+        // sender's tx time is in there, copy it over:
+        memcpy(_payload + 1, pck->data + ptr + 1, 8);
+        // and stuff ours in the trunk; 
+        size_t wptr = 9;
+        serializeTight<uint64_t>(getSystemMicroseconds(), _payload, &wptr);
+        serializeTight<uint8_t>(ourTimeTier, _payload, &wptr);
+        // sendy 
+        reply(pck, _payload, 18);
+      }
+      break;
+    case SKEY_TIME_STAMP_RES:
+      {
+        size_t rptr = ptr + 1;
+        // our tx time was a stamp from our *underlying* clock 
+        uint64_t txTime = deserializeTight<uint64_t>(pck->data, &rptr);
+        // if this was tx'd prior to a hard reset to our own clock, we should ignore the stamp, 
+        if(lastHardReset < txTime){
+          // their stamp is based on their *system* clock (our target) 
+          uint64_t stamp = deserializeTight<uint64_t>(pck->data, &rptr);
+          // and their tier:
+          uint8_t tier = deserializeTight<uint8_t>(pck->data, &rptr);
+          // these only ever hop once, so incoming port is in a fixed location:
+          uint8_t link = pck->data[5] & 0b00111111;
+          // now we can do the action 
+          timeOnStampReturn(link, tier, txTime, stamp);
+        }
+        // exit and give up the packet 
+        relinquishPacketToStack(pck);
+      }
+      break;
+    // inspect and mux with 
+  }
+
+}
+
+void OSAP_Runtime::reply(VPacket* pck, uint8_t* data, size_t len){
+  // extract the route & reverse it, 
+  getRouteFromPacket(pck, &_route);
+  // OSAP_DEBUG(OSAP_DEBUG_PRINT_ROUTE(&_route));
+  _route.reverse();
+  // OSAP_DEBUG(OSAP_DEBUG_PRINT_ROUTE(&_route));
+  // since the packet is already allocated (wherever the msg was sourced)
+  // we can just bonk it back in, i.e. re-write to the same data location:
+  stuffPacketRaw(pck, &_route, data, len);
+  // that's actually all there is to it (!) the reply is now loaded in, runtime collects & manages 
+}
+
+// ---------------------------------------------- Debug Funcs and Attach-er
+
+void OSAP_Runtime::attachDebugFunction(void (*_printFuncPtr)(String)){
+  OSAP_Runtime::printFuncPtr = _printFuncPtr;
+}
+
+void OSAP_Runtime::error(String msg){
+  if(printFuncPtr == nullptr) return;
+  OSAP_Runtime::printFuncPtr(msg);
+}
+
+void OSAP_Runtime::debug(String msg){
+  if(printFuncPtr == nullptr) return;
+  OSAP_Runtime::printFuncPtr(msg);
+}
+
+#ifdef OSAP_CONFIG_INCLUDE_DEBUG_MSGS
+
+String OSAP_Runtime::printRoute(Route* route){
+  String msg;
+  // this could be ~ fancier, i.e. decoding as well... 
+  // see routes.ts::print for an example
+  for(uint8_t p = 0; p < route->encodedPathLen; p ++){
+    msg += String(route->encodedPath[p]) + ", ";
+  }
+  return msg;
+}
+
+String OSAP_Runtime::printPacket(VPacket* pck){
+  String msg;
+  for(uint8_t b = 0; b < pck->len; b ++){
+    msg += String(pck->data[b]) + ",";
+  }
+  return msg;
+}
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/runtime/runtime.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/runtime/runtime.h
new file mode 100644
index 0000000..fd7f7d2
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/runtime/runtime.h
@@ -0,0 +1,148 @@
+// runtime !
+
+#ifndef RUNTIME_H_
+#define RUNTIME_H_
+
+#include <Arduino.h>
+#include "../osap_config.h"
+#include "../packets/routes.h"
+#include "../utils/fp_clock_utils.h"
+
+class NetResponder;
+class VPacket;
+class VPort;
+class LinkGateway;
+
+typedef struct TimeStats {
+  uint8_t tier = 255;
+  uint64_t lastRx = 0;
+  // this should be nanoseconds, right ? 
+  // maybe we need to redo ... some more ... 
+  int64_t offset = 0;
+} TimeStats;
+
+class OSAP_Runtime {
+  public:
+    // con-structor, 
+    OSAP_Runtime(const char* _typeName, const char* _name);
+    OSAP_Runtime(const char* _typeName);
+
+    // startup the OSAP instance and link layers 
+    void begin(void);
+    // operate the runtime 
+    void loop(void);
+
+    // ute-aids, 
+    void attachDebugFunction(void (*_printFuncPtr)(String));
+    // and debug-'ers 
+    static void error(String msg);
+    static void debug(String msg);
+
+    // big-debuggers we compile guard... 
+    #ifdef OSAP_CONFIG_INCLUDE_DEBUG_MSGS
+    static String printRoute(Route* route);
+    static String printPacket(VPacket* pck);
+    #endif 
+
+    // time service API 
+    uint64_t getSystemMicroseconds(void);
+    float getClockSkewAsFloat(void);
+
+    // instance-getter, for singleton-ness, 
+    static OSAP_Runtime* getInstance(void);
+
+    // lists ! 
+    VPort* ports[OSAP_CONFIG_MAX_PORTS];
+    uint16_t portCount = 0;
+    // TODO: links, not linkGateways ? 
+    LinkGateway* links[OSAP_CONFIG_MAX_LGATEWAYS];
+    uint16_t linkCount = 0;
+    // BGateway* bgateways[OSAP_CONFIG_MAX_BGATEWAYS];
+    uint16_t bgatewayCount = 0;
+
+    uint32_t debug_totalPacketsTimedOut = 0;
+    uint8_t debug_stackServiceHighWaterMark = 0;
+
+    uint8_t currentPacketHold = 0;
+    uint8_t maxPacketHold = 2;
+
+    // these should be private, then have a set of values we can get sats for 
+    fpint64_t clockSkew = fp_int64ToFixed64(1);
+    // how many us per second of skew, per us of offset ? 
+    fpint64_t clockSkewProportionalTerm = fp_float32ToFixed64(0.000001F);
+    fpint64_t propTerm = fp_int64ToFixed64(0);
+
+    fpint64_t propFilterAlpha = fp_float32ToFixed64(0.95F);
+    fpint64_t propFilterOneMinusAlpha = fp_float32ToFixed64(0.05F);
+
+    uint8_t ourTimeTier = 255;
+    
+    int64_t clockOffsetHardTrigger = 1000000;
+    bool useHardOffsetJumps = true;
+    // we can accumulate at some interval (microseconds)
+    uint64_t timeCalcInterval = 100000;
+    uint64_t underlyingStampPrevious = 0;
+    uint64_t timeBaseAtLastCalculation = 0;
+    // take note of hard resets, ignore returnals from prior op:
+    // rendered in systems' own clock 
+    uint64_t lastHardReset = 0;
+
+
+  private:
+    // only one among us 
+    static OSAP_Runtime* instance;
+
+    // discovery ute, 
+    friend class NetResponder; 
+    NetResponder* responder; 
+    
+    // stack (!) 
+    VPacket* stack;
+    size_t stackSize;
+
+    // names for the module,
+    // we allow 64-char typenames for modules 
+    char typeName[OSAP_PROPERNAMES_MAX_CHAR];
+    char moduleName[OSAP_PROPERNAMES_MAX_CHAR];
+
+    // utility objs / buffers 
+    static Route _route;
+    static uint8_t _payload[OSAP_CONFIG_PACKET_MAX_SIZE];
+
+    // graph traversals need to recognize loops, 
+    // so we stash a stateful id of last-to-scope-check-us, 
+    // so that traversers can connect dots... it's four random bytes 
+    uint8_t previousTraverseID[4] = { 0, 0, 0, 0 };
+
+    // time states and loop
+    void timeLoop(void);
+    void timeOnStampReturn(uint8_t link, uint8_t tier, uint64_t txTime, uint64_t stamp);
+
+    // measurements from our neighbours: 
+    // I suppose we could store this info in the link
+    TimeStats perLinkTimeStats[OSAP_CONFIG_MAX_LGATEWAYS];
+
+    uint64_t calculateSystemMicroseconds(bool interval);
+    void setSystemMicroseconds(uint64_t _us);
+
+    // we also do round-robin querying of our neighbours 
+    uint8_t timeQueryRecipient = 0;
+    uint64_t timeQueryLastTime = 0;
+    uint64_t timeQueryInterval = 100000;
+
+    // local ute for transport-query replies, 
+    // this stuffs replies back into the same packet-allocation, 
+    // so we don't need to re-allocate stack, etc, 
+    void reply(VPacket* pck, uint8_t* data, size_t len);
+
+    // and similar ute for us to send to neighbours... 
+    void send(VPacket* pck, Route* route, uint8_t* data, size_t len);
+
+    // local handler for system messages 
+    void handleSystemMessage(VPacket* pck);
+
+    // and those debug utes 
+    static void (*printFuncPtr)(String);
+};
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/links.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/links.cpp
new file mode 100644
index 0000000..465fcb2
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/links.cpp
@@ -0,0 +1,56 @@
+// links ! 
+
+#include "links.h"
+#include "../packets/packets.h"
+#include "../utils/serdes.h"
+#include "../utils/random_sequence_gen.h"
+
+#include "../utils/debug.h"
+
+LinkGateway::LinkGateway(OSAP_Runtime* _runtime, const char* _typeName, const char* _name){
+  // track our runtime, 
+  runtime = _runtime;
+
+  // don't over-insert: 
+  if(runtime->linkCount >= OSAP_CONFIG_MAX_LGATEWAYS){
+    OSAP_ERROR("too many links instantiated...");
+    return;
+  }
+  
+  // collect our index and stash ourselves in the runtime, 
+  index = runtime->linkCount;
+  runtime->links[runtime->linkCount ++] = this;
+
+  // copy-in names, respecting limits 
+  strncpy(typeName, _typeName, OSAP_TYPENAMES_MAX_CHAR);
+  strncpy(name, _name, OSAP_PROPERNAMES_MAX_CHAR);
+  // strncpy does not pad with spare '\0' in the case that charlimit exceeded 
+  typeName[OSAP_TYPENAMES_MAX_CHAR - 1] = '\0';
+  name[OSAP_PROPERNAMES_MAX_CHAR - 1] = '\0';
+
+  // names should be unique within a system, 
+  for(uint8_t p = 0; p < runtime->linkCount; p ++){
+    if(p == index) continue;
+    if(strcmp(name, runtime->links[p]->name) == 0){
+      randomGenAddChars(name, OSAP_PROPERNAMES_MAX_CHAR);
+    }
+  }
+}
+
+void LinkGateway::ingestPacket(VPacket* pck){
+  // this should be the case, badness if not
+  // since we should be only rx'ing from someone's prior LFWD instruction... 
+  if(pck->data[pck->data[0]] >> 6 != PKEY_LFWD){
+    OSAP_ERROR("bad PTR during packet ingest at link " + String(index));
+    relinquishPacketToStack(pck);
+    return;
+  }
+  // otherwise copy-in our index for rev-ersal,
+  pck->data[pck->data[0]] = PKEY_LFWD << 6 | index;
+  // bump the pointer up, 
+  pck->data[0] += 1;
+  // and calculate a service deadline, 
+  size_t rptr = 1;
+  uint16_t timeToLive = deserializeTight<uint16_t>(pck->data, &rptr);
+  pck->serviceDeadline = micros() + timeToLive;
+}
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/links.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/links.h
new file mode 100644
index 0000000..429b86a
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/links.h
@@ -0,0 +1,53 @@
+// links ! 
+
+#ifndef LINKS_H_
+#define LINKS_H_
+
+#include "../runtime/runtime.h"
+#include "../utils/keys.h"
+
+class LinkGateway {
+  public:
+    // -------------------------------- Link-Implementers Author these Funcs
+    // implement a .begin() to startup the link, 
+    virtual void begin(void) = 0;
+
+    // implement a function that is called once per runtime, 
+    virtual void loop(void) = 0;
+
+    // implement a function that reports whether/not 
+    // the link is ready to send new data 
+    virtual boolean clearToSend(void) = 0;
+
+    // implement a function that reports whether/not 
+    // the link is open... 
+    virtual boolean isOpen(void) = 0;
+
+    // implement a function that transmits this packet, 
+    virtual void send(uint8_t* data, size_t len) = 0;
+
+    // -------------------------------- Link-Implementers use these funcs 
+
+    // having written off-the-line data into `pck` during loop, 
+    // implementer calls this 
+    void ingestPacket(VPacket* pck);
+
+    // -------------------------------- Constructors
+
+    LinkGateway(OSAP_Runtime* _runtime, const char* _typeName, const char* _name);
+
+    // -------------------------------- Properties 
+
+    char typeName[OSAP_TYPENAMES_MAX_CHAR];
+    char name[OSAP_PROPERNAMES_MAX_CHAR];
+
+    // -------------------------------- States 
+    uint8_t currentPacketHold = 0;
+    uint8_t maxPacketHold = 2;
+
+    private:
+      OSAP_Runtime* runtime;
+      uint16_t index; 
+};
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/ports.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/ports.cpp
new file mode 100644
index 0000000..31e0d64
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/ports.cpp
@@ -0,0 +1,64 @@
+// pert pert pert 
+
+#include "ports.h"
+#include "../packets/packets.h"
+#include "../utils/random_sequence_gen.h"
+
+#include "../utils/debug.h"
+
+// default constructor 
+VPort::VPort(OSAP_Runtime* _runtime, const char* _typeName, const char* _name){
+  // track our runtime, 
+  runtime = _runtime;
+
+  // don't over-insert: 
+  if(runtime->portCount >= OSAP_CONFIG_MAX_PORTS){
+    OSAP_ERROR("too many ports instantiated...");
+    return;
+  } 
+  
+  // collect our index and stash ourselves in the runtime, 
+  index = runtime->portCount;
+  runtime->ports[runtime->portCount ++] = this;
+
+  // copy-in names, respecting limits 
+  strncpy(typeName, _typeName, OSAP_TYPENAMES_MAX_CHAR);
+  strncpy(name, _name, OSAP_PROPERNAMES_MAX_CHAR);
+  // strncpy does not pad with spare '\0' in the case that charlimit exceeded 
+  typeName[OSAP_TYPENAMES_MAX_CHAR - 1] = '\0';
+  name[OSAP_PROPERNAMES_MAX_CHAR - 1] = '\0';
+
+  // if we were given "anon" we rollup a new name, 
+  if(strcmp(_name, "anon") == 0){
+    strncpy(name, typeName, OSAP_PROPERNAMES_MAX_CHAR);
+    randomGenAddChars(name, OSAP_PROPERNAMES_MAX_CHAR);
+  }
+
+  // names should be unique within a system, 
+  for(uint8_t p = 0; p < runtime->portCount; p ++){
+    if(p == index) continue;
+    if(strcmp(name, runtime->ports[p]->name) == 0){
+      randomGenAddChars(name, OSAP_PROPERNAMES_MAX_CHAR);
+    }
+  }
+}
+
+uint8_t VPort::_payload[OSAP_CONFIG_PACKET_MAX_SIZE];
+
+void VPort::begin(void){};
+
+boolean VPort::clearToSend(void){
+  return claimPacketCheck(this);
+}
+
+void VPort::send(uint8_t* data, size_t len, Route* route, uint16_t destinationPort){
+  // allocate & check, 
+  VPacket* pck = claimPacketFromStack(this);
+  if(pck == nullptr) {
+    OSAP_ERROR("bad packet allocate on vport.send() at " + String(index));
+    return;
+  }
+  // stuff it, 
+  stuffPacketPortToPort(pck, route, index, destinationPort, data, len);
+  // I think that's actually it ? 
+}
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/ports.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/ports.h
new file mode 100644
index 0000000..ce26642
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/structure/ports.h
@@ -0,0 +1,49 @@
+// port port pert 
+// no bare ports: must implement thru child 
+
+#ifndef PORTS_H_
+#define PORTS_H_
+
+#include "../runtime/runtime.h"
+#include "../packets/routes.h"
+#include "../utils/keys.h"
+
+class VPort {
+  public:
+    // -------------------------------- Port-Facing API
+    // returns true if there is space available to write a packet into the vport 
+    boolean clearToSend(void);
+    // sends data of len along the provided route, to another port
+    // be sure to check if you are .clearToSend beforehand 
+    void send(uint8_t* data, size_t len, Route* route, uint16_t destinationPort);
+
+    // -------------------------------- Runtime-Facing API
+    virtual void begin(void);
+    virtual void onPacket(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort) = 0;
+
+    // -------------------------------- Constructors
+
+    // default constructor 
+    VPort(OSAP_Runtime* _runtime, const char* _typeName, const char* _name);
+    // delegates 
+    VPort(OSAP_Runtime* _runtime, const char* _typeName)
+      : VPort(_runtime, _typeName, "anon")
+    {}
+
+    // -------------------------------- Properties 
+    char typeName[OSAP_TYPENAMES_MAX_CHAR];
+    char name[OSAP_PROPERNAMES_MAX_CHAR];
+
+    // -------------------------------- States
+    uint8_t currentPacketHold = 0;
+    uint8_t maxPacketHold = 2;
+
+    // -------------------------------- stash-ute 
+    static uint8_t _payload[OSAP_CONFIG_PACKET_MAX_SIZE];
+
+  private:
+    OSAP_Runtime* runtime;   // our runtime... 
+    uint16_t index;     // our # 
+};
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/transport/sequential_receiver.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/transport/sequential_receiver.cpp
new file mode 100644
index 0000000..5e4b277
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/transport/sequential_receiver.cpp
@@ -0,0 +1,27 @@
+#include "sequential_receiver.h"
+#include "../utils/keys.h"
+#include "../utils/debug.h"
+
+OSAP_Sequential_Receiver::OSAP_Sequential_Receiver(const char* _typeName, const char* _name) : VPort(OSAP_Runtime::getInstance(), _typeName, _name) {};
+
+void OSAP_Sequential_Receiver::onPacket(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort){
+  if(data[0] != TKEY_SEQUENTIAL_TX){
+    OSAP_ERROR("rx'd oddball TKEY at sequence rx'er");
+    return; 
+  }
+
+  uint8_t msgID = data[1];
+  size_t replyLen = onData(data + 2, len - 2, sourceRoute, sourcePort, _payload + 2); 
+
+  // stuff our info, 
+  _payload[0] = TKEY_SEQUENTIAL_RX;
+  _payload[1] = msgID; 
+
+  // and ship that back out, 
+  #warning memory swappage needs more consideration; do we have race cond?
+  send(_payload, replyLen + 2, sourceRoute, sourcePort);
+}
+
+size_t OSAP_Sequential_Receiver::onData(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort, uint8_t* reply){
+  return 0;
+}
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/transport/sequential_receiver.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/transport/sequential_receiver.h
new file mode 100644
index 0000000..5146b56
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/transport/sequential_receiver.h
@@ -0,0 +1,84 @@
+
+#ifndef SEQUENTIAL_RX
+#define SEQUENTIAL_RX 
+
+#include "../structure/ports.h"
+
+class OSAP_Sequential_Receiver : public VPort {
+  public:
+    // -------------------------------- Constructors
+    OSAP_Sequential_Receiver(const char* _name, const char* _typeName);
+
+    // -------------------------------- Port-Facing API
+    // we override the onPacket handler of the port class, 
+    void onPacket(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort) override;
+
+    // and provide an overrideable to our consumer, 
+    virtual size_t onData(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort, uint8_t* reply); // = 0;
+
+};
+
+#endif 
+
+/*
+// there's a possible version of the same that uses a handover-style function ingest, 
+// but which then requires static functions to ingest; rather than instances of classes... 
+// it would be possible to allow for either style in the same object, I'm leaving that option out for clarity 
+
+// .h 
+class OSAP_Sequential_Receiver : public VPort {
+  public:
+    // -------------------------------- Constructors
+    // OSAP_Sequential_Receiver(const char* _name, size_t (*_onDataCallable)(uint8_t* data, size_t len, uint8_t* reply));
+    // for void returners 
+    // OSAP_Sequential_Receiver(const char* _name, void (*_onDataCallable)(uint8_t* data, size_t len, uint8_t* reply));
+
+    // -------------------------------- Port-Facing API
+    // we override the onPacket handler of the port class, 
+    void onPacket(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort) override;
+
+    // and provide an overrideable to our consumer, 
+    virtual void onData(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort) = 0;
+
+  // private:
+  //     size_t (*onDataCallableWithReply)(uint8_t* data, size_t len, uint8_t* reply) = nullptr;
+  //     void (*onDataCallableWithoutReply)(uint8_t* data, size_t len) = nullptr;
+
+};
+
+// .cpp 
+OSAP_Sequential_Receiver::OSAP_Sequential_Receiver(
+  const char* _name, 
+  size_t (*_onDataCallable)(uint8_t* data, size_t len, uint8_t* reply)
+  ) : VPort(OSAP_Runtime::getInstance(), "seqnc_rx", _name) 
+{
+  onDataCallableWithReply = _onDataCallable;
+}
+
+void OSAP_Sequential_Receiver::onPacket(uint8_t* data, size_t len, Route* sourceRoute, uint16_t sourcePort){
+  if(data[0] != TKEY_SEQUENTIAL_TX){
+    OSAP_ERROR("rx'd oddball TKEY at sequence rx'er");
+    return; 
+  }
+
+  uint8_t msgID = data[1];
+  size_t replyLen = 0; 
+
+  // call the attached function w/ an offset, 
+  // note: this is from Runtime::_payload to VPort::_payload temporary... 
+  if(onDataCallableWithReply != nullptr){
+    replyLen = onDataCallableWithReply(data + 2, len - 2, _payload + 2);
+  } else if (onDataCallableWithoutReply != nullptr){
+    onDataCallableWithoutReply(data + 2, len - 2);
+  }
+
+  // stuff our info, 
+  _payload[0] = TKEY_SEQUENTIAL_RX;
+  _payload[1] = msgID; 
+
+  // and ship that back out, 
+  #warning memory swappage needs more consideration; do we have race cond?
+  send(_payload, replyLen + 2, sourceRoute, sourcePort);
+}
+
+*/
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/debug.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/debug.h
new file mode 100644
index 0000000..28c68a2
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/debug.h
@@ -0,0 +1,23 @@
+
+#ifndef OSAP_DEBUG_H_
+#define OSAP_DEBUG_H_
+
+#include "../runtime/runtime.h"
+
+// debug w/ this...
+#ifdef OSAP_CONFIG_INCLUDE_DEBUG_MSGS
+#define OSAP_DEBUG(msg) OSAP_Runtime::debug(msg)
+#define OSAP_DEBUG_PRINT_ROUTE(route) OSAP_Runtime::printRoute(route)
+#define OSAP_DEBUG_PRINT_PACKET(pck) OSAP_Runtime::printPacket(pck)
+#else
+#define OSAP_DEBUG(msg)
+#endif
+
+// genny error msgs w/ this...
+#ifdef OSAP_CONFIG_INCLUDE_ERROR_MSGS
+#define OSAP_ERROR(msg) OSAP_Runtime::error(msg)
+#else
+#define OSAP_ERROR(msg)
+#endif
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/fp_clock_utils.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/fp_clock_utils.cpp
new file mode 100644
index 0000000..a6239f0
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/fp_clock_utils.cpp
@@ -0,0 +1,50 @@
+#include "fp_clock_utils.h"
+
+// I've picked 20 bits of precision, that means we can express down to 
+// 1ppm of skew - 1us per second... seems like enough to start, 
+// esp. since we can't measure any more than 1us offset anyways ! 
+
+// 20 bits decimal:          1 048 576
+// 44 bits integer: 17 592 186 044 416
+
+const int32_t fp_scale = 22;
+
+// this app typically multiplies one big by one little,
+// i.e. an offset by a filtering value, or an interval by the skew.
+// since after multiplication of 2^20 x 2^20 (1x1) we have only 2^22 bits, 
+// we guard such that big, little do not combine to overflow this during 
+// the intermediate step 
+const int64_t fp_int_big_max = (1 << (64 - 2 * fp_scale)) - 1;
+const int64_t fp_int_little_max = 2;
+
+// const int32_t   fp_int_max =    32767;
+// const int32_t   fp_int_min =   -32767;
+// const int64_t   fp_32b_max =    2147483647;
+// const int64_t   fp_32b_min =   -2147483647;
+
+int64_t fp_fixed64ToInt64(fpint64_t fixed){
+  return (fixed >> fp_scale);
+}
+
+float fp_fixed64ToFloat32(fpint64_t fixed){
+  return ((float)fixed / (float)(1 << fp_scale));
+}
+
+fpint64_t fp_int64ToFixed64(int64_t integer){
+  if(integer > fp_int_big_max) integer = fp_int_big_max;
+  if(integer < - fp_int_big_max) integer = - fp_int_big_max;
+  return (integer << fp_scale);
+}
+
+fpint64_t fp_float32ToFixed64(float flt){
+  if(flt > (float)fp_int_big_max) return fp_int64ToFixed64(fp_int_big_max);
+  if(flt < (float)(-fp_int_big_max)) return fp_int64ToFixed64(-fp_int_big_max);
+  return (flt * (float)(1 << fp_scale));
+}
+
+fpint64_t fp_mult64x64_bigLittle(fpint64_t big, fpint64_t little){
+  if(little > fp_int64ToFixed64(fp_int_little_max)) little = fp_int64ToFixed64(fp_int_little_max);
+  if(little < fp_int64ToFixed64(-fp_int_little_max)) little = fp_int64ToFixed64(-fp_int_little_max);
+  // return ((big * little) / (1 << fp_scale)); 
+  return ((big * little) >> fp_scale);
+}
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/fp_clock_utils.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/fp_clock_utils.h
new file mode 100644
index 0000000..b059428
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/fp_clock_utils.h
@@ -0,0 +1,16 @@
+#ifndef FP_CLOCK_UTILS_H_
+#define FP_CLOCK_UTILS_H_
+
+#include <Arduino.h>
+
+typedef int64_t fpint64_t;
+
+int64_t fp_fixed64ToInt64(fpint64_t fixed);
+float fp_fixed64ToFloat32(fpint64_t fixed);
+
+fpint64_t fp_int64ToFixed64(int64_t integer);
+fpint64_t fp_float32ToFixed64(float flt);
+
+fpint64_t fp_mult64x64_bigLittle(fpint64_t big, fpint64_t little);
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/keys.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/keys.h
new file mode 100644
index 0000000..9844ff9
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/keys.h
@@ -0,0 +1,70 @@
+// keys 
+
+#ifndef KEYS_H_
+#define KEYS_H_
+
+#include <Arduino.h>
+
+
+// are [0:1] in a byte 
+
+// system message 
+#define PKEY_SMSG 0  
+// point forwards: send the packt along a point-to-point link 
+#define PKEY_LFWD 1
+// bus forwards: send the packet on a bus 
+#define PKEY_BFWD 2  
+// port datagram: the packet is a datagram for a port in this module 
+#define PKEY_DGRM 3  
+
+
+// bits [3:7] (0-31) in a SMSG 
+
+// get runtime info
+#define SKEY_RTINFO_REQ 0
+#define SKEY_RTINFO_RES 1
+// get module type
+#define SKEY_MTYPEGET_REQ 2
+#define SKEY_MTYPEGET_RES 3
+// get module name
+#define SKEY_MNAMEGET_REQ 4
+#define SKEY_MNAMEGET_RES 5
+// set module name
+#define SKEY_MNAMESET_REQ 6
+#define SKEY_MNAMESET_RES 7
+// get point-link info
+#define SKEY_LINKINFO_REQ 8
+#define SKEY_LINKINFO_RES 9
+// get bus-link info
+#define SKEY_BUSINFO_REQ 10
+#define SKEY_BUSINFO_RES 11
+// get port info
+#define SKEY_PORTINFO_REQ 12
+#define SKEY_PORTINFO_RES 13
+
+// get time settings 
+#define SKEY_TIME_CONFIG_GET_REQ 18 
+#define SKEY_TIME_CONFIG_GET_RES 19 
+
+// set time settings 
+#define SKEY_TIME_CONFIG_SET_REQ 20 
+#define SKEY_TIME_CONFIG_SET_RES 21 
+
+// get a time stamp 
+#define SKEY_TIME_STAMP_REQ 16 
+#define SKEY_TIME_STAMP_RES 17 
+
+
+// transport protocol keys 
+#define TKEY_SEQUENTIAL_TX 31 
+#define TKEY_SEQUENTIAL_RX 32
+
+// basically enums 
+
+// keys for build types 
+#define BUILDTYPEKEY_EMBEDDED_CPP 50
+#define BUILDTYPEKEY_JAVASCRIPT 51
+#define BUILDTYPEKEY_PYTHON 52
+
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/micros_64.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/micros_64.cpp
new file mode 100644
index 0000000..7977187
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/micros_64.cpp
@@ -0,0 +1,19 @@
+#include "micros_64.h"
+
+uint32_t lastMicros = 0;
+uint64_t overflows = 0;
+
+uint64_t micros64(void){
+
+  // TODO: don't trust arduino's micros() - it goes backwards - forreal - sometimes 
+  // meaning that we need this threshold value... 
+  uint32_t currentMicros = micros();
+
+  if(currentMicros < lastMicros && (lastMicros - currentMicros) > 1000000){
+    overflows ++;
+  }
+
+  lastMicros = currentMicros; 
+
+  return (overflows << 32) | currentMicros;
+}
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/micros_64.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/micros_64.h
new file mode 100644
index 0000000..98c0e19
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/micros_64.h
@@ -0,0 +1,8 @@
+#ifndef MICROS_64_H_
+#define MICROS_64_H_
+
+#include <Arduino.h>
+
+uint64_t micros64(void);
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/platform_flash.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/platform_flash.cpp
new file mode 100644
index 0000000..7793de0
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/platform_flash.cpp
@@ -0,0 +1,51 @@
+#include "platform_flash.h"
+#include "../osap_config.h"
+
+// TODO: better per-platform guards, 
+// i.e. compile-time error "looks like your core is not supported..."
+// and FlashStorage_SAMD should be explicit #if defined(SAMD21...)
+#if defined(ARDUINO_ARCH_MBED_RP2040) || defined(ARDUINO_ARCH_RP2040) || defined(ARDUINO_TEENSY41) || defined(ARDUINO_TEENSY40)
+#include <EEPROM.h>
+#else
+#include <FlashStorage_SAMD.h>
+#endif
+
+const int MAGIC_SIGGY = 0xBEEFDEED;
+const int STORAGE_ADDR = 0;
+char tempChars[OSAP_PROPERNAMES_MAX_CHAR];
+int storedSignature;
+
+void flashBegin(void){
+  #if defined(ARDUINO_ARCH_MBED_RP2040) || defined(ARDUINO_ARCH_RP2040)
+  EEPROM.begin(4096);
+  #elif defined(ARDUINO_TEENSY41) || defined(ARDUINO_TEENSY40)
+  EEPROM.begin();
+  #endif 
+}
+
+bool flashNameStorageCheck(void){
+  EEPROM.get(STORAGE_ADDR, storedSignature);
+  return storedSignature == MAGIC_SIGGY;
+}
+
+void flashCopySavedNameInto(char* dest){
+  EEPROM.get(STORAGE_ADDR + sizeof(storedSignature), tempChars);
+  strncpy(dest, tempChars, OSAP_PROPERNAMES_MAX_CHAR);
+  dest[OSAP_PROPERNAMES_MAX_CHAR - 1] = '\0';
+}
+
+void flashSaveName(char* source){
+  strncpy(tempChars, source, OSAP_PROPERNAMES_MAX_CHAR);
+  tempChars[OSAP_PROPERNAMES_MAX_CHAR - 1] = '\0';
+  EEPROM.put(STORAGE_ADDR, MAGIC_SIGGY);
+  EEPROM.put(STORAGE_ADDR + sizeof(storedSignature), tempChars);
+  // seems as though this is and earle-only ? or it aint in the teensy, 
+  // and it aint in the docs: https://docs.arduino.cc/learn/built-in-libraries/eeprom/
+  #if defined(ARDUINO_ARCH_MBED_RP2040) || defined(ARDUINO_ARCH_RP2040)
+  EEPROM.commit();
+  #elif defined(ARDUINO_TEENSY41) || defined(ARDUINO_TEENSY40)
+  // EEPROM.commit();
+  #else 
+  EEPROM.commit();
+  #endif 
+}
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/platform_flash.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/platform_flash.h
new file mode 100644
index 0000000..62b3dcb
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/platform_flash.h
@@ -0,0 +1,13 @@
+#ifndef PLATFORM_SPECIFICS_H_
+#define PLATFORM_SPECIFICS_H_
+
+// at the moment, just flash codes per platform 
+
+#include <Arduino.h>
+
+void flashBegin(void);
+bool flashNameStorageCheck(void);
+void flashCopySavedNameInto(char* dest);
+void flashSaveName(char* name);
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/random_sequence_gen.cpp b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/random_sequence_gen.cpp
new file mode 100644
index 0000000..12c69b7
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/random_sequence_gen.cpp
@@ -0,0 +1,17 @@
+// randy bit gen 
+
+#include "random_sequence_gen.h"
+
+void randomGenAddChars(char* dest, size_t maxLen){
+  size_t len = strlen(dest);
+  if(len + 5 >= maxLen) len = maxLen - 5;
+  dest[len ++] = '_';
+  // seed random w/ timestamp - improvement would be unconnected ADC line or sth 
+  srand((uint)micros());
+  for(uint8_t c = 0; c < 5; c ++){
+    int randNum = rand() % 26;
+    dest[len + c] = randNum + 'a';
+  }
+  // finally, 
+  dest[len + 5] = '\0';
+}
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/random_sequence_gen.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/random_sequence_gen.h
new file mode 100644
index 0000000..abe9d8b
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/random_sequence_gen.h
@@ -0,0 +1,8 @@
+#ifndef RANDOM_SEQUENCE_GEN_H_
+#define RANDOM_SEQUENCE_GEN_H_
+
+#include <Arduino.h>
+
+void randomGenAddChars(char* dest, size_t maxLen);
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/serdes.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/serdes.h
new file mode 100644
index 0000000..89921ac
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/serdes.h
@@ -0,0 +1,356 @@
+#ifndef OSAP_SERDES_H_
+#define OSAP_SERDES_H_ 
+
+#include "serdes_keys.h"
+
+// --------------------------  
+// TODO: write serializeSafe() versions, which stash (and check for) keys ! 
+// TODO: serializers should be length-guarded: serializeTight(var, buffer, wptr, maxsize)
+//       ... they could simply stop writing in those cases 
+
+// --------------------------  Base Cases
+
+template<typename T>
+void serializeTight(T var, uint8_t* buffer, size_t* wptr){
+  static_assert(is_supported_type<T>::value, "One of the types you are trying to serialize \
+is not included in OSAP's type set. Please use only standard C types.");
+}
+
+template<typename T>
+T deserializeTight(uint8_t* buffer, size_t* rptr){
+  static_assert(is_supported_type<T>::value, "One of the types you are trying to deserialize \
+is not included in OSAP's type set. Please use only standard C types.");
+}
+
+// --------------------------  Boolean
+
+template<>inline 
+void serializeTight<bool>(bool var, uint8_t* buffer, size_t* wptr){
+  buffer[*wptr] = var ? 1 : 0;
+  (*wptr) ++;
+}
+
+template<>inline 
+bool deserializeTight<bool>(uint8_t* buffer, size_t* rptr){
+  bool result = buffer[*rptr];
+  (*rptr) ++;
+  return result; 
+}
+
+// -------------------------- Serialize Signed Integers 
+
+
+template<>inline 
+void serializeTight<int8_t>(int8_t var, uint8_t* buffer, size_t* wptr){
+  buffer[*wptr] = var; 
+  (*wptr) ++;
+}
+
+template<>inline 
+void serializeTight<int16_t>(int16_t var, uint8_t* buffer, size_t* wptr){
+  size_t offset = *wptr;
+  buffer[offset ++] = var & 255;
+  buffer[offset ++] = (var >> 8) & 255;
+  *wptr = offset;
+}
+
+template<>inline 
+void serializeTight<int32_t>(int32_t var, uint8_t* buffer, size_t* wptr){
+  size_t offset = *wptr;
+  buffer[offset ++] = var & 255;
+  buffer[offset ++] = (var >> 8) & 255;
+  buffer[offset ++] = (var >> 16) & 255;
+  buffer[offset ++] = (var >> 24) & 255;
+  *wptr = offset;
+}
+
+template<>inline 
+void serializeTight<int64_t>(int64_t var, uint8_t* buffer, size_t* wptr){
+  size_t offset = *wptr;
+  buffer[offset ++] = var & 255;
+  buffer[offset ++] = (var >> 8) & 255;
+  buffer[offset ++] = (var >> 16) & 255;
+  buffer[offset ++] = (var >> 24) & 255;
+  buffer[offset ++] = (var >> 32) & 255;
+  buffer[offset ++] = (var >> 40) & 255;
+  buffer[offset ++] = (var >> 48) & 255;
+  buffer[offset ++] = (var >> 56) & 255;
+  *wptr = offset; 
+}
+
+// -------------------------- Deserialize Signed Integers 
+
+template<>inline
+int8_t deserializeTight<int8_t>(uint8_t* buffer, size_t* rptr){
+  int8_t result = buffer[*rptr];
+  (*rptr) ++;
+  return result; 
+}
+
+
+template<>inline 
+int16_t deserializeTight<int16_t>(uint8_t* buffer, size_t* rptr){
+  int16_t result = 0;
+  size_t offset = *rptr;
+  result |= static_cast<int16_t>(buffer[offset ++]);
+  result |= static_cast<int16_t>(buffer[offset ++]) << 8;
+  *rptr = offset; 
+  return result;  
+}
+
+template<>inline 
+int32_t deserializeTight<int32_t>(uint8_t* buffer, size_t* rptr){
+  int32_t result = 0;
+  size_t offset = *rptr;
+  result |= static_cast<int32_t>(buffer[offset ++]);
+  result |= static_cast<int32_t>(buffer[offset ++]) << 8;
+  result |= static_cast<int32_t>(buffer[offset ++]) << 16;
+  result |= static_cast<int32_t>(buffer[offset ++]) << 24;
+  *rptr = offset; 
+  return result;  
+}
+
+template<>inline 
+int deserializeTight<int>(uint8_t* buffer, size_t* rptr){
+  return deserializeTight<int32_t>(buffer, rptr);
+}
+
+template<>inline 
+int64_t deserializeTight<int64_t>(uint8_t* buffer, size_t* rptr){
+  int64_t result = 0;
+  size_t offset = *rptr; 
+  result |= static_cast<int64_t>(buffer[offset ++]);
+  result |= static_cast<int64_t>(buffer[offset ++]) << 8;
+  result |= static_cast<int64_t>(buffer[offset ++]) << 16;
+  result |= static_cast<int64_t>(buffer[offset ++]) << 24;
+  result |= static_cast<int64_t>(buffer[offset ++]) << 32;
+  result |= static_cast<int64_t>(buffer[offset ++]) << 40;
+  result |= static_cast<int64_t>(buffer[offset ++]) << 48;
+  result |= static_cast<int64_t>(buffer[offset ++]) << 56;
+  *rptr = offset; 
+  return result;
+}
+
+// --------------------------  Serialize Unsigned Integers 
+
+template<>inline 
+void serializeTight<uint8_t>(uint8_t var, uint8_t* buffer, size_t* wptr){
+  buffer[*wptr] = var; 
+  (*wptr) ++;
+}
+
+template<>inline 
+void serializeTight<uint16_t>(uint16_t var, uint8_t* buffer, size_t* wptr){
+  size_t offset = *wptr;
+  buffer[offset ++] = var & 255;
+  buffer[offset ++] = (var >> 8) & 255;
+  *wptr = offset;
+}
+
+template<>inline 
+void serializeTight<uint32_t>(uint32_t var, uint8_t* buffer, size_t* wptr){
+  size_t offset = *wptr;
+  buffer[offset ++] = var & 255;
+  buffer[offset ++] = (var >> 8) & 255;
+  buffer[offset ++] = (var >> 16) & 255;
+  buffer[offset ++] = (var >> 24) & 255;
+  *wptr = offset;
+}
+
+template<>inline 
+void serializeTight<uint64_t>(uint64_t var, uint8_t* buffer, size_t* wptr){
+  size_t offset = *wptr;
+  buffer[offset ++] = var & 255;
+  buffer[offset ++] = (var >> 8) & 255;
+  buffer[offset ++] = (var >> 16) & 255;
+  buffer[offset ++] = (var >> 24) & 255;
+  buffer[offset ++] = (var >> 32) & 255;
+  buffer[offset ++] = (var >> 40) & 255;
+  buffer[offset ++] = (var >> 48) & 255;
+  buffer[offset ++] = (var >> 56) & 255;
+  *wptr = offset; 
+}
+
+// --------------------------  Deserialize Unsigned Integers 
+
+template<>inline
+uint8_t deserializeTight<uint8_t>(uint8_t* buffer, size_t* rptr){
+  uint8_t result = buffer[*rptr];
+  (*rptr) ++;
+  return result; 
+}
+
+template<>inline 
+uint16_t deserializeTight<uint16_t>(uint8_t* buffer, size_t* rptr){
+  uint16_t result = 0;
+  size_t offset = *rptr;
+  result |= static_cast<uint16_t>(buffer[offset ++]);
+  result |= static_cast<uint16_t>(buffer[offset ++]) << 8;
+  *rptr = offset; 
+  return result;
+}
+
+template<>inline 
+uint32_t deserializeTight<uint32_t>(uint8_t* buffer, size_t* rptr){
+  uint32_t result = 0;
+  size_t offset = *rptr;
+  result |= static_cast<uint32_t>(buffer[offset ++]);
+  result |= static_cast<uint32_t>(buffer[offset ++]) << 8;
+  result |= static_cast<uint32_t>(buffer[offset ++]) << 16;
+  result |= static_cast<uint32_t>(buffer[offset ++]) << 24;
+  *rptr = offset; 
+  return result;
+}
+
+template<>inline 
+uint64_t deserializeTight<uint64_t>(uint8_t* buffer, size_t* rptr){
+  uint64_t result = 0;
+  size_t offset = *rptr; 
+  result |= static_cast<uint64_t>(buffer[offset ++]);
+  result |= static_cast<uint64_t>(buffer[offset ++]) << 8;
+  result |= static_cast<uint64_t>(buffer[offset ++]) << 16;
+  result |= static_cast<uint64_t>(buffer[offset ++]) << 24;
+  result |= static_cast<uint64_t>(buffer[offset ++]) << 32;
+  result |= static_cast<uint64_t>(buffer[offset ++]) << 40;
+  result |= static_cast<uint64_t>(buffer[offset ++]) << 48;
+  result |= static_cast<uint64_t>(buffer[offset ++]) << 56;
+  *rptr = offset; 
+  return result;
+}
+
+// -------------------------- Serdes Floats  
+
+union union_float {
+  uint8_t bytes[4];
+  float f;
+};
+
+union union_double {
+  uint8_t bytes[8];
+  double d;
+};
+
+
+template<>inline
+void serializeTight<float>(float var, uint8_t* buffer, size_t* wptr){
+  union_float union_f;
+  union_f.f = var;
+  size_t offset = *wptr;
+  buffer[offset ++] = union_f.bytes[0]; 
+  buffer[offset ++] = union_f.bytes[1]; 
+  buffer[offset ++] = union_f.bytes[2]; 
+  buffer[offset ++] = union_f.bytes[3]; 
+  *wptr = offset; 
+}
+
+template<>inline 
+float deserializeTight<float>(uint8_t* buffer, size_t* rptr){
+  size_t offset = *rptr;
+  union_float union_f = {
+    .bytes = {
+      buffer[offset ++],
+      buffer[offset ++],
+      buffer[offset ++],
+      buffer[offset ++],
+    }
+  };
+  *rptr = offset; 
+  return union_f.f;
+}
+
+template<>inline
+void serializeTight<double>(double var, uint8_t* buffer, size_t* wptr){
+  union_double union_d;
+  union_d.d = var;
+  size_t offset = *wptr;
+  buffer[offset ++] = union_d.bytes[0]; 
+  buffer[offset ++] = union_d.bytes[1]; 
+  buffer[offset ++] = union_d.bytes[2]; 
+  buffer[offset ++] = union_d.bytes[3]; 
+  buffer[offset ++] = union_d.bytes[4]; 
+  buffer[offset ++] = union_d.bytes[5]; 
+  buffer[offset ++] = union_d.bytes[6]; 
+  buffer[offset ++] = union_d.bytes[7]; 
+  *wptr = offset; 
+}
+
+template<>inline 
+double deserializeTight<double>(uint8_t* buffer, size_t* rptr){
+  size_t offset = *rptr;
+  union_double union_d = {
+    .bytes = {
+      buffer[offset ++],
+      buffer[offset ++],
+      buffer[offset ++],
+      buffer[offset ++],
+      buffer[offset ++],
+      buffer[offset ++],
+      buffer[offset ++],
+      buffer[offset ++],
+    }
+  };
+  *rptr = offset; 
+  return union_d.d;
+}
+
+// -------------------------- Serdes Strings
+
+template<>inline 
+void serializeTight<String>(String var, uint8_t* buffer, size_t* wptr){
+  size_t len = var.length(); 
+  if(len > 128) len = 128; 
+  buffer[(*wptr) ++] = len;
+  for(uint8_t i = 0; i < len; i ++){
+    buffer[(*wptr) ++] = var.charAt(i);
+  } 
+}
+
+template<>inline 
+void serializeTight<char*>(char* var, uint8_t* buffer, size_t* wptr){
+  // buffer[(*wptr) ++] = TYPEKEY_STRING;
+  size_t len = strlen(var);
+  buffer[(*wptr) ++] = len;
+  // this should copy the string but not its trailing zero, 
+  memcpy(&(buffer[*wptr]), var, len);
+  (*wptr) += len;
+}
+
+// fk it, we can expose our serialized 'string' as an arduino String 
+// for convenience / familiarity... nothing in-system uses this, so 
+// flash shouldn't be affected until it's invoked by i.e. autoRPC w/ String args 
+template<>inline 
+String deserializeTight<String>(uint8_t* buffer, size_t* rptr){
+  // swappable buffer 
+  static char string_stash[256] = { 'h', 'e', 'l', 'l', 'o' };
+  // otherwise we have this len to unpack:
+  size_t len = buffer[(*rptr)];
+  // copy those into our stash and stuff a null terminator: 
+  memcpy(string_stash, buffer + (*rptr) + 1, len);
+  string_stash[len] = '\0';
+  // don't forget to increment the rptr accordingly
+  *rptr += len + 1;
+  // a new String, on the stack, to return: 
+  return string_stash;
+  // return String(string_stash);
+}
+
+// to deserialize char*, we use a different API where we deserialize straight 
+// into an available variable... which it should be possible to do for any type fwiw,
+// and maybe a good TODO if we want to save some cycles etc ? 
+
+template<typename T>
+void deserializeTightInto(T dest, uint8_t* buffer, size_t* rptr, size_t maxLen){}
+
+template<>inline
+void deserializeTightInto<char*>(char* dest, uint8_t* buffer, size_t* rptr, size_t maxLen){
+  // the byte at [rptr] denotes length of the incoming string, 
+  size_t len = buffer[(*rptr)];
+  if(len >= maxLen) len = maxLen - 1;
+  // copy-into, and append the delimeter 
+  memcpy(dest, buffer + (*rptr) + 1, len);
+  dest[len] = '\0';
+  // deserializers expect their read-pointers incremented 
+  *rptr += len;
+}
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/serdes_keys.h b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/serdes_keys.h
new file mode 100644
index 0000000..28a4860
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/src/osap/src/utils/serdes_keys.h
@@ -0,0 +1,198 @@
+#ifndef OSAP_SERDES_KEYS_H_
+#define OSAP_SERDES_KEYS_H_
+
+#include <Arduino.h>
+#include <type_traits>
+
+// --------------------------  Key Codes 
+
+//                      dec    name   bin          dec
+#define TYPEKEY_NULL    0   // null   0b00000000     0
+#define TYPEKEY_BOOL    1   // bool   0b00000001     1 
+#define TYPEKEY_UNKNWN  3   // unknwn 0b00000011     3 
+
+#define TYPEKEY_I8      16  // i8     0b00010000    16
+#define TYPEKEY_I16     17  // i16    0b00010001    17
+#define TYPEKEY_I32     18  // i32    0b00010010    18
+#define TYPEKEY_I64     19  // i64    0b00010011    19
+#define TYPEKEY_I128    20  // i128   0b00010100    20
+
+#define TYPEKEY_U8      24  // u8     0b00011000    24
+#define TYPEKEY_U16     25  // u16    0b00011001    25
+#define TYPEKEY_U32     26  // u32    0b00011010    26
+#define TYPEKEY_U64     27  // u64    0b00011011    27
+#define TYPEKEY_U128    28  // u128   0b00011100    28
+
+#define TYPEKEY_F16     33  // f16    0b00100001    33
+#define TYPEKEY_F32     34  // f32    0b00100010    34
+#define TYPEKEY_F64     35  // f64    0b00100011    35
+#define TYPEKEY_F128    36  // f128   0b00100100    36
+
+#define TYPEKEY_ASCII   48  // ascii  0b00110000    48
+#define TYPEKEY_UTF8    49  // utf8   0b00110001    49 
+
+#define TYPEKEY_ARRY    64  // arry   0b01000000    64
+#define TYPEKEY_TNSR    65  // tnsr   0b01000001    65
+
+// --------------------------  We declare a unit type, for void-passers
+
+struct Unit{};
+constexpr Unit unit{};
+
+// --------------------------  Key Getters w/ Existence Checkers 
+
+// ---------------- Unknowns:
+
+template<typename T>
+struct is_supported_type : std::false_type {};
+
+// the default / unspecialized will deploy when we have 
+// an unknown key: since we don't have codes for those, we should throw a 
+// compile time error 
+template<typename T>
+uint8_t getTypeKey(void){
+static_assert(is_supported_type<T>::value, "One of the types you have deployed as a function return, \
+or as an argument, is not included in OSAP's type set. Please use only standard C types.");
+  return TYPEKEY_UNKNWN;
+}
+
+// ---------------- Null / Void:
+
+template<>
+struct is_supported_type<Unit> : std::true_type {};
+
+template<>
+struct is_supported_type<void> : std::true_type {};
+
+template<> inline
+uint8_t getTypeKey<Unit>(void){
+  return TYPEKEY_NULL;
+}
+
+template<> inline
+uint8_t getTypeKey<void>(void){
+  return TYPEKEY_NULL;
+}
+
+// ---------------- Boolean:
+
+template<>
+struct is_supported_type<bool> : std::true_type {};
+
+template<> inline
+uint8_t getTypeKey<bool>(void){
+  return TYPEKEY_BOOL;
+}
+
+// ---------------- Signed Integers:
+
+template<>
+struct is_supported_type<int8_t> : std::true_type {};
+
+template<>
+struct is_supported_type<int16_t> : std::true_type {};
+
+template<>
+struct is_supported_type<int32_t> : std::true_type {};
+
+template<>
+struct is_supported_type<int> : std::true_type {};
+
+template<>
+struct is_supported_type<int64_t> : std::true_type {};
+
+template<> inline 
+uint8_t getTypeKey<int8_t>(void){
+  return TYPEKEY_I8;
+}
+
+template<> inline 
+uint8_t getTypeKey<int16_t>(void){
+  return TYPEKEY_I16;
+}
+
+template<> inline 
+uint8_t getTypeKey<int32_t>(void){
+  return TYPEKEY_I32;
+}
+
+template<> inline 
+uint8_t getTypeKey<int>(void){
+  return TYPEKEY_I32;
+}
+
+template<> inline 
+uint8_t getTypeKey<int64_t>(void){
+  return TYPEKEY_I64;
+}
+
+// ---------------- Unsigned Integers:
+
+template<>
+struct is_supported_type<uint8_t> : std::true_type {};
+
+template<>
+struct is_supported_type<uint16_t> : std::true_type {};
+
+template<>
+struct is_supported_type<uint32_t> : std::true_type {};
+
+template<>
+struct is_supported_type<uint64_t> : std::true_type {};
+
+template<> inline 
+uint8_t getTypeKey<uint8_t>(void){
+  return TYPEKEY_U8;
+}
+
+template<> inline 
+uint8_t getTypeKey<uint16_t>(void){
+  return TYPEKEY_U16;
+}
+
+template<> inline 
+uint8_t getTypeKey<uint32_t>(void){
+  return TYPEKEY_U32;
+}
+
+template<> inline 
+uint8_t getTypeKey<uint64_t>(void){
+  return TYPEKEY_U64;
+}
+
+// ---------------- Floats:
+
+template<>
+struct is_supported_type<float> : std::true_type {};
+
+template<>
+struct is_supported_type<double> : std::true_type {};
+
+template<> inline
+uint8_t getTypeKey<float>(void){
+  return TYPEKEY_F32;
+}
+
+template<> inline
+uint8_t getTypeKey<double>(void){
+  return TYPEKEY_F64;
+}
+
+// ---------------- Strings:
+
+template<>
+struct is_supported_type<char*> : std::true_type {};
+
+template<>
+struct is_supported_type<String> : std::true_type {};
+
+template<> inline 
+uint8_t getTypeKey<char*>(void){
+  return TYPEKEY_UTF8;
+}
+template<> inline
+uint8_t getTypeKey<String>(void){
+  return TYPEKEY_UTF8;
+}
+
+#endif 
\ No newline at end of file
diff --git a/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/test/README b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/test/README
new file mode 100644
index 0000000..9b1e87b
--- /dev/null
+++ b/new_shit/circuits/stepper-hbridge/firmware/dual-hbridge/test/README
@@ -0,0 +1,11 @@
+
+This directory is intended for PlatformIO Test Runner and project tests.
+
+Unit Testing is a software testing method by which individual units of
+source code, sets of one or more MCU program modules together with associated
+control data, usage procedures, and operating procedures, are tested to
+determine whether they are fit for use. Unit testing finds problems early
+in the development cycle.
+
+More information about PlatformIO Unit Testing:
+- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html
diff --git a/new_shit/circuits/stepper-hbridge/firmware/maxl-stepper/src/main.cpp b/new_shit/circuits/stepper-hbridge/firmware/maxl-stepper/src/main.cpp
index 6ac0ac5..78f3c39 100644
--- a/new_shit/circuits/stepper-hbridge/firmware/maxl-stepper/src/main.cpp
+++ b/new_shit/circuits/stepper-hbridge/firmware/maxl-stepper/src/main.cpp
@@ -132,23 +132,3 @@ void loop() {
   }
 }
 
-
-/*
-// TODO would be to imagine a struct-unfucker like so:
-
-typedef struct motionState_t {
-  float pos;
-  float vel;
-  float accel;
-} motionState_t;
-
-// a templated class that writes a serialization routine
-// for this struct, and can also report type signatures. 
-// could write a constructor for that where the programmer 
-// annotates the type with names:
-
-GenericSerializer<motionState_t> serInstance("motionState", "pos, vel, accel"); 
-
-// and this thing... could be used within the rpc thing ... 
-// TODO would also be to evaluate https://uscilab.github.io/cereal/ 
-*/
diff --git a/new_shit/python/boilerplate/main.py b/new_shit/python/boilerplate/main.py
index 5e9d5fb..5253c34 100644
--- a/new_shit/python/boilerplate/main.py
+++ b/new_shit/python/boilerplate/main.py
@@ -2,7 +2,6 @@ import asyncio
 from osap.bootstrap.auto_usb_serial.auto_usb_serial import AutoUSBPorts 
 from osap.osap import OSAP 
 
-from modules.maxl_stepper import MAXLStepper
 
 
 osap = OSAP("auto_modules_main")
@@ -18,15 +17,9 @@ async def main():
 
 
     # instantiate each of our modules, 
-    motor_x_back = MAXLStepper(osap, "motor_x_back")
-    motor_y = MAXLStepper(osap, "motor_y")
-    motor_x_front = MAXLStepper(osap, "motor_x_front")
     
     
     # and set each up, 
-    await motor_x_back.begin()
-    await motor_y.begin()
-    await motor_x_front.begin()
     
 
 async def run():
diff --git a/new_shit/python/maxl/__pycache__/core.cpython-312.pyc b/new_shit/python/maxl/__pycache__/core.cpython-312.pyc
index a76e014830644d3b4c6ca99d184fae280667003d..87103b75e1c1c7a7c8c9bf364b3da42b526ffebd 100644
GIT binary patch
delta 1298
zcmaEp_dcKRG%qg~0|Ns?W9;#?V4aD4^Mq0uQaE$Oa>b*>85vT!i`Y`QChq$wqse%S
z+t)F|C%7cFpdhvAB@+V!gC^rG7XM(!fX$Z~9heveHjA+6F*1s5c4m!WV&tDZhy4(v
z+2nYR<BWov)j31i8J#xQ3WzW<s!g6Gl)*T8@^7IXY9+!TyFs{yxkLm+gYasQ;S3B6
z#f&|9HOyJ!lM97K86_q^WD=hIKv;owDhopm!(>M}5uPkrka7r~e2~jPsYDgRVPL3X
z$Wnu`5p<TuWJh7)$sdH+C*K$0n0%Q_j;Ta-@<k!F$@fKg8MP)m%7{&77L`;MgK0@&
zsbPp0hw(}bVXQ18u%k>TI|@rp&KKpDmWIhxGMF<=VC+!>lT79eJ!dCR7S&*snY>5T
zLsc+0u_7nFIJG1`Gp{7Is4Ow3D1d>1;TBhBab{j|Nn&1dY7zfrVX-}I`5^ztOuj0n
z!OX@PFiG6n&ETS#!3L4*h8`CUJuZuRUKjAZAmDjNSawFn8t$vYCO4#%u1lF*lrq^6
za^2MXqN(=@$BU+Zm!<r#i}+s@@&CZf#u>o)L11#Z__8cf20`_oHv~L?J`nN$RqV*X
zz|dsjCdjy3$4!v&pgN-)C)+^{B{xCFLtKn*JZy)!ML=u?MK?jl!;Fk>{A`DroH^VC
z8ISQWf=GT4nal_a00ssIHU<WUW(Ed^&pDGDB^nr$Co@Spsg&@-RMaq)@WI%yxGs{c
zVagJmEGQ#9Ia<<>F?I4PNm<73$tNV68968WNGVGc@iQ<m6lH*t9dl6(h^-7F3Mbb}
z>9RF}LTkh14N_)|tdpNhY1Bi*<qC4R1YVXhzb;~aLB#xyfanDYy%iPL^_?&3J73Uq
zIpBOj%;Tzn=Lc?9PA|qUJPe$C7x+}Ka;SaaXW&%&@qvp$)Z$mMIw+u&oJ<&(Fgh8q
zELC(eVLZrg>tw=sh=tL~i0u%o4v1~U=w!0FMVgO;QDF0A<uFFZ%*n4*tl7lCQ9oHt
z)qpW~a=5B02biCpS~9ss)tRwi@(EQn#`4MURm~X-C#$RZOM((Wl@KV)Ip-Ip>g6V8
z=Edja=NI&E?pJ%m$XGSGMk7<#=c2C9iJ<f0C&Mp<MO+Wdx)_#qAv@<{Snh@V!t43v
z7xT+6>sDM<sQkdqDp|EzNK=?yt{fC<{-9uFy~U(waEmdss1qav4$_H}oejJhZ%pnt
zC}b?1%xLJtC@|U2u+j>wDHNnE8<bpy3i69HOEUBG;*%4LN>Yn66Z49yK(aa@0&F-3
zB#tIdW;B}4cy04cqccpp#UNRbzlv-@ta%{92}J0E2yGDI0wWwJPcqfe7hrW^{G`Uk
zs{TpJiIG+3gCCOuE7uC<FANH-Tt#4AAPt%dMY$k-&68i6c1&(G6XOS^m0O(o#fb%a
qAY$?~vp~iblV6ybaz16ydB`kqmqlT+nz=cDDH9{tCk7A+HVps;s9BZ(

delta 1197
zcmaE#|0a*`G%qg~0|Ns?RM@e!>)I3f<_V>87xAQUrf}tm<%&m%Gcu%bPTcoX<|PvY
z1A`{xEf)V^#{f;nTim{m5kA2ssRae8MVl`(IxsQvZx&(EV`LQG?93X$#3(p<4*MZS
z)5-B1#~B4St8<33Gdgar6%b+KV`64t@Md6Sn9fkcki{^$P*HgDCLs^TrpdpBcCgei
zX9-U(6c(M##VtIUQAClwg$1Nc45Z9c668=+Tp|tQm&n3cS#mHIf-X^nv1=Hzlt89U
z_TUzt>>$aZv6>MgMaY237lqWgV2W!PCpU_SO;!|@RThD0XJANSsbPp0h4D&sVXQ1Y
zkdGJ*Cofc1lBr>chkK)v!JJ_NV~?OYL(d0uhMqH%w~J~pN=<$s>cP)boLUl}nOBlp
zRF;@i6foIWY!6!=0|P^G&}4pb4Q5tOpUGC@);8J~#k5zrT-R~FsN;ND%;ma(%LM_K
z8)9<T#SAWr8Eg=_Zs>l|(ESACMMJO4V&2yUye|rPf8b{2^kMwKH+i@CvJ_zkLG_<E
z1YCaH5b*w0Y|X&H&}89i&$wI1)t>R7I-{!v+d&N_S9``oT#T;PY=^j2L2Ls?S6jA2
zhRz(W_KZiZ89}5ih)jltB-rC@3=9m-3=9mPeI}olXkZMU>?7&KQp1$RJNclT@Z_VC
ze)6F#3?*<KDIBn%Wn=(_OHcJ=BdKOa_Q~6%l=(E7i((iU7>blZM8V{bQo3vnpuku*
zSw-56k!5nUw1x=6*MgVDjIRqAUl1^!yii)oos)&ri}4E=11H}FKGmxnY9DwRIF){U
z;9w9m`BkhA^0AVW3gZ$+Ck2+JicTtw2ibK&qzR*w65Byj9VZpWLrRQJDw~;P_&6B(
zHw&tSF*0UM&QP^x6r8+L)qpW)@-0<Wj`Y-$_}s*boXPBJ&W!n!z17qh%O)48nKKql
zUZv(Q35vTaAyA%i&M!*U%T3J8i_gi=FX-7Ur2dAHv2^l(jZ9tli@NS7n9j4GWWNv?
zd_6GrVqofpwDgOC85gp0u4ffp%qqI9TYOca<O4UWWa;Lqn!@aIWuOr82W3sxTTFTe
zw-_^vIzU3;;F>V`n1MIr)yYDJg^VSWTMT^|`6pjAth54a3I!?4VqjpnB~*}KoLQ2Y
zpBJB;SX7c)oSB$cR0)#R0TE!sIUwObVRDPnbjHh@WsJ`-2^4{3LH;VT1+nH%{$VP^
z=rCE-OoN-B)rIks3MZ@jCyB`(W^!yfAO%g6bIdw;IP;4W3-mxlk-+2+W>S--%mWyg
kPtG<s<$TC2aF<2lE{oCRmFDLB#Y~J`pBO-75hy1C0QYq-Q2+n{

diff --git a/new_shit/python/maxl/core.py b/new_shit/python/maxl/core.py
index c4c4aed..d1f1b34 100644
--- a/new_shit/python/maxl/core.py
+++ b/new_shit/python/maxl/core.py
@@ -11,9 +11,10 @@ import numpy.typing as npt
 from .types import MAXLControlPoint, MAXLInterpolationIntervals, MAXLStates
 from .queue_planner import MAXLQueuePlanner
 
+from modules.maxl_stepper import MAXLStepper 
+
 if TYPE_CHECKING:
     from ..osap.osap import OSAP 
-    from ..modules.maxl_stepper import MAXLStepper 
 
 # returns [pos, vel, acc, jerk]
 def get_states_from_spline_pts(p0, p1, p2, p3, t1, t_now, t_interval_length):
@@ -114,8 +115,9 @@ class MAXLCore:
             if actuator is not None:
                 print(f"MAXL: starting up {actuator.device_name} ...")
                 await actuator.begin()
-                await actuator.set_interval(self.interpolation_bits)
-                await actuator.set_current_scale(self.actuator_currents[a])
+                await actuator.maxl_set_interval(self.interpolation_bits)
+                if isinstance(actuator, MAXLStepper):
+                    await actuator.set_current_scale(self.actuator_currents[a])
 
         self.control_points.append(MAXLControlPoint(np.zeros(len(self.queue_planner.axes)), np.zeros(len(self.actuators)), now + self.twin_to_real_gap_us, 1))
 
@@ -132,7 +134,8 @@ class MAXLCore:
         for a, actuator in enumerate(self.actuators):
             if actuator is not None:
                 print(f"MAXL: attempting shutdown of {actuator.device_name} ...")
-                await actuator.set_current_scale(0) 
+                if isinstance(actuator, MAXLStepper):
+                    await actuator.set_current_scale(0) 
                 print(f"MAXL: ... shutdown of {actuator.device_name} OK")
         print("MAXL: ... shutdown OK")
 
@@ -172,7 +175,7 @@ class MAXLCore:
                                 if pt.position_actuator[a] > 16000 or pt.position_actuator[a] < -16000:
                                     print(f"MAXL: WARNING: you are getting close to wrapping fxp16_16 * 1.5625 w/ \
                                           {pt.position_actuator[a]:.3f} ... time to finish that project !")
-                                tasks.append(actuator.add_control_point(pt.time, pt.position_actuator[a], pt.flags))
+                                tasks.append(actuator.maxl_add_control_point(pt.time, pt.position_actuator[a], pt.flags))
                         pt.tx_time = now
                         self.control_point_most_recent_tx = pt 
                         await asyncio.gather(*tasks) 
@@ -189,7 +192,7 @@ class MAXLCore:
                     real_actuators = [] 
                     for actuator in self.actuators:
                         if actuator is not None:
-                            tasks.append(actuator.get_maxl_error_message())
+                            tasks.append(actuator.maxl_get_error_message())
                             real_actuators.append(actuator)
 
                     messages = await asyncio.gather(*tasks)
diff --git a/new_shit/python/modules/__pycache__/dual_h_bridge.cpython-312.pyc b/new_shit/python/modules/__pycache__/dual_h_bridge.cpython-312.pyc
new file mode 100644
index 0000000000000000000000000000000000000000..f1e0cdea4d4e8a81216159140c01e2d4c8bbf592
GIT binary patch
literal 3545
zcmX@j%ge>Uz`)QPb384Qoq^#ohy%kcP{wBy1_p-d3@HpLj5!Rsj8TlaOi@gXAU;zL
zb1q913nK#)gF8bCa|=TX%W5Wwt|-<@R!z2-AdV)}EtcfO;*wjeA*BU5shW(pSp0(>
z1Cl{<Fw6#Jd@cdomC6vsn8Fanl){+GoWhjKlE#w4+`<yYn!?h;5XF|ln#!KSmdc*S
zlEU7?62+0ik;<9Il)~A<62+CmmCBjIoywlVlggRKmcrY@62+aum&%gHl)~S_62+6k
zm&%*UnaZBVB+0<Qkj9iE(83bMS1G6|bc@@iG%?4+sVFlgJ@pn#esN;KE$)=mvdrYv
z_`Jm2)MRF;8$lE+0|Nty|G9(_6gD+XH4O0}aWJl7%mT@Q*$ASBDTNUhIyDUO&~Rd4
zz^R%ENj2O&oT{0TRKsEpx7qM`s$qx+`33AuoMy8knGK66h8l(}xIJL)V4{X03$6kz
z048b}vN*sD6rzS93!M5;1VQHVpo)Na>8v#j@$4WL2v;&_viaQ-E-%U~NrlFke`!fU
zX-V-df!xH3ocQ9@63@Jn)S|M)oLeGbk;Ie~=lr~qqWqkI{LH)(sAzg>iEB|&evxl#
zadBdLDpYrRYDqwTab`(oex4>r5hnu!!!53&g5>z*#GIVeqFd7OV2k53;*-FMB|aZw
zcYIMn@-4A=uyw_$CGnY17l6g3A>xTCDe=h=cf=Qf9D*#Fo>~&03UW?-F2p@xNvMe+
z$pWaWz~bx>=M-x)-(o3F%}FZ)1u@vQ#h~P(prG(8z{M)Yr6|83DZe77peR2pHMvAL
zCqKP7rZ_vbBsrr}H#adkBQq~GCNH%-zBnVZB&MLUBqKjBCO1E&G$*w<CZ#kn2kuY3
zg34PQ@$s2?nI-Y@RU$~)MGqzlN=wB{7#J8D7;Z?bb+BCFkhr0(zutbO{SNC39<i6T
z<3M5>H`KJ2=P%6PkbS{9^s-tQNK6??UEF2uc#xO|RxvDkAMglV=h3;yqjLkqP`}8d
z4rahb;0%z|2W~bAt`3%7p3k79l*|Ysp%|2)n;94wJ|{6SFnBXCGE4_0N2nw+<-!mv
z#lTR@h&{`!hAM4lNMWdEW?-1cG@ZGPm6d^!p+|;=p_0Lzp@)4fb2;NmMn6raA~8_<
zVogd-&&<<gDiR0r*q~7hDkKyXiX<2q7>Z;W7#OMqkpms9MTCKYp;()Nf#C(ij|PSt
zVp7v{Cgyx%VB}QnaJwNSF<ob(&SbsoJPH?i6h1ODaw^{7QTSC1%3w{(`ix5%b=j72
z=ri78OU}>CiBE*mNhoC<JWwJC1PaztkFkacR(fCt2RJBLK|xU@!@$6x$y6i=@;(d5
z`<l$)uqcuTd0qkJOK7SF2gfZj?0K+C2|0wYs{sWkQjqZpUFXxg$ftLm&-fyr@dmdY
zZkPF-uX8wG;Bdad!S{igfzyQ%8e|GujEfjGSQfKsG2Y^bWpBUIT&K*E;$%={K_ebq
zH-HmT7+GPq8k#7H2{9p1_$Wa_50rR{R6t<`att)(+!Dknk*Z{oLkU9~6c@#s@H7Pq
zAkB+>nvh^xQGc1w{yK;K1rB>?@HoJNM_!Y0A)`9WA~sMRUy_-ddW#iY#@%8~%SlWx
zP6nkUSO|ei3UCNTkrhHUOf}4_K?wrXdcnwMnCVIw9!e~bWTg%g&;Su2j~0WRrl0@|
zF)?tEV3gIUi3__La7xuh2|J|3<+4NdfaqmD_v;+)7dYIZ;pYJhKSgcE#f+LPOW3p-
zZ?P4nmXsFdVK1JF$OtoBg;FhJ2`DbW@lpb>yKCTWm0(bDC4$JKEJdIqrwEkdia-%?
zi@CU@2wrd%r52awloTT;KS*GLsxOqf4NG8Rr~xNseRyDsOJ5f^zbI~gUEJoPxXop8
zyX%5>9c*{_g{L^r5WCE;aDhYN12cn=Jv6t<nKLe6G-X*RYR-rfj3DoVlimy}24f5p
zs6MD=!XKDOvY^@;9O#GwGK~ow*y@PDW-Ss0B~hfn2DM#S({l0?OJD^gC?((GfHe(Z
zbw8w(gk*hCxWeSIWPN05P>v|JhljYl@^yKui}F_2<?S!Z+h3M<ye{e3$=AWskpT&H
zk?#5>EK5RHcwAO6y})mJfy49zGlP^9<F8_V1_p*EIY%zW1&odyEDJRpxfuO4`9bXm
zP-8ki{uWn!JfxKoAAgG{KEALtF$W@31d5*`J&?aaZFF$OS7Z$0DuW0k5TOPlK($_x
z0f+_4y+x)B3=At7iljgSpd!8q)LaA;An9UI&!UCl0~0SR*Nl)447{vd8<;<Xs84cC
ztco8vm{|EYn0{bjV&y-e`WZw)go=^a!eHqgp<wESF<eG*MKXvDHpFZN>x$$JrYo{8
zYFK_@U}80cI0)nxKTWn<Y$cTinR)5poKpmH*DX#^PeTtxKs*joS!4<F1l%XTIBXz6
oWmjawz`y{i9Ew5d;sY}yBjbGrxw{Nf-&xcc%|0=xF+%JE0L2a-@c;k-

literal 0
HcmV?d00001

diff --git a/new_shit/python/modules/__pycache__/maxl_stepper.cpython-312.pyc b/new_shit/python/modules/__pycache__/maxl_stepper.cpython-312.pyc
index 95576ee5cbf8070721ef49ff883ce40cf0ca9e06..6d8bc55bb28f4f6406f94dcfdd2625e81f5b3e32 100644
GIT binary patch
delta 270
zcmX@7^hSyIG%qg~0|NuYm6+pc*&BJ&xm5*o6DxA!i&IPDGxJJPi^>vns$_i~BYc8O
zQVR-Fi}b+Ki~G45wZy>8#FUiy<ovvnqWqlrg8a<9k}4$(<(t>@$S~@Fm8Ykc#HSV&
z<rl^0rWO|`rl(?2o}OB=`8%&aBh)P*Ed}|-nI)O|d05=CIg#I-(Wdw_0~0I%2M#7y
r{tdz(K<pi%VCsZ1Tt;z4GKj4RQf0P+bw%<9(-m14H7qAz5vT$Haz0;X

delta 223
zcmaE(bWVx)G%qg~0|NttxcafQn2o&Y+|oS7sU`85c_pbuWr;ae626WRKEWla1qG=^
zdW&arGb#usrliCt=jW9a<>$l~<Y(rURLLSM+I*NthEXRywIn__u_7lvwWuh+C_Xo}
zxHvIAwMq$DB}~m`Za#lTX&w-_Aip@XBr`t`)!xnZ{N{|(%AXmSSouG2FtPHlaQ*;d
g?_dQ}2a+dW6cFQHV7fwhMd}Kvi^?XGKM7O;07iXGcK`qY

diff --git a/new_shit/python/modules/__pycache__/sketchy_machine_motion.cpython-312.pyc b/new_shit/python/modules/__pycache__/sketchy_machine_motion.cpython-312.pyc
index 9560e1f2a1dbeddbf1fda40234e8ac6ca7a2afcb..c050e9984643295899d81ccd19222b753ca0f7d3 100644
GIT binary patch
delta 2263
zcmZp5d+f<~nwOW0fq{V`KIwQ`jMPLv3C0Bz)x-T58B!Qh*mC%D1)>CU1)~JPeD)ln
zT;V9;T#+adFrOnwG*>K2ELS{AoRJ}gGfIMq!JQ$6tA!zjdo>ftPzHu5$x22|o{0w(
zc(`3k6LUPAiZWBuQ#aoAXJni(S(j<CR0=~4Lp(P`F#|)1B%CEZ`3_SuHy@lYKY0VQ
z_vER}0+YE}xEMjaXmLTftSXFE!;qygIZ<AC@>~`!abcKf2{w6QKCHrAjG~iQu;|Nx
zG#7!0m!JUBWPUk~fq|h2<iMAVlRvZgF$zp}VvS-G0EsG0Uc{;;oB4&2f#IbQ0|SGm
zSP?%+94rZPWs&OSm#n$!x47an;*-E(P+Y_bQUNmi7H?r`YH4bGK~7>`UTRSh&*VZj
zRYvZ~)7f;mk&Kyqj%^m3I0FMivFYSI_E?D<QgR(EJ^W8(b=TzI5>~pQq<l+K^Om^E
z<U8z77>za`<WOf+sbNZC201yMC5<VVL6gO=2oy0zQVa|XFF`C#_9DZ{|2dUZO&Ay$
zZt>*j#g}B}rp6bSq!tvJg4|~Y@(o*&If!jD*^SGK(Q@)cE)zB%kUM5iKF!sqd&2xe
zaL7rk3ld=$_`@!6gcVscFfb%D!or?`fq{pCfuWg!f#EX~^W=K&QxYjGu=G*G5YGlv
zSi(Pf1G5}ciQwb}W|PVFJYtjQ3yJZhv!pYmur6Y(VaO7iypTt9@*^JM$&9>WlPB_u
z38b*CVPDM-F`$MaO9~Y8rpz#YJW}d`h%qpvaIA*9jFF*45hj|YG?|e{n2~dGBCoWh
zJWMo&3!%1#AxmcRM@eBu)yawSS}KeTB?x8Q2xS;X@=Q+Tm6}{H$U0ezkB^aevL&Co
z;w|2k(!`wjl8o}if`Zf{P3GsbW`e*;`yx=V7Wqsr;#1`YryT`QxT{WH#OKW@KKUJ=
zkEd`E3rGl@EObFEJrJP}B3MC$0f+#FND&8!1vUhd06|<g5Mc-+bS78ws|bRkwHOp0
z3PqM6(a_23_~qGRKyj-&`7*zQ&>bn&1u4rj7iMmdzbxh0!P3J&Sy(`sJ23QmV8X?~
zgbNahlPv_+`MAiq+A|)JV|2A-IU=v)YR`C-o6*&p<tUFjh;7X1YRhuegbl>DW(1M8
zAQB~sfP4i`B9|sR$jdV|s!TSN6`!0SFU*p{n8G-@Q9^d|7D-{IM&-#HCB-K1mlv75
zn^!8LlA)5poT10WoS}zfEps`eCKDuqYqAu90^*ifc~NFbDm>4{=a-fgl$I11>3~u@
zM{!1JNlJcsUQrmx!$`ppIeERHQhf<XG=hPF;RVBw28J8l{QdTw_7}L-ZU~7@*Pp0=
zUC831ki`zc9gdfU?5^|JUEs09qDJeYkk(}(o$EY07kP9(Ff;I|e_&?dwg2&eN9R{D
zDE&3*II1(QV{}wzS+DD;&UjFU(NUG<pe(y1yE@}RRYphk&1^!M%uGcRlM6+a#RC}_
z7*;YvGBGIsLRc!33q?gI9}wlP4+43N4V0|%Qi_5>9PZ?z)Wnk1_>#op>>_Y3XUWLV
zO)UZ?o?HCssU`6_nYo!I@x>*HC8>}+4@y$E*wPbAGE$3*Km|Y%IDLWA%`K7Q)ROq*
z(xRf&yps5W{Nl`#%>29}O;F+qVPFttxW$*AUy>i6n3octSe}?!qRCWbJ~>`Yk`0``
z;wRUM$uU-Ko-4MC*$|Y>ic~;4!9D?%Nt(<>AX|!(L84k90y%0XcSxBq_HN!Qb(x7#
zeDXwD5k|ww%Vd>#L7oO{(PS?&pL|UgR7NSvnK4e=93i)y(Ls~ZPm={=ZYC&1m~&F|
zAj(<5<=QRIipnZb02QSd6@ct41Vub3K`JOHC=^*vc2sa-TLuyfnj9-9KY5ixXFaIU
zy2YHCS5jmJ(gDs_p&(Wyh=>OfX&?fWhKedck;VWn79rUTR4x^P2r-bUpgiBg@PWyQ
z)oez{2L>ZnvkTUt5IQ6KGl>5oi;<T#oN<BhX9f`cNx?~sRq2xf3#;xY9zj;EPim~J
zsf?e5cv)>eE3mNIKx_h;uPFsd1e_&BiOH!+iOJcwSo2DA3o47UCVx@%vJ=hCPbtkw
zE!G1UNU*A@2vm~X;>t~|$k8jQEJ!Ub0(+MeERdXElv)HSU?wLhNz@~1F&?mdeqL&P
zN`6`qs7@~e75qgGpnw3mrl=Og0@V)SVEDyh1F_z&sEdJt0hIrWL8;^eGb1D8Z3e#E
z3<9?qgzhp(Jq011y9~Nd84T|;=-p><xX)nvfro)hpn*;BJ4*-?qs=D<5DE4;0OxcQ
A{Qv*}

delta 1942
zcmaFt+3Lo3nwOW0fq{V`JLg!MsN_UG3C1ZC)x(`~`J?z58B!Qh*m4AN1)~IWg`$MO
zeD)mST#+b|T+t{|MurrQC^04mcZL+s7KRkA)l49R7#O0&D;YJpC!SH*_}hn(v1zgg
z(_)?yafloPLy6>MR_0`GUN~QN@<txH$?v4ZCcozqo4l7<keeTeoHC2x<a5kiyvi{7
z8ip*n$qRXfC&#gHi3`C*OR&j{VAnNy4h!exn=I-wAl*eE;^h}c1_n*$m(v&+7>Xpo
z#AF#(KSut^*{o4)Ag2|{O+L-4C0hjY(n})-1_n*hB0i8pu%rNpr94@PEmyjT1H|TJ
zU|_h#TUeS}ni^k_lbDy6T2#b6c^R83BiH0JY&zUXS|>BJ&tem0U|=ZLo4lAkR`7|e
z?wb5t!b&%kly6CD-4a)uEWz=FQET&G4s}NHbmlasU<OTQzamh$zhneCguO^_vIm!v
zsv*cup8UM{lFZ!H_~Me(f+CPZi;O{v*osU*?y{WR&*jBvHu)Bp37aR#&MA{cxck&D
zNO)b~_qxF0Rb;`yz>o|w78bBP3=9m-3=9mPw=qpV&wYxigm>~q9xtAB=5&S>mPL#;
z3|V}WH;9T(zAqv?nN3t|vOljFTMFwMw$<#D<9TJwRx?8ks$qx+nFQvPNP{T`28I;&
z)lj<_8A@bfqFHj21zCg{IVS(*l@>v$<%Fx9d{9(^Q4yR7)(J@}A(_VoSA$_5Gxuu7
z$?JurCLiV#WaOEAl}}wrlll3qnILe|zQ_X<JRXx}`BlM5u}BWYSDx(4@69MSc_zP)
zy<iawNC+Hr+8~w=h|mQQY#@RiL?ERG5Z4(*=z$2W$$A1RVxTxE2KiW_$P6SJ$iTo*
zB{jK$U6ea1H9a#g5)>s|lRE?)Cf^cJW|9b)%pthW$JxwPlJT$wqpL8>VM`rXNya0p
zjIN?AN7U3^B^i(MGP;Vh9OYvJu|*j{q&SE~i9}E&fFm(vGNYpR<PD1K+N^7t%NbWP
z`e`y1X@L?BM{!1JNlJcsUQrOp5lD^<oh&b`WLf|cm0@6Dc){?af#C+9P=9`B{&haJ
zi+pOA`82L`Xk6mZ_*D#w<0d%`#s!ROEDPB*HXj$xWM+K{Dr_bTic3!R6K5CqWnf@f
z$qY`vNQBbl9C3wuKafk<5(^4a^HPfZK^*SnqSVBa)cBIb;_M=D3TMg4&rK}?#lS88
z^wg60oXp(JlKA41#FA7<dI!bJEw=Q;l8n?MaN;ilM-nI+Ziy79mc%EQ78RxDmBbh1
z7iX4a=I0fugW@89fkBkv7GHXPNq&4{UP^pod17XXCR35gWCaOHHgI&sOtzPhV=Uer
zC$Wp!5ENHMN+6w}tXO0X%4N(&AX|zOK%yET0y!)vd&-zFwr#GHxy&Rc28wu=AXguS
zDmDdo{}6u#O^zbH$?5XSyr3`uo1n>FWHNcWJSe+9k~d@Q-z=%HoYAQ$1Y{8l#G*7%
z5HaVZ=0P;DfHV0m&Wg$^P>2<!7v+K+kq3%8P~ufkP*5l`o22BzHXkGuG+9nTesZQ#
zXFV&}oXotEB6E-iaIyuZ&7x2cHwHu`gNQ;9Q3{Gc25?CMNyVUIy$D2zfK2saU|?ur
z_`qbyYBnR}1A`%}*#+xR2%VAr8N~mP!N|+%&A34LGXseJq~IjVs`N>ZkyY~(n;@&!
zCpA{qRK`z2ysS2#6<AnpAU1)_*OY)H3eJ+E#N^bZ#N_N-ta+um1(ikVlQ%1S)pO-0
zR^;fFR2HNb7lFOR2^L7sFG?+f=h0h2U_sQf8Bu8SfMxUZQsYzd(~3YTw}>0$Yg-Tj
zazs%Thy^Mq!M^{+VUwGmQks)$SESm;z`y{?IK`mU@`0I=k?}SI-)#ng+YCZ?8Kj<q
Wkj~x72UJA({h1hTJ~4nuu<rnTj<Hz)

diff --git a/new_shit/python/modules/dual_h_bridge.py b/new_shit/python/modules/dual_h_bridge.py
new file mode 100644
index 0000000..004a86f
--- /dev/null
+++ b/new_shit/python/modules/dual_h_bridge.py
@@ -0,0 +1,44 @@
+from typing import cast, Tuple 
+from osap.osap import OSAP 
+
+class DualHBridge:
+    def __init__(self, osap: OSAP, device_name: str):
+        self.device_name = device_name 
+        self._write_h_bridge_outputs_rpc = osap.rpc_caller(device_name, "writeHBridgeOutputs")
+        self._maxl_set_interval_rpc = osap.rpc_caller(device_name, "maxl_setInterval")
+        self._maxl_add_control_point_rpc = osap.rpc_caller(device_name, "maxl_addControlPoint")
+        self._maxl_get_error_message_rpc = osap.rpc_caller(device_name, "maxl_getErrorMessage")
+        self._maxl_get_position_rpc = osap.rpc_caller(device_name, "maxl_getPosition")
+        self.callers = [
+            self._write_h_bridge_outputs_rpc,
+            self._maxl_set_interval_rpc,
+            self._maxl_add_control_point_rpc,
+            self._maxl_get_error_message_rpc,
+            self._maxl_get_position_rpc
+        ]
+        
+    async def begin(self):
+        for caller in self.callers:
+            await caller.begin()
+    
+    async def write_h_bridge_outputs(self, coil_a: float, coil_b: float):
+        await self._write_h_bridge_outputs_rpc.call(coil_a, coil_b)
+        return
+    
+    async def maxl_set_interval(self, intervalNumBits: int):
+        await self._maxl_set_interval_rpc.call(intervalNumBits)
+        return
+    
+    async def maxl_add_control_point(self, time: int, point: float, flags: int):
+        await self._maxl_add_control_point_rpc.call(time, point, flags)
+        return
+    
+    async def maxl_get_error_message(self) -> str:
+        result = await self._maxl_get_error_message_rpc.call()
+        return cast(str, result)
+    
+    async def maxl_get_position(self)-> Tuple[int, float] :
+        time, position = await self._maxl_get_position_rpc.call() #type: ignore
+        return cast(int, time), cast(float, position)
+        
+    
\ No newline at end of file
diff --git a/new_shit/python/modules/maxl_stepper.py b/new_shit/python/modules/maxl_stepper.py
index 7740b77..ca52fb5 100644
--- a/new_shit/python/modules/maxl_stepper.py
+++ b/new_shit/python/modules/maxl_stepper.py
@@ -38,19 +38,19 @@ class MAXLStepper:
         await self._set_final_scalar_rpc.call(scalar)
         return
     
-    async def set_interval(self, intervalNumBits: int):
+    async def maxl_set_interval(self, intervalNumBits: int):
         await self._maxl_set_interval_rpc.call(intervalNumBits)
         return
     
-    async def add_control_point(self, time: int, point: float, flags: int):
+    async def maxl_add_control_point(self, time: int, point: float, flags: int):
         await self._maxl_add_control_point_rpc.call(time, point, flags)
         return
     
-    async def get_maxl_error_message(self) -> str:
+    async def maxl_get_error_message(self) -> str:
         result = await self._maxl_get_error_message_rpc.call()
         return cast(str, result)
     
-    async def get_position(self)-> Tuple[int, float] :
+    async def maxl_get_position(self)-> Tuple[int, float] :
         time, position = await self._maxl_get_position_rpc.call() #type: ignore
         return cast(int, time), cast(float, position)
         
diff --git a/new_shit/python/modules/sketchy_machine_motion.py b/new_shit/python/modules/sketchy_machine_motion.py
index a063f61..979c149 100644
--- a/new_shit/python/modules/sketchy_machine_motion.py
+++ b/new_shit/python/modules/sketchy_machine_motion.py
@@ -6,6 +6,8 @@ import numpy.typing as npt
 from osap.osap import OSAP 
 
 from modules.maxl_stepper import MAXLStepper 
+from modules.dual_h_bridge import DualHBridge
+
 from maxl.types import MAXLInterpolationIntervals 
 from maxl.core import MAXLCore, MAXLCoreConfig 
 from maxl.queue_planner import MAXLQueuePlanner, MAXLQueueConfig 
@@ -35,12 +37,13 @@ class SketchyMachineMotion:
         self._motor_x_back = None
         self._motor_x_front = None
         self._motor_y = None 
+        self._h_bridges = None 
 
         self.queue_planner = MAXLQueuePlanner(MAXLQueueConfig(
             axes = ['X', 'Y', 'Z'],
             inertial_axes_count = 3, 
-            max_accels = [1000, 1000, 500],
-            max_vels = [150, 150, 150],
+            max_accels = [1000, 1000, 10],
+            max_vels = [150, 150, 1],
             interpolation_interval = self.interpolation_interval, 
             twin_to_real_gap_ms = self.twin_to_real_ms, 
             lookahead_queue_length = 64,
@@ -83,7 +86,7 @@ class SketchyMachineMotion:
         # print(f"{z_fl_actu:.3f}, {z_fr_actu:.3f}, {z_bk_actu:.3f}")
 
         # returning (axes, actuator)
-        return axes_pt, [x_back_after_dof, x_front_after_dof, y_after_dof]
+        return axes_pt, [x_back_after_dof, x_front_after_dof, y_after_dof, axes_pt[2]]
     
 
     async def begin(self):
@@ -91,9 +94,10 @@ class SketchyMachineMotion:
         self._motor_x_back = MAXLStepper(self.osap, "motor_x_back")
         self._motor_x_front = MAXLStepper(self.osap, "motor_x_front")
         self._motor_y = MAXLStepper(self.osap, "motor_y")
+        self._h_bridges = DualHBridge(self.osap, "dual_thwapper")
 
         self._maxl_core = MAXLCore(self.osap, MAXLCoreConfig(
-            actuators = [self._motor_x_back, self._motor_x_front, self._motor_y],
+            actuators = [self._motor_x_back, self._motor_x_front, self._motor_y, self._h_bridges],
             actuator_currents = [0.2, 0.2, 0.2],
             interpolation_interval = self.interpolation_interval, 
             twin_to_real_gap_ms = self.twin_to_real_ms,
@@ -110,7 +114,10 @@ class SketchyMachineMotion:
         await asyncio.sleep(0.25)
 
     async def shutdown(self):
-        await self._maxl_core.shutdown() 
+        if self._h_bridges is not None:
+            await self._h_bridges.write_h_bridge_outputs(0, 0) 
+        if self._maxl_core is not None: 
+            await self._maxl_core.shutdown() 
 
     async def home(self):
 
diff --git a/new_shit/python/osap/bootstrap/metaprog/__pycache__/module_author.cpython-312.pyc b/new_shit/python/osap/bootstrap/metaprog/__pycache__/module_author.cpython-312.pyc
index 0235183dbed98ce59dddca9880ac1ad61f6db72d..7cdf01b0a1c191c716daffe97b0e3574e27031f7 100644
GIT binary patch
delta 245
zcmdmN{LhH*G%qg~0|NuYVx41Y+axyfW%F>cFfcGMGcYiG&YRrKlgn1a6wIK>x><nN
zoJm-d`4&@A>Mhpdf}G5fTP#`mnR%15`JK6B85kHW7#J9e%_i^QH{Sf6-=C3DYO=ea
z9IGk=1B3hKEWsE?E_DV5h9VFVGWmj#HlzCHKSCdw7&Rxq6Ln*hnrtejBm+`>i?^V%
zBqKjBGdVslF*o%VYe7+FUP+Pc<U%oBA&_oO?jj?QNyZ?;eDVe{SvE}&Q)BXFu@J`C
g%^Ko&7`Z_XDgqf-q&}HnGJ}<uQTmhI<QhqH0LHC8p#T5?

delta 299
zcmexowAq;NG%qg~0|NuYWSwJaic%Z-vU#{z85kIt85kHocT8^P$yF#}2g!qQ3Tq8h
z4Z~`X90LObBSQ^SFoP!B=5IXaOe$3z&dz>`xv5qPnk=`Nic)W}78m4XmfT{=%FoQZ
z#ad95nO8E|f!~=+j)8%}f`Ngd*lBVvzcJ4f7S0Z>3Hb|3uCVBAKEUtK$S6HoKv0fV
zje&t7V6(Ac3?r8Y0|P@5h=`p$Q%IXpWAjm=k4%hOledeyF-lMVC#oa`QhbZIpt2+*
zKQA*mJ})shwMYu2OK!4_n63~=uO@eqF-XJ&L|9C&7L#Su0x>lw&l3w_Oxyff><%M0
a$ZbU+!-_N}-;&5+<!6-sWH8xX(i{K-Axa?t

diff --git a/new_shit/python/sketchy.py b/new_shit/python/sketchy.py
index 0fa3628..0166911 100644
--- a/new_shit/python/sketchy.py
+++ b/new_shit/python/sketchy.py
@@ -18,6 +18,10 @@ system_interpolation_interval = MAXLInterpolationIntervals.INTERVAL_16384
 system_twin_to_real_ms = 200
 
 machine_extents = [80, 150]
+jog_rate = 100
+draw_rate = 50
+z_up = 0 
+z_down = -0.75
 
 async def main():
     try:
@@ -25,7 +29,9 @@ async def main():
 
         print("---------------------------------- get our files ...")
         segments = scale_and_process_svg("svg/test_files/rhino.svg", machine_extents, 0.25)
-        print(F"SVG has {len(segments)} paths...")
+        print(F"SVG has {len(segments)} segments...")
+
+        # raise Exception("bail")
 
         osap = OSAP("py-printer")
         loop = asyncio.get_event_loop()
@@ -51,53 +57,29 @@ async def main():
         print("---------------------------------- homing ...")
         await machine.home() 
 
-        # await machine.tour_extents() 
+        await machine.tour_extents() 
+
+        for s, segment in enumerate(segments):
+            # jog 2 above 1st pt 
+            first_pt = segment[0] 
+            xyz = [*first_pt, z_up]
+            await machine.queue_planner.goto_via_queue(xyz, jog_rate)
 
-        for segment in segments:
+            # draw seg 
             for pt in segment:
-                print(F"SEG: {pt[0]:.2f}, {pt[1]:.2f}")
-                xyz = [*pt, 0]
-                await machine.queue_planner.goto_via_queue(xyz, 50)
+                xyz = [*pt, z_down]
+                await machine.queue_planner.goto_via_queue(xyz, draw_rate)
+
+            # lift at last pt 
+            last_pt = segment[-1]
+            xyz = [*last_pt, z_up]
+            await machine.queue_planner.goto_via_queue(xyz, jog_rate)
 
         print("Flush...")
         await machine.queue_planner.flush_queue()
 
         await machine.queue_planner.goto_and_await([0,0,0], 100)
 
-        raise Exception("bail")
-
-        parser.set_current_position(extents_after_homing)
-
-        for _ in range(85000):
-            line = parser.get_next_line()
-            if line is None:
-                break 
-            if line.line_num % 100 == 0:
-                print(F"consuming {line.line_num} ... \t"\
-                        F"add_seg: {machine.queue_planner._profiler_addsegment.avg:.1F}, {machine.queue_planner._profiler_addsegment.hwm:.1F}\t "\
-                        F"new_cp: {machine.queue_planner._profiler_newcp.avg:.1F}, {machine.queue_planner._profiler_newcp.hwm:.1F}\t "\
-                        F"replan: {machine.queue_planner._profiler_replan.avg:.1F}, {machine.queue_planner._profiler_replan.hwm:.1F}")
-
-            e_absolute += line.e_delta 
-            pos_targ = [line.x, line.y, line.z, e_absolute]
-            if line.z > 1.4 and fan_set == False and line.line_num > 500:
-                fan_set = True 
-                if SET_TEMPS:
-                    await hotend_module.set_pcf(1) 
-            # print(line.line_num, line)
-            # gcodes spec mm/minute, we think in mm/sec 
-            await machine.queue_planner.goto_via_queue(pos_targ, line.target_velocity / 60)
-            await asyncio.sleep(0)
-
-        print("... flushing")
-        await machine.queue_planner.flush_queue()
-        print("... done")
-
-        await asyncio.sleep(1)
-
-        # # make it a little easier to home up next time... 
-        # await queue_planner.goto_now(extents_after_homing, 100)
-
         print("---------------------------------- END of main()")
 
 
@@ -111,7 +93,7 @@ async def main():
     finally: 
         print("---------------------------------- Finally: attempting shutdown...")
         if machine is not None:
-            await machine._maxl_core.shutdown() 
+            await machine.shutdown() 
         print("----------------------------------  shutdown OK")
 
 
diff --git a/new_shit/python/svg/__pycache__/svg_tools.cpython-312.pyc b/new_shit/python/svg/__pycache__/svg_tools.cpython-312.pyc
index c7f39b9dc086aa2378207a7b5067746fbaa8fcc0..e3602598f511f236206844cba7ef9fe04ed31b45 100644
GIT binary patch
delta 39
vcmaE*{YsnnG%qg~0|Ns?bmH+e%Z<Dd!i-#-(}cB{SQQv0KDbSuDjEs^-*gJw

delta 39
vcmaE*{YsnnG%qg~0|NuYhwNi%;v0D*gc;d3rwMB@vC1(@d~ljPRWuX;>?R9M

-- 
GitLab