Commit 84735ac0 authored by Jake Read's avatar Jake Read
Browse files

embedded deltas... from machine week activities? nothing major

parent 1e452de7
...@@ -1067,7 +1067,7 @@ design rules under a new name.</description> ...@@ -1067,7 +1067,7 @@ design rules under a new name.</description>
<attribute name="NAME" x="27.686" y="41.402" size="1.016" layer="25"/> <attribute name="NAME" x="27.686" y="41.402" size="1.016" layer="25"/>
<attribute name="VALUE" x="27.559" y="37.592" size="1.016" layer="27" ratio="10"/> <attribute name="VALUE" x="27.559" y="37.592" size="1.016" layer="27" ratio="10"/>
</element> </element>
<element name="R8" library="passives" package="1206" value="1k" x="33.655" y="40.005" smashed="yes" rot="R180"> <element name="R8" library="passives" package="1206" value="470R" x="33.655" y="40.005" smashed="yes" rot="R180">
<attribute name="NAME" x="34.417" y="39.1795" size="1.016" layer="25" rot="R180"/> <attribute name="NAME" x="34.417" y="39.1795" size="1.016" layer="25" rot="R180"/>
<attribute name="PACKAGE" value="1206" x="33.655" y="40.005" size="1.016" layer="27" rot="R180" display="off"/> <attribute name="PACKAGE" value="1206" x="33.655" y="40.005" size="1.016" layer="27" rot="R180" display="off"/>
<attribute name="PRECISION" value="" x="33.655" y="40.005" size="1.016" layer="27" rot="R180" display="off"/> <attribute name="PRECISION" value="" x="33.655" y="40.005" size="1.016" layer="27" rot="R180" display="off"/>
...@@ -1081,7 +1081,7 @@ design rules under a new name.</description> ...@@ -1081,7 +1081,7 @@ design rules under a new name.</description>
<attribute name="NAME" x="27.686" y="38.862" size="1.016" layer="25"/> <attribute name="NAME" x="27.686" y="38.862" size="1.016" layer="25"/>
<attribute name="VALUE" x="27.559" y="35.052" size="1.016" layer="27" ratio="10"/> <attribute name="VALUE" x="27.559" y="35.052" size="1.016" layer="27" ratio="10"/>
</element> </element>
<element name="R9" library="passives" package="1206" value="1k" x="33.655" y="37.465" smashed="yes" rot="R180"> <element name="R9" library="passives" package="1206" value="470R" x="33.655" y="37.465" smashed="yes" rot="R180">
<attribute name="NAME" x="34.417" y="36.6395" size="1.016" layer="25" rot="R180"/> <attribute name="NAME" x="34.417" y="36.6395" size="1.016" layer="25" rot="R180"/>
<attribute name="PACKAGE" value="1206" x="33.655" y="37.465" size="1.016" layer="27" rot="R180" display="off"/> <attribute name="PACKAGE" value="1206" x="33.655" y="37.465" size="1.016" layer="27" rot="R180" display="off"/>
<attribute name="PRECISION" value="" x="33.655" y="37.465" size="1.016" layer="27" rot="R180" display="off"/> <attribute name="PRECISION" value="" x="33.655" y="37.465" size="1.016" layer="27" rot="R180" display="off"/>
...@@ -1095,7 +1095,7 @@ design rules under a new name.</description> ...@@ -1095,7 +1095,7 @@ design rules under a new name.</description>
<attribute name="NAME" x="27.686" y="36.322" size="1.016" layer="25"/> <attribute name="NAME" x="27.686" y="36.322" size="1.016" layer="25"/>
<attribute name="VALUE" x="27.559" y="32.512" size="1.016" layer="27" ratio="10"/> <attribute name="VALUE" x="27.559" y="32.512" size="1.016" layer="27" ratio="10"/>
</element> </element>
<element name="R10" library="passives" package="1206" value="1k" x="33.655" y="34.925" smashed="yes" rot="R180"> <element name="R10" library="passives" package="1206" value="470R" x="33.655" y="34.925" smashed="yes" rot="R180">
<attribute name="NAME" x="34.417" y="34.0995" size="1.016" layer="25" rot="R180"/> <attribute name="NAME" x="34.417" y="34.0995" size="1.016" layer="25" rot="R180"/>
<attribute name="PACKAGE" value="1206" x="33.655" y="34.925" size="1.016" layer="27" rot="R180" display="off"/> <attribute name="PACKAGE" value="1206" x="33.655" y="34.925" size="1.016" layer="27" rot="R180" display="off"/>
<attribute name="PRECISION" value="" x="33.655" y="34.925" size="1.016" layer="27" rot="R180" display="off"/> <attribute name="PRECISION" value="" x="33.655" y="34.925" size="1.016" layer="27" rot="R180" display="off"/>
...@@ -1109,7 +1109,7 @@ design rules under a new name.</description> ...@@ -1109,7 +1109,7 @@ design rules under a new name.</description>
<attribute name="NAME" x="27.686" y="33.782" size="1.016" layer="25"/> <attribute name="NAME" x="27.686" y="33.782" size="1.016" layer="25"/>
<attribute name="VALUE" x="27.559" y="29.972" size="1.016" layer="27" ratio="10"/> <attribute name="VALUE" x="27.559" y="29.972" size="1.016" layer="27" ratio="10"/>
</element> </element>
<element name="R11" library="passives" package="1206" value="1k" x="33.655" y="32.385" smashed="yes" rot="R180"> <element name="R11" library="passives" package="1206" value="470R" x="33.655" y="32.385" smashed="yes" rot="R180">
<attribute name="NAME" x="34.417" y="31.5595" size="1.016" layer="25" rot="R180"/> <attribute name="NAME" x="34.417" y="31.5595" size="1.016" layer="25" rot="R180"/>
<attribute name="PACKAGE" value="1206" x="33.655" y="32.385" size="1.016" layer="27" rot="R180" display="off"/> <attribute name="PACKAGE" value="1206" x="33.655" y="32.385" size="1.016" layer="27" rot="R180" display="off"/>
<attribute name="PRECISION" value="" x="33.655" y="32.385" size="1.016" layer="27" rot="R180" display="off"/> <attribute name="PRECISION" value="" x="33.655" y="32.385" size="1.016" layer="27" rot="R180" display="off"/>
...@@ -1209,7 +1209,7 @@ design rules under a new name.</description> ...@@ -1209,7 +1209,7 @@ design rules under a new name.</description>
<attribute name="NAME" x="27.305" y="31.115" size="1.27" layer="25"/> <attribute name="NAME" x="27.305" y="31.115" size="1.27" layer="25"/>
<attribute name="VALUE" x="27.305" y="27.305" size="1.27" layer="27"/> <attribute name="VALUE" x="27.305" y="27.305" size="1.27" layer="27"/>
</element> </element>
<element name="R7" library="passives" package="1206" value="1k" x="33.655" y="29.845" smashed="yes" rot="R180"> <element name="R7" library="passives" package="1206" value="470R" x="33.655" y="29.845" smashed="yes" rot="R180">
<attribute name="NAME" x="34.925" y="28.702" size="1.016" layer="25" rot="R180"/> <attribute name="NAME" x="34.925" y="28.702" size="1.016" layer="25" rot="R180"/>
<attribute name="PACKAGE" value="1206" x="33.655" y="29.845" size="1.778" layer="27" font="vector" rot="R180" display="off"/> <attribute name="PACKAGE" value="1206" x="33.655" y="29.845" size="1.778" layer="27" font="vector" rot="R180" display="off"/>
<attribute name="PRECISION" value="" x="33.655" y="29.845" size="1.778" layer="27" font="vector" rot="R180" display="off"/> <attribute name="PRECISION" value="" x="33.655" y="29.845" size="1.778" layer="27" font="vector" rot="R180" display="off"/>
......
...@@ -6325,22 +6325,22 @@ chip</description> ...@@ -6325,22 +6325,22 @@ chip</description>
<part name="GND11" library="supply1" deviceset="GND" device=""/> <part name="GND11" library="supply1" deviceset="GND" device=""/>
<part name="GND12" library="supply1" deviceset="GND" device=""/> <part name="GND12" library="supply1" deviceset="GND" device=""/>
<part name="D2" library="lights" deviceset="LED" device="1206" value="LED1206"/> <part name="D2" library="lights" deviceset="LED" device="1206" value="LED1206"/>
<part name="R8" library="passives" deviceset="RESISTOR" device="1206" value="1k"/> <part name="R8" library="passives" deviceset="RESISTOR" device="1206" value="470R"/>
<part name="+3V4" library="supply1" deviceset="+3V3" device=""/> <part name="+3V4" library="supply1" deviceset="+3V3" device=""/>
<part name="J15" library="SparkFun-Connectors" deviceset="CONN_02" device="LOCK"/> <part name="J15" library="SparkFun-Connectors" deviceset="CONN_02" device="LOCK"/>
<part name="GND17" library="supply1" deviceset="GND" device=""/> <part name="GND17" library="supply1" deviceset="GND" device=""/>
<part name="D3" library="lights" deviceset="LED" device="1206" value="LED1206"/> <part name="D3" library="lights" deviceset="LED" device="1206" value="LED1206"/>
<part name="R9" library="passives" deviceset="RESISTOR" device="1206" value="1k"/> <part name="R9" library="passives" deviceset="RESISTOR" device="1206" value="470R"/>
<part name="+3V5" library="supply1" deviceset="+3V3" device=""/> <part name="+3V5" library="supply1" deviceset="+3V3" device=""/>
<part name="J16" library="SparkFun-Connectors" deviceset="CONN_02" device="LOCK"/> <part name="J16" library="SparkFun-Connectors" deviceset="CONN_02" device="LOCK"/>
<part name="GND18" library="supply1" deviceset="GND" device=""/> <part name="GND18" library="supply1" deviceset="GND" device=""/>
<part name="D4" library="lights" deviceset="LED" device="1206" value="LED1206"/> <part name="D4" library="lights" deviceset="LED" device="1206" value="LED1206"/>
<part name="R10" library="passives" deviceset="RESISTOR" device="1206" value="1k"/> <part name="R10" library="passives" deviceset="RESISTOR" device="1206" value="470R"/>
<part name="+3V6" library="supply1" deviceset="+3V3" device=""/> <part name="+3V6" library="supply1" deviceset="+3V3" device=""/>
<part name="J17" library="SparkFun-Connectors" deviceset="CONN_02" device="LOCK"/> <part name="J17" library="SparkFun-Connectors" deviceset="CONN_02" device="LOCK"/>
<part name="GND19" library="supply1" deviceset="GND" device=""/> <part name="GND19" library="supply1" deviceset="GND" device=""/>
<part name="D5" library="lights" deviceset="LED" device="1206" value="LED1206"/> <part name="D5" library="lights" deviceset="LED" device="1206" value="LED1206"/>
<part name="R11" library="passives" deviceset="RESISTOR" device="1206" value="1k"/> <part name="R11" library="passives" deviceset="RESISTOR" device="1206" value="470R"/>
<part name="+3V7" library="supply1" deviceset="+3V3" device=""/> <part name="+3V7" library="supply1" deviceset="+3V3" device=""/>
<part name="J18" library="SparkFun-Connectors" deviceset="CONN_02" device="LOCK"/> <part name="J18" library="SparkFun-Connectors" deviceset="CONN_02" device="LOCK"/>
<part name="GND20" library="supply1" deviceset="GND" device=""/> <part name="GND20" library="supply1" deviceset="GND" device=""/>
...@@ -6390,7 +6390,7 @@ chip</description> ...@@ -6390,7 +6390,7 @@ chip</description>
<part name="P+5" library="supply1" deviceset="+5V" device=""/> <part name="P+5" library="supply1" deviceset="+5V" device=""/>
<part name="P+6" library="supply1" deviceset="+5V" device=""/> <part name="P+6" library="supply1" deviceset="+5V" device=""/>
<part name="D9" library="lights" deviceset="LED" device="1206" value="LED1206"/> <part name="D9" library="lights" deviceset="LED" device="1206" value="LED1206"/>
<part name="R7" library="passives" deviceset="RESISTOR" device="1206" value="1k"/> <part name="R7" library="passives" deviceset="RESISTOR" device="1206" value="470R"/>
<part name="+3V3" library="supply1" deviceset="+3V3" device=""/> <part name="+3V3" library="supply1" deviceset="+3V3" device=""/>
<part name="J20" library="SparkFun-Connectors" deviceset="CONN_02" device="LOCK"/> <part name="J20" library="SparkFun-Connectors" deviceset="CONN_02" device="LOCK"/>
<part name="GND7" library="supply1" deviceset="GND" device=""/> <part name="GND7" library="supply1" deviceset="GND" device=""/>
......
...@@ -19,7 +19,7 @@ UsedLibrary="C:/Dropbox/CBA/circuits/eagle/parts/SparkFun-Eagle-Libraries/SparkF ...@@ -19,7 +19,7 @@ UsedLibrary="C:/Dropbox/CBA/circuits/eagle/parts/SparkFun-Eagle-Libraries/SparkF
Type="Schematic Editor" Type="Schematic Editor"
Number=1 Number=1
File="2020-08_psu-breakout.sch" File="2020-08_psu-breakout.sch"
View="-45.293 31.146 556.518 211.07" View="191.998 139.609 359.952 189.822"
WireWidths=" 0.0762 0.1016 0.127 0.15 0.2 0.2032 0.254 0.3048 0.4064 0.508 0.6096 0.8128 1.016 1.27 2.54 0.1524" WireWidths=" 0.0762 0.1016 0.127 0.15 0.2 0.2032 0.254 0.3048 0.4064 0.508 0.6096 0.8128 1.016 1.27 2.54 0.1524"
PadDiameters=" 0.254 0.3048 0.4064 0.6096 0.8128 1.016 1.27 1.4224 1.6764 1.778 1.9304 2.1844 2.54 3.81 6.4516 0" PadDiameters=" 0.254 0.3048 0.4064 0.6096 0.8128 1.016 1.27 1.4224 1.6764 1.778 1.9304 2.1844 2.54 3.81 6.4516 0"
PadDrills=" 0.2 0.25 0.3 0.35 0.4 0.45 0.5 0.55 0.65 0.7 0.75 0.8 0.85 0.9 1 0.6" PadDrills=" 0.2 0.25 0.3 0.35 0.4 0.45 0.5 0.55 0.65 0.7 0.75 0.8 0.85 0.9 1 0.6"
...@@ -58,14 +58,14 @@ ArcDirection=0 ...@@ -58,14 +58,14 @@ ArcDirection=0
AddLevel=2 AddLevel=2
PadsSameType=0 PadsSameType=0
Layer=91 Layer=91
Views=" 1: -45.293 31.146 556.518 211.07" Views=" 1: 191.998 139.609 359.952 189.822"
Sheet="1" Sheet="1"
[Win_2] [Win_2]
Type="Board Editor" Type="Board Editor"
Number=2 Number=2
File="2020-08_psu-breakout.brd" File="2020-08_psu-breakout.brd"
View="12.384 -7.24152 122.016 84.5385" View="22.6761 -7.9544 114.036 68.529"
WireWidths=" 0.1016 0.15 0.2 2.54 0 0.508 0.2032 0.254 0.3048 0.4064 0.1524 1.016 1.27 0.127 0.6096 0.8128" WireWidths=" 0.1016 0.15 0.2 2.54 0 0.508 0.2032 0.254 0.3048 0.4064 0.1524 1.016 1.27 0.127 0.6096 0.8128"
PadDiameters=" 0.254 0.3048 0.4064 0.6096 0.8128 1.016 1.27 1.4224 1.6764 1.778 1.9304 2.1844 2.54 3.81 6.4516 0" PadDiameters=" 0.254 0.3048 0.4064 0.6096 0.8128 1.016 1.27 1.4224 1.6764 1.778 1.9304 2.1844 2.54 3.81 6.4516 0"
PadDrills=" 0.2 0.25 0.3 0.35 0.4 0.5 0.55 0.65 0.7 0.75 0.8 0.85 0.9 1 0.6 0.45" PadDrills=" 0.2 0.25 0.3 0.35 0.4 0.5 0.55 0.65 0.7 0.75 0.8 0.85 0.9 1 0.6 0.45"
......
...@@ -18,4 +18,21 @@ This is a circuit & mount for a small power supply and embedded system bus-head ...@@ -18,4 +18,21 @@ This is a circuit & mount for a small power supply and embedded system bus-head
### Firmware ### Firmware
I use this board mostly as the 'coordinator' for modular motion systems, firmware is [here](firmware) and uses platform.io to run, see [this guide](https://mtm.cba.mit.edu/2021/2021-10_microcontroller-primer/fab-platformio/) to build and load code. I use this board mostly as the 'coordinator' for modular motion systems, firmware is [here](firmware) and uses platform.io to run, see [this guide](https://mtm.cba.mit.edu/2021/2021-10_microcontroller-primer/fab-platformio/) to build and load code.
\ No newline at end of file
### Shorthand BOM
- 7x 470R / 120R / LED Choice R
- 3x 1k
- 2x 4k7
- 2x 10k
- 4x 1uF
- 4x 10uF
- 8x LED,
- TVS Diode
- 2x Hi-Side Gate DRV MIC5014
- 3x NFET TPW4R008NH
- Optional I2C Display
- Optional 4x Pushbutton
- Optional Pololu D36V50F5 Regulator (PSU -> RPI)
- Optional RPI
\ No newline at end of file
// indicators for the module // circuit specific indicators: modular-motion-head 2021-08-26
// older module (with smt debug) these are *not routed* my mistake
// newer module they are PA27 and PB08 respectively #define PIN_BM(pin) (uint32_t)(1 << pin)
#define CLKLIGHT_PIN 27 #define PIN_HI(port, pin) PORT->Group[port].OUTSET.reg = PIN_BM(pin)
#define CLKLIGHT_PORT PORT->Group[0] #define PIN_LO(port, pin) PORT->Group[port].OUTCLR.reg = PIN_BM(pin)
#define CLKLIGHT_BM (uint32_t)(1 << CLKLIGHT_PIN) #define PIN_TGL(port, pin) PORT->Group[port].OUTTGL.reg = PIN_BM(pin)
#define CLKLIGHT_ON CLKLIGHT_PORT.OUTCLR.reg = CLKLIGHT_BM #define PIN_SETUP_OUTPUT(port, pin) PORT->Group[port].DIRSET.reg = PIN_BM(pin)
#define CLKLIGHT_OFF CLKLIGHT_PORT.OUTSET.reg = CLKLIGHT_BM
#define CLKLIGHT_TOGGLE CLKLIGHT_PORT.OUTTGL.reg = CLKLIGHT_BM #define CLKLIGHT_ON PIN_LO(0, 27)
#define CLKLIGHT_SETUP CLKLIGHT_PORT.DIRSET.reg = CLKLIGHT_BM; CLKLIGHT_OFF #define CLKLIGHT_OFF PIN_HI(0, 27)
#define CLKLIGHT_TOGGLE PIN_TGL(0, 27)
#define ERRLIGHT_PIN 8 #define CLKLIGHT_SETUP PIN_SETUP_OUTPUT(0, 27); CLKLIGHT_OFF
#define ERRLIGHT_PORT PORT->Group[1]
#define ERRLIGHT_BM (uint32_t)(1 << ERRLIGHT_PIN) #define ERRLIGHT_ON PIN_LO(1, 8)
#define ERRLIGHT_ON ERRLIGHT_PORT.OUTCLR.reg = ERRLIGHT_BM #define ERRLIGHT_OFF PIN_HI(1, 8)
#define ERRLIGHT_OFF ERRLIGHT_PORT.OUTSET.reg = ERRLIGHT_BM #define ERRLIGHT_TOGGLE PIN_TGL(1, 8)
#define ERRLIGHT_TOGGLE ERRLIGHT_PORT.OUTTGL.reg = ERRLIGHT_BM #define ERRLIGHT_SETUP PIN_SETUP_OUTPUT(1, 8); ERRLIGHT_OFF
#define ERRLIGHT_SETUP ERRLIGHT_PORT.DIRSET.reg = ERRLIGHT_BM; ERRLIGHT_OFF
// breakout debugs are pin-to-gnd,
// PSU-breakout board lights, // PA13, PA12, PB15, PB14, PA04
#define DEBUG1PIN_PIN 13 #define DEBUG1PIN_ON PIN_LO(0, 13)
#define DEBUG1PIN_PORT PORT->Group[0] #define DEBUG1PIN_OFF PIN_HI(0, 13)
#define DEBUG1PIN_BM (uint32_t)(1 << DEBUG1PIN_PIN) #define DEBUG1PIN_HI PIN_HI(0, 13)
#define DEBUG1PIN_HI DEBUG1PIN_PORT.OUTSET.reg = DEBUG1PIN_BM #define DEBUG1PIN_LO PIN_LO(0, 13)
#define DEBUG1PIN_LO DEBUG1PIN_PORT.OUTCLR.reg = DEBUG1PIN_BM #define DEBUG1PIN_TOGGLE PIN_TGL(0, 13)
// in the case of the psu-breakout-board, where this code probably lives, pin-hi is led-off, pin-lo is led-on, #define DEBUG1PIN_SETUP PIN_SETUP_OUTPUT(0, 13); PIN_HI(0, 13)
#define DEBUG1PIN_ON DEBUG1PIN_LO
#define DEBUG1PIN_OFF DEBUG1PIN_HI #define DEBUG2PIN_ON PIN_LO(0, 13)
#define DEBUG1PIN_TOGGLE DEBUG1PIN_PORT.OUTTGL.reg = DEBUG1PIN_BM #define DEBUG2PIN_OFF PIN_HI(0, 13)
#define DEBUG1PIN_SETUP DEBUG1PIN_PORT.DIRSET.reg = DEBUG1PIN_BM; DEBUG1PIN_HI #define DEBUG2PIN_HI PIN_HI(0, 13)
#define DEBUG2PIN_LO PIN_LO(0, 13)
#define DEBUG2PIN_PIN 12 #define DEBUG2PIN_TOGGLE PIN_TGL(0, 13)
#define DEBUG2PIN_PORT PORT->Group[0] #define DEBUG2PIN_SETUP PIN_SETUP_OUTPUT(0, 13); PIN_HI(0, 13)
#define DEBUG2PIN_BM (uint32_t)(1 << DEBUG2PIN_PIN)
#define DEBUG2PIN_HI DEBUG2PIN_PORT.OUTSET.reg = DEBUG2PIN_BM #define DEBUG3PIN_ON PIN_LO(1, 15)
#define DEBUG2PIN_LO DEBUG2PIN_PORT.OUTCLR.reg = DEBUG2PIN_BM #define DEBUG3PIN_OFF PIN_HI(1, 15)
#define DEBUG2PIN_ON DEBUG2PIN_LO #define DEBUG3PIN_HI PIN_HI(1, 15)
#define DEBUG2PIN_OFF DEBUG2PIN_HI #define DEBUG3PIN_LO PIN_LO(1, 15)
#define DEBUG2PIN_TOGGLE DEBUG2PIN_PORT.OUTTGL.reg = DEBUG2PIN_BM #define DEBUG3PIN_TOGGLE PIN_TGL(1, 15)
#define DEBUG2PIN_SETUP DEBUG2PIN_PORT.DIRSET.reg = DEBUG2PIN_BM; DEBUG2PIN_HI #define DEBUG3PIN_SETUP PIN_SETUP_OUTPUT(1, 15); PIN_HI(1, 15)
#define DEBUG3PIN_PIN 15 #define DEBUG4PIN_ON PIN_LO(1, 14)
#define DEBUG3PIN_PORT PORT->Group[1] #define DEBUG4PIN_OFF PIN_HI(1, 14)
#define DEBUG3PIN_BM (uint32_t)(1 << DEBUG3PIN_PIN) #define DEBUG4PIN_HI PIN_HI(1, 14)
#define DEBUG3PIN_HI DEBUG3PIN_PORT.OUTSET.reg = DEBUG3PIN_BM #define DEBUG4PIN_LO PIN_LO(1, 14)
#define DEBUG3PIN_LO DEBUG3PIN_PORT.OUTCLR.reg = DEBUG3PIN_BM #define DEBUG4PIN_TOGGLE PIN_TGL(1, 14)
#define DEBUG3PIN_ON DEBUG3PIN_LO #define DEBUG4PIN_SETUP PIN_SETUP_OUTPUT(1, 14); PIN_HI(1, 14)
#define DEBUG3PIN_OFF DEBUG3PIN_HI
#define DEBUG3PIN_TOGGLE DEBUG3PIN_PORT.OUTTGL.reg = DEBUG3PIN_BM #define DEBUG5PIN_ON PIN_LO(0, 4)
#define DEBUG3PIN_SETUP DEBUG3PIN_PORT.DIRSET.reg = DEBUG3PIN_BM; DEBUG3PIN_HI #define DEBUG5PIN_OFF PIN_HI(0, 4)
#define DEBUG5PIN_HI PIN_HI(0, 4)
#define DEBUG4PIN_PIN 14 #define DEBUG5PIN_LO PIN_LO(0, 4)
#define DEBUG4PIN_PORT PORT->Group[1] #define DEBUG5PIN_TOGGLE PIN_TGL(0, 4)
#define DEBUG4PIN_BM (uint32_t)(1 << DEBUG4PIN_PIN) #define DEBUG5PIN_SETUP PIN_SETUP_OUTPUT(0, 4); PIN_HI(0, 4)
#define DEBUG4PIN_HI DEBUG4PIN_PORT.OUTSET.reg = DEBUG4PIN_BM
#define DEBUG4PIN_LO DEBUG4PIN_PORT.OUTCLR.reg = DEBUG4PIN_BM
#define DEBUG4PIN_ON DEBUG4PIN_LO
#define DEBUG4PIN_OFF DEBUG4PIN_HI
#define DEBUG4PIN_TOGGLE DEBUG4PIN_PORT.OUTTGL.reg = DEBUG4PIN_BM
#define DEBUG4PIN_SETUP DEBUG4PIN_PORT.DIRSET.reg = DEBUG4PIN_BM; DEBUG4PIN_HI
\ No newline at end of file
...@@ -51,7 +51,7 @@ EP_ONDATA_RESPONSES onMoveData(uint8_t* data, uint16_t len){ ...@@ -51,7 +51,7 @@ EP_ONDATA_RESPONSES onMoveData(uint8_t* data, uint16_t len){
// do load // do load
float target[3] = {targetChunks[0].f, targetChunks[1].f, targetChunks[2].f }; float target[3] = {targetChunks[0].f, targetChunks[1].f, targetChunks[2].f };
//sysError("targets, rate: " + String(target[0], 6) + ", " + String(target[1], 6) + ", " + String(target[2], 6) + ", " + String(feedrateChunk.f, 6)); //sysError("targets, rate: " + String(target[0], 6) + ", " + String(target[1], 6) + ", " + String(target[2], 6) + ", " + String(feedrateChunk.f, 6));
planner->append_move(target, SR_NUM_MOTORS, feedrateChunk.f, targetChunks[3].f); // mm/min -> mm/sec planner->append_move(target, SR_NUM_MOTORS, feedrateChunk.f, targetChunks[3].f); // it's mm/sec
return EP_ONDATA_ACCEPT; return EP_ONDATA_ACCEPT;
} }
} else { } else {
...@@ -60,15 +60,10 @@ EP_ONDATA_RESPONSES onMoveData(uint8_t* data, uint16_t len){ ...@@ -60,15 +60,10 @@ EP_ONDATA_RESPONSES onMoveData(uint8_t* data, uint16_t len){
} }
} }
vertex_t* moveQueueEp = osapBuildEndpoint("moveQueue", onMoveData, nullptr); // 2 endpoint_t* moveQueueEp = osapBuildEndpoint("moveQueue", onMoveData); // 2
// -------------------------------------------------------- POSITION ENDPOINT // -------------------------------------------------------- POSITION ENDPOINT
EP_ONDATA_RESPONSES onPositionSet(uint8_t* data, uint16_t len);
boolean beforePositionQuery(void);
vertex_t* positionEp = osapBuildEndpoint("position", onPositionSet, beforePositionQuery); // 3
EP_ONDATA_RESPONSES onPositionSet(uint8_t* data, uint16_t len){ EP_ONDATA_RESPONSES onPositionSet(uint8_t* data, uint16_t len){
// only if it's not moving, // only if it's not moving,
if(smoothie_is_moving()){ if(smoothie_is_moving()){
...@@ -88,55 +83,47 @@ EP_ONDATA_RESPONSES onPositionSet(uint8_t* data, uint16_t len){ ...@@ -88,55 +83,47 @@ EP_ONDATA_RESPONSES onPositionSet(uint8_t* data, uint16_t len){
} }
} }
boolean beforePositionQuery(void){ endpoint_t* positionEp = osapBuildEndpoint("positions", onPositionSet); // 3
uint8_t posData[16];
void updatePositions(void){
// write new pos data periodically, // write new pos data periodically,
uint8_t posData[16];
uint16_t poswptr = 0; uint16_t poswptr = 0;
ts_writeFloat32(smoothieRoll->actuators[0]->floating_position, posData, &poswptr); ts_writeFloat32(smoothieRoll->actuators[0]->floating_position, posData, &poswptr);
ts_writeFloat32(smoothieRoll->actuators[1]->floating_position, posData, &poswptr); ts_writeFloat32(smoothieRoll->actuators[1]->floating_position, posData, &poswptr);
ts_writeFloat32(smoothieRoll->actuators[2]->floating_position, posData, &poswptr); ts_writeFloat32(smoothieRoll->actuators[2]->floating_position, posData, &poswptr);
ts_writeFloat32(smoothieRoll->actuators[3]->floating_position, posData, &poswptr); ts_writeFloat32(smoothieRoll->actuators[3]->floating_position, posData, &poswptr);
memcpy(positionEp->ep->data, posData, 16); endpointWrite(positionEp, posData, 16);
positionEp->ep->dataLen = 16;
return true;
} }
// -------------------------------------------------------- CURRENT SPEEDS // -------------------------------------------------------- CURRENT SPEEDS
boolean beforeSpeedQuery(void); endpoint_t* speedEp = osapBuildEndpoint("speeds");
uint8_t speedData[16];
vertex_t* speedEp = osapBuildEndpoint("speed", nullptr, beforeSpeedQuery);
boolean beforeSpeedQuery(void){ void updateSpeeds(void){
// collect actuator speeds, // collect actuator speeds,
uint8_t speedData[16];
uint16_t wptr = 0; uint16_t wptr = 0;
ts_writeFloat32(smoothieRoll->actuators[0]->get_current_speed(), speedData, &wptr); ts_writeFloat32(smoothieRoll->actuators[0]->get_current_speed(), speedData, &wptr);
ts_writeFloat32(smoothieRoll->actuators[1]->get_current_speed(), speedData, &wptr); ts_writeFloat32(smoothieRoll->actuators[1]->get_current_speed(), speedData, &wptr);
ts_writeFloat32(smoothieRoll->actuators[2]->get_current_speed(), speedData, &wptr); ts_writeFloat32(smoothieRoll->actuators[2]->get_current_speed(), speedData, &wptr);
ts_writeFloat32(smoothieRoll->actuators[3]->get_current_speed(), speedData, &wptr); ts_writeFloat32(smoothieRoll->actuators[3]->get_current_speed(), speedData, &wptr);
memcpy(speedEp->ep->data, speedData, 16); endpointWrite(speedEp, speedData, 16);
speedEp->ep->dataLen = 16;
return true;
} }
// -------------------------------------------------------- MOTION STATE EP // -------------------------------------------------------- MOTION STATE EP
boolean beforeMotionStateQuery(void); endpoint_t* motionStateEp = osapBuildEndpoint("motionState"); // 4
uint8_t motionData[1];
vertex_t* motionStateEp = osapBuildEndpoint("motionState", nullptr, beforeMotionStateQuery); // 4 void updateMotionState(void){
boolean beforeMotionStateQuery(void){
uint8_t motion;
if(smoothieRoll->actuators[0]->is_moving() || smoothieRoll->actuators[1]->is_moving() || smoothieRoll->actuators[2]->is_moving() || !smoothie_is_queue_empty()){ if(smoothieRoll->actuators[0]->is_moving() || smoothieRoll->actuators[1]->is_moving() || smoothieRoll->actuators[2]->is_moving() || !smoothie_is_queue_empty()){
motion = 1; motionData[0] = 1;
} else { } else {
motion = 0; motionData[0] = 0;
} }
motionStateEp->ep->data[0] = motion; endpointWrite(motionStateEp, motionData, 1);
motionStateEp->ep->dataLen = 1;
//sysError("motion query " + String(motion));
return true;
} }
// -------------------------------------------------------- WAIT TIME EP // -------------------------------------------------------- WAIT TIME EP
...@@ -152,7 +139,7 @@ EP_ONDATA_RESPONSES onWaitTimeData(uint8_t* data, uint16_t len){ ...@@ -152,7 +139,7 @@ EP_ONDATA_RESPONSES onWaitTimeData(uint8_t* data, uint16_t len){
return EP_ONDATA_ACCEPT; return EP_ONDATA_ACCEPT;
} }
vertex_t* waitTimeEp = osapBuildEndpoint("waitTime", onWaitTimeData, nullptr); // 5 endpoint_t* waitTimeEp = osapBuildEndpoint("waitTime", onWaitTimeData); // 5
// -------------------------------------------------------- ACCEL SETTTINGS // -------------------------------------------------------- ACCEL SETTTINGS
...@@ -172,7 +159,7 @@ EP_ONDATA_RESPONSES onAccelSettingsData(uint8_t* data, uint16_t len){ ...@@ -172,7 +159,7 @@ EP_ONDATA_RESPONSES onAccelSettingsData(uint8_t* data, uint16_t len){
return EP_ONDATA_ACCEPT; return EP_ONDATA_ACCEPT;
} }
vertex_t* accelSettingsEp = osapBuildEndpoint("accelSettings", onAccelSettingsData, nullptr); endpoint_t* accelSettingsEp = osapBuildEndpoint("accelSettings", onAccelSettingsData);
// -------------------------------------------------------- RATES SETTINGS // -------------------------------------------------------- RATES SETTINGS
...@@ -192,7 +179,7 @@ EP_ONDATA_RESPONSES onRateSettingsData(uint8_t* data, uint16_t len){ ...@@ -192,7 +179,7 @@ EP_ONDATA_RESPONSES onRateSettingsData(uint8_t* data, uint16_t len){
return EP_ONDATA_ACCEPT; return EP_ONDATA_ACCEPT;
} }
vertex_t* rateSettingsEp = osapBuildEndpoint("rateSettings", onRateSettingsData, nullptr); endpoint_t* rateSettingsEp = osapBuildEndpoint("rateSettings", onRateSettingsData);
// -------------------------------------------------------- SETUP // -------------------------------------------------------- SETUP
...@@ -203,29 +190,30 @@ void setup() { ...@@ -203,29 +190,30 @@ void setup() {
DEBUG2PIN_SETUP; DEBUG2PIN_SETUP;
DEBUG3PIN_SETUP; DEBUG3PIN_SETUP;
DEBUG4PIN_SETUP; DEBUG4PIN_SETUP;
DEBUG5PIN_SETUP;
// osap // osap
osapSetup(); osapSetup("modularMotionHead");
// ports // ports
vt_usbSerial_setup(); vt_usbSerial_setup();
osapAddVertex(vt_usbSerial); // 0 osapAddVertex(vt_usbSerial); // 0
vt_ucBusHead_setup(); vt_ucBusHead_setup();
osapAddVertex(vt_ucBusHead); // 1 osapAddVertex(vt_ucBusHead); // 1
// move to queue // move to queue
osapAddVertex(moveQueueEp); // 2 osapAddEndpoint(moveQueueEp); // 2
// position // position
osapAddVertex(positionEp); // 3 osapAddEndpoint(positionEp); // 3
// speed // speed
osapAddVertex(speedEp); // 4 osapAddEndpoint(speedEp); // 4
// motion state // motion state
osapAddVertex(motionStateEp); // 5 osapAddEndpoint(motionStateEp); // 5
// set wait time (ms) // set wait time (ms)
osapAddVertex(waitTimeEp); // 6 osapAddEndpoint(waitTimeEp); // 6
// acceler8 settings // acceler8 settings
osapAddVertex(accelSettingsEp); // 7 osapAddEndpoint(accelSettingsEp); // 7
// r8 settings // r8 settings
osapAddVertex(rateSettingsEp); // 8 osapAddEndpoint(rateSettingsEp); // 8
// smoothie (and frequency of loop below) // smoothie (and frequency of loop below)
smoothieRoll->init(20000); smoothieRoll->init(10000);
// 25kHz base (40us period) or // 25kHz base (40us period) or
// 20kHz base (50us period) // 20kHz base (50us period)
// 10kHz base (100us period) // 10kHz base (100us period)
...@@ -233,11 +221,23 @@ void setup() { ...@@ -233,11 +221,23 @@ void setup() {
d51ClockBoss->start_ticker_a(100); d51ClockBoss->start_ticker_a(100);
} }
unsigned long epUpdateInterval = 100; // ms
unsigned long lastUpdate = 0;
void loop() { void loop() {
// write ~ every second, transmit on chb to drop 1 // main recursive osap loop:
// check indices on the way down / up ... was shifting, are not anymore
osapLoop(); osapLoop();
conveyor->on_idle(nullptr); // smoothie checks / etc:
//conveyor->on_idle(nullptr);
// run 10Hz endpoint update:
if(millis() > lastUpdate + epUpdateInterval){
DEBUG5PIN_TOGGLE;
lastUpdate = millis();
updatePositions();
updateSpeeds();
updateMotionState();
}
} // end loop } // end loop
// runs on period defined by timer_a setup: // runs on period defined by timer_a setup:
...@@ -262,7 +262,7 @@ void TC0_Handler(void){ ...@@ -262,7 +262,7 @@ void TC0_Handler(void){
// each of these ticks drops 10 data bytes, so if we have 17 byte packet, can do every 2nd packet // each of these ticks drops 10 data bytes, so if we have 17 byte packet, can do every 2nd packet
// which would occupy the full bus - notgood - or we can do every 3rd... I'll pick every 4th. // which would occupy the full bus - notgood - or we can do every 3rd... I'll pick every 4th.
timeTick ++; timeTick ++;
if(timeTick > 3){ if(timeTick > 2){
DEBUG2PIN_HI; DEBUG2PIN_HI;
timeTick = 0; timeTick = 0;
uint16_t mpptr = 0; // motion packet pointer uint16_t mpptr = 0; // motion packet pointer
...@@ -290,4 +290,4 @@ void TC0_Handler(void){ ...@@ -290,4 +290,4 @@ void TC0_Handler(void){
timeBlink = 0; timeBlink = 0;
} }
DEBUG1PIN_LO; DEBUG1PIN_LO;
} }
\ No newline at end of file
Subproject commit 23064339e200c3819af8bc55988b57d3eaa28a2e Subproject commit acbff5f3f0333d072780d32246ac15a6aa7f1a62
...@@ -62,7 +62,6 @@ void StepTicker::start(){ ...@@ -62,7 +62,6 @@ void StepTicker::start(){
#warning This leaves config as is, see startup to 'make proper'. #warning This leaves config as is, see startup to 'make proper'.
void StepTicker::set_frequency( float frequency ){ void StepTicker::set_frequency( float frequency ){
this->frequency = frequency; this->frequency = frequency;
this->period = 80; // set manually above, floorf((SystemCoreClock / 4.0F) / frequency); // SystemCoreClock/4 = Timer increments in a second
} }
// step clock // step clock
......