diff --git a/.gitmodules b/.gitmodules index 6deb88208aadda4f58e96873b65665a69a7d4cdf..fa16f1593bab25e8e9231cf4034d1a8b40e02d4c 100644 --- a/.gitmodules +++ b/.gitmodules @@ -4,3 +4,6 @@ [submodule "controller/osapjs"] path = controller/osapjs url = ssh://git@gitlab.cba.mit.edu:846/jakeread/osapjs.git +[submodule "firmware/cl-step-controller/src/osape"] + path = firmware/cl-step-controller/src/osape + url = ssh://git@gitlab.cba.mit.edu:846/jakeread/osape.git diff --git a/controller/client/clStepClient.js b/controller/client/clStepClient.js new file mode 100644 index 0000000000000000000000000000000000000000..711042b30e8410d6ff3ec23223e762fb52627dfa --- /dev/null +++ b/controller/client/clStepClient.js @@ -0,0 +1,276 @@ +/* +clank-client.js + +clank controller client side + +Jake Read at the Center for Bits and Atoms +(c) Massachusetts Institute of Technology 2020 + +This work may be reproduced, modified, distributed, performed, and +displayed for any purpose, but must acknowledge the open systems assembly protocol (OSAP) project. +Copyright is retained and must be preserved. The work is provided as is; +no warranty is provided, and users accept all liability. +*/ + +'use strict' + +import OSAP from '../osapjs/core/osap.js' +import { TS, PK, DK, AK, EP } from '../osapjs/core/ts.js' +import NetRunner from '../osapjs/client/netrunner/osap-render.js' + +// the clank 'virtual machine' +import ClStepVM from './clStepVM.js' + +import { AutoPlot } from '../osapjs/client/components/autoPlot.js' +import { Button } from '../osapjs/client/interface/button.js' +import { TextInput } from '../osapjs/client/interface/textInput.js' + +console.log("hello clank controller") + +// an instance of some osap capable thing (the virtual object) +// that will appear on the network, be virtually addressable +let osap = new OSAP() +osap.name = "cl-step tuner client" + +// draws network, +let netrunner = new NetRunner(osap, 10, 760, false) + +// -------------------------------------------------------- THE VM + +// vm, +let vm = new ClStepVM(osap, TS.route().portf(0).portf(1).end()) + +// -------------------------------------------------------- QUERY MAG + +let magDiagnosticsBtn = new Button(10, 10, 94, 14, 'mag?') +magDiagnosticsBtn.onClick(() => { + vm.getMagDiagnostics().then((result) => { + console.log(result) + magDiagnosticsBtn.good("ok", 500) + }).catch((err) => { + console.error(err) + magDiagnosticsBtn.bad("err", 500) + }) +}) + +// -------------------------------------------------------- DO CALIB + +let runCalibBtn = new Button(10, 40, 94, 14, 'calibr8') +runCalibBtn.onClick(() => { + vm.runCalib().then(() => { + runCalibBtn.good("ok", 500) + }).catch((err) => { + console.error(err) + runCalibBtn.bad("err", 500) + }) +}) + +// -------------------------------------------------------- QUERY POSITION + +let posnLp = false +let positionQueryBtn = new Button(10, 70, 94, 14, 'pos?') +positionQueryBtn.onClick(() => { + if (posnLp) { + posnLp = false + } else { + let loop = () => { + if (!posnLp) { + positionQueryBtn.bad("halted", 500) + } else { + vm.getPosition().then((pos) => { + $(positionQueryBtn.elem).text(pos.toFixed(3)) + setTimeout(loop, 10) + }).catch((err) => { + console.error(err) + posnLp = false; + setTimeout(loop, 10) + }) + } + } + posnLp = true + loop() + } +}) + +// -------------------------------------------------------- LOOP SPEC + +let encPlot = new AutoPlot(130, 10, 500, 210, 'encoder') +encPlot.setHoldCount(500) +//tempPlot.setYDomain(0, 100) +encPlot.redraw() + +let anglePlot = new AutoPlot(130, 230, 500, 210, 'angle reading') +anglePlot.setHoldCount(500) +//tempPlot.setYDomain(0, 100) +anglePlot.redraw() + +let angleEstPlot = new AutoPlot(130, 450, 500, 210, 'angle estimate') +angleEstPlot.setHoldCount(500) +//tempPlot.setYDomain(0, 100) +angleEstPlot.redraw() + +let angleDotPlot = new AutoPlot(130, 670, 500, 210, 'angle dot') +angleDotPlot.setHoldCount(500) +angleDotPlot.redraw() + +let specLp = false +let specPlotCount = 0 +let loopQueryBtn = new Button(10, 100, 94, 14, 'spec?') +loopQueryBtn.onClick(() => { + if (specLp) { + specLp = false + } else { + let loop = () => { + if (!specLp) { + loopQueryBtn.bad("halted", 500) + } else { + vm.getSpec().then((spec) => { + specPlotCount++ + encPlot.pushPt([specPlotCount, spec.encoder]); encPlot.redraw() + anglePlot.pushPt([specPlotCount, spec.angle]); anglePlot.redraw() + angleEstPlot.pushPt([specPlotCount, spec.angleEstimate]); angleEstPlot.redraw() + setTimeout(loop, 10) + }).catch((err) => { + console.error(err) + specLp = false; + setTimeout(loop, 10) + }) + } + } + specLp = true + loop() + } +}) + +// -------------------------------------------------------- MOTION FEED + +// -------------------------------------------------------- PID + +let PIDController = (xPlace, yPlace) => { + let pVal = new TextInput(xPlace, yPlace + 120, 110, 20, '-0.1') + let iVal = new TextInput(xPlace, yPlace + 150, 110, 20, '0.0') + let dVal = new TextInput(xPlace, yPlace + 180, 110, 20, '0.1') + + let pidSetBtn = new Button(xPlace, yPlace + 210, 104, 14, 'set PID') + pidSetBtn.onClick(() => { + let p = parseFloat(pVal.value) + let i = parseFloat(iVal.value) + let d = parseFloat(dVal.value) + if (Number.isNaN(p) || Number.isNaN(i) || Number.isNaN(d)) { + pidSetBtn.bad("bad parse", 1000) + return + } + tvm.setPIDTerms([p, i, d]).then(() => { + pidSetBtn.good("ok", 500) + }).catch((err) => { + console.error(err) + pidSetBtn.bad("err", 1000) + }) + }) + + let tempPlot = new AutoPlot(xPlace + 120, yPlace, 420, 230) + tempPlot.setHoldCount(500) + //tempPlot.setYDomain(0, 100) + tempPlot.redraw() + + let effortPlot = new AutoPlot(xPlace + 120, yPlace + 240, 420, 150) + effortPlot.setHoldCount(500) + //effortPlot.setYDomain(-10, 10) + effortPlot.redraw() + + let tempLpBtn = new Button(xPlace, yPlace + 90, 104, 14, 'plot temp') + let tempLp = false + let tempLpCount = 0 + tempLpBtn.onClick(() => { + if (tempLp) { + tempLp = false + tempLpBtn.good("stopped", 500) + } else { + let poll = () => { + if (!tempLp) return + tvm.getExtruderTemp().then((temp) => { + //console.log(temp) + tempLpCount++ + tempPlot.pushPt([tempLpCount, temp]) + tempPlot.redraw() + return tvm.getExtruderTempOutput() + }).then((effort) => { + //console.log(effort) + effortPlot.pushPt([tempLpCount, effort]) + effortPlot.redraw() + setTimeout(poll, 200) + }).catch((err) => { + tempLp = false + console.error(err) + tempLpBtn.bad("err", 500) + }) + } + tempLp = true + poll() + } + }) +} + +//PIDController(240, 10) + + +// -------------------------------------------------------- STARTUP LOCAL + +let wscVPort = osap.vPort() +wscVPort.name = 'websocket client' +wscVPort.maxSegLength = 1024 + +let LOGPHY = false + +// to test these systems, the client (us) will kickstart a new process +// on the server, and try to establish connection to it. +console.log("making client-to-server request to start remote process,") +console.log("and connecting to it w/ new websocket") +// ok, let's ask to kick a process on the server, +// in response, we'll get it's IP and Port, +// then we can start a websocket client to connect there, +// automated remote-proc. w/ vPort & wss medium, +// for args, do '/processName.js?args=arg1,arg2' + +jQuery.get('/startLocal/osapl-usb-bridge.js', (res) => { + if (res.includes('OSAP-wss-addr:')) { + let addr = res.substring(res.indexOf(':') + 2) + if (addr.includes('ws://')) { + let status = EP.PORTSTATUS.OPENING + wscVPort.status = () => { return status } + console.log('starting socket to remote at', addr) + let ws = new WebSocket(addr) + // opens, + ws.onopen = (evt) => { + status = EP.PORTSTATUS.OPEN + // implement rx + ws.onmessage = (msg) => { + msg.data.arrayBuffer().then((buffer) => { + let uint = new Uint8Array(buffer) + if (LOGPHY) console.log('PHY WSC Recv') + if (LOGPHY) TS.logPacket(uint) + wscVPort.receive(uint) + }).catch((err) => { + console.error(err) + }) + } + // implement tx + wscVPort.send = (buffer) => { + if (LOGPHY) console.log('PHY WSC Send', buffer) + ws.send(buffer) + } + } + ws.onerror = (err) => { + status = EP.PORTSTATUS.CLOSED + console.log('sckt err', err) + } + ws.onclose = (evt) => { + status = EP.PORTSTATUS.CLOSED + console.log('sckt closed', evt) + } + } + } else { + console.error('remote OSAP not established', res) + } +}) + diff --git a/controller/client/clStepVM.js b/controller/client/clStepVM.js new file mode 100644 index 0000000000000000000000000000000000000000..7f2a9c6dd90d94591a2f74a8986585c3f87d5290 --- /dev/null +++ b/controller/client/clStepVM.js @@ -0,0 +1,217 @@ +/* +cclStepVM.js + +vm for closed-loop stepper motors + +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 open systems assembly protocol (OSAP) project. +Copyright is retained and must be preserved. The work is provided as is; +no warranty is provided, and users accept all liability. +*/ + +import { TS, PK, DK, AK, EP } from '../osapjs/core/ts.js' + +export default function ClStepVM(osap, route) { + + // ------------------------------------------------------ 0: DIAGNOSTICS QUERY + let diagnosticsQuery = osap.query(route, TS.endpoint(0, 0), 512) + this.getMagDiagnostics = () => { + return new Promise((resolve, reject) => { + diagnosticsQuery.pull().then((data) => { + let result = { + magHi: TS.read('boolean', data, 0, true), + magLo: TS.read('boolean', data, 1, true), + cordicOverflow: TS.read('boolean', data, 2, true), + compensationComplete: TS.read('boolean', data, 3, true), + angularGainCorrection: TS.read('uint8', data, 4, true), + cordicMagnitude: TS.read('uint16', data, 5, true) + } + resolve(result) + }).catch((err) => { + reject(err) + }) + }) + } + + // ------------------------------------------------------ 1: RUN CALIB + + let calibEP = osap.endpoint() + calibEP.addRoute(route, TS.endpoint(0, 1), 512) + calibEP.setTimeoutLength(10000) + this.runCalib = () => { + return new Promise((resolve, reject) => { + calibEP.write(new Uint8Array(0)).then(() => { + resolve() + }).catch((err) => { reject(err) }) + }) + } + + // ------------------------------------------------------ 3: POSITION QUERY + + let positionQuery = osap.query(route, TS.endpoint(0, 3), 512) + this.getPosition = () => { + return new Promise((resolve, reject) => { + positionQuery.pull().then((data) => { + let pos = TS.read('float32', data, 0, true) + resolve(pos) + }).catch((err) => { reject(err) }) + }) + } + + // ------------------------------------------------------ 4: LOOP SPEC + + let specQuery = osap.query(route, TS.endpoint(0, 4), 512) + this.getSpec = () => { + return new Promise((resolve, reject) => { + specQuery.pull().then((data) => { + let result = { + encoder: TS.read('uint16', data, 0, true), + angle: TS.read('float32', data, 2, true), + angleEstimate: TS.read('float32', data, 6, true) + } + resolve(result) + }).catch((err) => { reject(err) }) + }) + } + + /* + // ------------------------------------------------------ POS + // ok: we make an 'endpoint' that will transmit moves, + let moveEP = osap.endpoint() + // add the machine head's route to it, + moveEP.addRoute(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 1), 512) + // and set a long timeout, + // moveEP.setTimeoutLength(60000) + this.addMoveToQueue = (move) => { + // write the gram, + let wptr = 0 + let datagram = new Uint8Array(20) + // write rate + wptr += TS.write('float32', move.rate, datagram, wptr, true) + // write posns + wptr += TS.write('float32', move.position.X, datagram, wptr, true) + wptr += TS.write('float32', move.position.Y, datagram, wptr, true) + wptr += TS.write('float32', move.position.Z, datagram, wptr, true) + if (move.position.E) { + //console.log(move.position.E) + wptr += TS.write('float32', move.position.E, datagram, wptr, true) + } else { + wptr += TS.write('float32', 0, datagram, wptr, true) + } + // do the networking, + return new Promise((resolve, reject) => { + moveEP.write(datagram).then(() => { + resolve() + }).catch((err) => { + reject(err) + }) + }) + } + + // to set the current position, + let setPosEP = osap.endpoint() + setPosEP.addRoute(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 2), 512) + setPosEP.setTimeoutLength(10000) + this.setPos = (pos) => { + let wptr = 0 + let datagram = new Uint8Array(16) + wptr += TS.write('float32', pos.X, datagram, wptr, true) + wptr += TS.write('float32', pos.Y, datagram, wptr, true) + wptr += TS.write('float32', pos.Z, datagram, wptr, true) + if (pos.E) { + wptr += TS.write('float32', pos.E, datagram, wptr, true) + } else { + wptr += TS.write('float32', 0, datagram, wptr, true) + } + // ship it + return new Promise((resolve, reject) => { + setPosEP.write(datagram).then(() => { + resolve() + }).catch((err) => { reject(err) }) + }) + } + + // an a 'query' to check current position + let posQuery = osap.query(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 2), 512) + this.getPos = () => { + return new Promise((resolve, reject) => { + posQuery.pull().then((data) => { + let pos = { + X: TS.read('float32', data, 0, true), + Y: TS.read('float32', data, 4, true), + Z: TS.read('float32', data, 8, true), + E: TS.read('float32', data, 12, true) + } + resolve(pos) + }).catch((err) => { reject(err) }) + }) + } + + // another query to see if it's currently moving, + // update that endpoint so we can 'write halt' / 'write go' with a set + let motionQuery = osap.query(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 3), 512) + this.awaitMotionEnd = () => { + return new Promise((resolve, reject) => { + let check = () => { + motionQuery.pull().then((data) => { + if (data[0] > 0) { + setTimeout(check, 50) + } else { + resolve() + } + }).catch((err) => { + reject(err) + }) + } + setTimeout(check, 50) + }) + } + + // endpoint to set per-axis accelerations, + let accelEP = osap.endpoint() + accelEP.addRoute(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 5), 512) + this.setAccels = (accels) => { // float array, len 4 XYZE + let wptr = 0 + let datagram = new Uint8Array(16) + wptr += TS.write('float32', accels.X, datagram, wptr, true) + wptr += TS.write('float32', accels.Y, datagram, wptr, true) + wptr += TS.write('float32', accels.Z, datagram, wptr, true) + if (accels.E) { + wptr += TS.write('float32', accels.E, datagram, wptr, true) + } else { + wptr += TS.write('float32', 0, datagram, wptr, true) + } + return new Promise((resolve, reject) => { + accelEP.write(datagram).then(() => { + resolve() + }).catch((err) => { reject(err) }) + }) + } + + let rateEP = osap.endpoint() + rateEP.addRoute(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 6), 512) + this.setRates = (rates) => { + // in firmware we think of mm/sec, + // in gcode and up here we think in mm/minute + // so conversion happens here + let wptr = 0 + let datagram = new Uint8Array(16) + wptr += TS.write('float32', rates.X / 60, datagram, wptr, true) + wptr += TS.write('float32', rates.Y / 60, datagram, wptr, true) + wptr += TS.write('float32', rates.Z / 60, datagram, wptr, true) + if (rates.E) { + wptr += TS.write('float32', rates.E / 60, datagram, wptr, true) + } else { + wptr += TS.write('float32', 100, datagram, wptr, true) + } + return new Promise((resolve, reject) => { + rateEP.write(datagram).then(() => { + resolve() + }).catch((err) => { reject(err) }) + }) + } + */ +} \ No newline at end of file diff --git a/controller/client/clankClient.js b/controller/client/clankClient.js deleted file mode 100644 index 324f822b07b8648d2b4acb0b97ff2f92ff8a3e26..0000000000000000000000000000000000000000 --- a/controller/client/clankClient.js +++ /dev/null @@ -1,808 +0,0 @@ -/* -clank-client.js - -clank controller client side - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2020 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the open systems assembly protocol (OSAP) project. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -'use strict' - -import OSAP from '../osapjs/core/osap.js' -import { TS, PK, DK, AK, EP } from '../osapjs/core/ts.js' -import NetRunner from '../osapjs/client/netrunner/osap-render.js' - -// the clank 'virtual machine' -import ClankVM from './clankVirtualMachine.js' - -// sort of stand-alone prototype input / output system for JS... it doth not network -import { Input, Output } from '../osapjs/core/modules.js' - -import { GCodePanel } from '../osapjs/client/components/gCodePanel.js' -import { AutoPlot } from '../osapjs/client/components/autoPlot.js' -import { Button } from '../osapjs/client/interface/button.js' -import { TextInput } from '../osapjs/client/interface/textInput.js' -import { JogBox } from '../osapjs/client/components/jogBox.js' - -console.log("hello clank controller") - -// an instance of some osap capable thing (the virtual object) -// that will appear on the network, be virtually addressable -let osap = new OSAP() -osap.name = "clank client" -osap.description = "clank cz browser interface" - -// draws network, -let netrunner = new NetRunner(osap, 10, 760, false) - -// -------------------------------------------------------- THE VM - -// vm, -let vm = new ClankVM(osap) - -// -------------------------------------------------------- MOTION FEED - -// panel, -let gCodePanel = new GCodePanel(10, 10) - -// pipe moves 2 machine -window.eForward = 0 -window.eRetract = 0 -let moveInput = new Input() -gCodePanel.moveOut.attach(moveInput) -moveInput.addListener((move) => { - return new Promise((resolve, reject) => { - move.rate = move.rate // ? - /* - if(move.position.E > 0){ - window.eForward += move.position.E - } else { - window.eRetract += move.position.E - } - resolve() - return - */ - vm.addMoveToQueue(move).then(() => { - resolve() - }).catch((err) => { reject(err) }) - }) -}) - -let jogBox = new JogBox(240, 10, vm) - -// this is... kind of buggy. button state sometimes straightforwards, sometimes callback hell -let posBtn = new Button(430, 10, 344, 14, 'pos') -let posLp = false -posBtn.onClick(() => { - if (posLp) { - posLp = false - posBtn.good("stop", 500) - } else { - let poll = () => { - if (!posLp) return - vm.getPos().then((pos) => { - if (posLp) { - $(posBtn.elem).text(`X: ${pos.X.toFixed(2)}, Y: ${pos.Y.toFixed(2)}, Z: ${pos.Z.toFixed(2)}, E: ${pos.E.toFixed(2)}`) - setTimeout(poll, 50) - } - }).catch((err) => { - posLp = false - console.error(err) - posBtn.bad("err", 1000) - }) - } - posLp = true - poll() - } -}) - -let setStartBtn = new Button(360, 130, 94, 14, 'offset zero') -setStartBtn.onClick(() => { - vm.setPos({ - X: 0, - Y: 0, - Z: 121.8, - E: 0 - }).then(() => { - setStartBtn.good("ok", 500) - }).catch((err) => { - console.error(err) - setStartBtn.bad("err", 500) - }) -}) - -let gotoZeroBtn = new Button(360, 160, 94, 14, 'goto zero') -gotoZeroBtn.onClick(() => { - vm.addMoveToQueue({ - rate: 600, - position: { - X: 0, - Y: 0, - Z: 0, - E: 0, - } - }).then(() => { - gotoZeroBtn.good("ok", 500) - }).catch((err) => { - console.error(err) - gotoZeroBtn.bad("err", 500) - }) -}) - -// -------------------------------------------------------- TEMP CONTROLLER - -let tempController = (xPlace, yPlace, i, init) => { - let tvm = vm.tvm[i] - - let tempSet = new TextInput(xPlace, yPlace, 110, 20, `${init}`) - - let tempSetBtn = new Button(xPlace, yPlace + 30, 104, 14, 'set temp') - tempSetBtn.onClick(() => { - let temp = parseFloat(tempSet.value) - if (Number.isNaN(temp)) { - tempSetBtn.bad("parse err", 1000) - return - } - tvm.setExtruderTemp(temp).then(() => { - tempSetBtn.good("ok", 500) - }).catch((err) => { - console.error(err) - tempSetBtn.bad("err", 1000) - }) - }) - - let tempCoolBtn = new Button(xPlace, yPlace + 60, 104, 14, 'cooldown') - tempCoolBtn.onClick(() => { - tvm.setExtruderTemp(0).then(() => { - tempCoolBtn.good("ok", 500) - }).catch((err) => { - console.error(err) - tempCoolBtn.bad("err", 500) - }) - }) - - let tempPlot = new AutoPlot(xPlace + 120, yPlace, 420, 230) - tempPlot.setHoldCount(500) - //tempPlot.setYDomain(0, 100) - tempPlot.redraw() - - let effortPlot = new AutoPlot(xPlace + 120, yPlace + 240, 420, 150) - effortPlot.setHoldCount(500) - //effortPlot.setYDomain(-10, 10) - effortPlot.redraw() - - let tempLpBtn = new Button(xPlace, yPlace + 90, 104, 14, 'plot temp') - let tempLp = false - let tempLpCount = 0 - tempLpBtn.onClick(() => { - if (tempLp) { - tempLp = false - tempLpBtn.good("stopped", 500) - } else { - let poll = () => { - if (!tempLp) return - tvm.getExtruderTemp().then((temp) => { - //console.log(temp) - tempLpCount++ - tempPlot.pushPt([tempLpCount, temp]) - tempPlot.redraw() - return tvm.getExtruderTempOutput() - }).then((effort) => { - //console.log(effort) - effortPlot.pushPt([tempLpCount, effort]) - effortPlot.redraw() - setTimeout(poll, 200) - }).catch((err) => { - tempLp = false - console.error(err) - tempLpBtn.bad("err", 500) - }) - } - tempLp = true - poll() - } - }) - - let pVal = new TextInput(xPlace, yPlace + 120, 110, 20, '-0.1') - let iVal = new TextInput(xPlace, yPlace + 150, 110, 20, '0.0') - let dVal = new TextInput(xPlace, yPlace + 180, 110, 20, '0.1') - - let pidSetBtn = new Button(xPlace, yPlace + 210, 104, 14, 'set PID') - pidSetBtn.onClick(() => { - let p = parseFloat(pVal.value) - let i = parseFloat(iVal.value) - let d = parseFloat(dVal.value) - if (Number.isNaN(p) || Number.isNaN(i) || Number.isNaN(d)) { - pidSetBtn.bad("bad parse", 1000) - return - } - tvm.setPIDTerms([p, i, d]).then(() => { - pidSetBtn.good("ok", 500) - }).catch((err) => { - console.error(err) - pidSetBtn.bad("err", 1000) - }) - }) -} - -tempController(240, 190, 0, 220) -tempController(240, 590, 1, 60) - -// -------------------------------------------------------- MOTION SETTINGS -// todo: should bundle with jog, position query, etc ? or get on with other work - -let setRatesBtn = new Button(790, 10, 84, 24, 'set acc & max fr') -let accText = new Button(790, 50, 84, 14, 'mm/sec^2') -let xAccVal = new TextInput(790, 80, 90, 20, '300') -let yAccVal = new TextInput(790, 110, 90, 20, '300') -let zAccVal = new TextInput(790, 140, 90, 20, '50') -let eAccVal = new TextInput(790, 170, 90, 20, '900') - -let rateText = new Button(790, 200, 84, 14, 'mm/min') -let xRateVal = new TextInput(790, 230, 90, 20, '12000') -let yRateVal = new TextInput(790, 260, 90, 20, '12000') -let zRateVal = new TextInput(790, 290, 90, 20, '1000') -let eRateVal = new TextInput(790, 320, 90, 20, '60000') - -let setupMotion = () => { - // accel - let aVals = { - X: parseFloat(xAccVal.value), - Y: parseFloat(yAccVal.value), - Z: parseFloat(zAccVal.value), - E: parseFloat(eAccVal.value) - } - for (let v in aVals) { - if (Number.isNaN(aVals[v])) { console.error('bad parse for float', v); return } - } - // rates - let rVals = { - X: parseFloat(xRateVal.value), - Y: parseFloat(yRateVal.value), - Z: parseFloat(zRateVal.value), - E: parseFloat(eRateVal.value) - } - for (let v in rVals) { - if (Number.isNaN(rVals[v])) { console.error('bad parse for float', r); return } - } - // network - return new Promise((resolve, reject) => { - vm.setAccels(aVals).then(() => { - return vm.setRates(rVals) - }).then(() => { - resolve() - }).catch((err) => { reject(err) }) - }) -} - -setRatesBtn.onClick(() => { - setupMotion().then(() => { - setRatesBtn.good("ok", 500) - }).catch((err) => { - console.error(err) - setRatesBtn.bad("err", 500) - }) -}) - -// -------------------------------------------------------- MOTOR SETTINGS - -let setMotorsBtn = new Button(790, 360, 84, 14, 'motor setup') -setMotorsBtn.onClick(() => { - vm.initMotors().then(() => { - setMotorsBtn.good("ok", 500) - }).catch((err) => { - console.error(err) - setMotorsBtn.bad("err", 500) - }) -}) - -let disableMotorsBtn = new Button(790, 390, 84, 14, 'disable') -disableMotorsBtn.onClick(() => { - vm.disableMotors().then(() => { - disableMotorsBtn('ok', 500) - }).catch((err) => { - console.error(err) - disableMotorsBtn.bad("err", 500) - }) -}) - -let enableMotorsBtn = new Button(790, 420, 84, 14, 'enable') -enableMotorsBtn.onClick(() => { - vm.enableMotors().then(() => { - enableMotorsBtn('ok', 500) - }).catch((err) => { - console.error(err) - enableMotorsBtn.bad("err", 500) - }) -}) - -// -------------------------------------------------------- MACHINE INIT - -let initMachineBtn = new Button(470, 130, 84, 44, 'init vm') -initMachineBtn.onClick(() => { - setupMotion().then(() => { - return vm.initMotors() - }).then(() => { - initMachineBtn.good("ok", 500) - }).catch((err) => { - console.error(err) - initMachineBtn.bad("err", 500) - }) -}) - -// -------------------------------------------------------- TOOLCHANGER - -let tcBtn = new Button(430, 40, 94, 14, 'tc') -tcBtn.onClick(() => { - if ($(tcBtn.elem).text() == 'close tc') { - vm.closeTC().then(() => { - tcBtn.good('ok', 500) - setTimeout(() => { - $(tcBtn.elem).text('open tc') - }, 500) - }).catch((err) => { - console.error(err) - tcBtn.bad('err', 500) - setTimeout(() => { - $(tcBtn.elem).text('close tc') - }, 500) - }) - } else { - vm.openTC().then(() => { - tcBtn.good('ok', 500) - setTimeout(() => { - $(tcBtn.elem).text('close tc') - }, 500) - }).catch((err) => { - console.error(err) - tcBtn.bad('err', 500) - setTimeout(() => { - $(tcBtn.elem).text('open tc') - }, 500) - }) - } -}) -$(tcBtn.elem).text('close tc') - -let dropBtn = new Button(430, 70, 94, 14, 'drop T0') -dropBtn.onClick(() => { - vm.dropTool(0).then(() => { - dropBtn.good("ok", 500) - }).catch((err) => { - console.error(err) - dropBtn.bad("err", 500) - }) -}) - -let pickupBtn = new Button(430, 100, 94, 14, 'pickup T0') -pickupBtn.onClick(() => { - vm.pickTool(0).then(() => { - pickupBtn.good("ok", 500) - }).catch((err) => { - console.error(err) - pickupBtn.bad("err", 500) - }) -}) - -// -------------------------------------------------------- ENDPOINT TEST - -let ep = osap.endpoint() -ep.addRoute(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 0), 512) - -let epTestBtn = new Button(240, 130, 104, 14, 'ep test') -epTestBtn.onClick(() => { - testRun(10).then((res) => { - console.warn(res) - epTestBtn.good(`avg ${res}`, 500) - }).catch((err) => { - console.log('err') - }) - /* - let datagram = Uint8Array.from([12, 24, 36]) - console.warn('begin') - let start = performance.now() - ep.write(datagram).then(() => { - console.log(performance.now() - start) - console.warn('end') - epTestBtn.good("resolves") - console.warn('RESOLVE EP WRITE') - }).catch((err) => { - epTestBtn.bad("rejects") - console.error('EP REJECT') - console.error(err) - }) - */ -}) - -let testRun = async (count) => { - let datagram = Uint8Array.from([12, 24, 36]) - let start = performance.now() - let avg = 0 - try { - for (let i = 0; i < count; i++) { - console.log(`test ${i}`) - await ep.write(datagram) - let now = performance.now() - avg += now - start - start = now - } - } catch (err) { - throw new Error(err) - } - return avg / count -} - -let posns = osap.query(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 0), 512) - -let qTestBtn = new Button(240, 160, 104, 14, 'query test') -qTestBtn.onClick(() => { - posns.pull().then((data) => { - console.warn("query passed", data) - qTestBtn.good('ok', 200) - }).catch((err) => { - console.warn("query fails") - console.error(err) - qTestBtn.bad('fail', 200) - }) -}) - -/* - -// connect awaitMotionEnd() to gcode parser - -let motionWaitIn = new Input() -gCodePanel.awaitMotionEnd.attach(motionWaitIn) -motionWaitIn.addListener(async () => { - return new Promise((resolve, reject) => { - vm.awaitMotionEnd().then(() => { - resolve() - }).catch((err) => { - console.error(err) - reject(err) - }) - }) -}) - -// pipe spindle 2 machine -let spindleIn = new Input() -gCodePanel.spindleOut.attach(spindleIn) -spindleIn.addListener(async (rpm) => { - return new Promise((resolve, reject) => { - vm.setRPM(rpm).then(() => { - setTimeout(resolve, 500) - }).catch((err) => { - console.error(err) - reject(err) - }) - }) -}) - -let vm = new VirtualMachine(osap) - -// -------------------------------------------------------- HOME, JOG, ZERO - -// pardon the mess, these are redefined for the jog box... -// could properly wrap all btn action up over there, sometime! - -let BTN_RED = 'rgb(242, 201, 201)' -let BTN_GRN = 'rgb(201, 242, 201)' -let BTN_YLW = 'rgb(240, 240, 180)' -let BTN_GREY = 'rgb(242, 242, 242)' -let BTN_HANGTIME = 1000 -let BTN_ERRTIME = 2000 - -// go home -let homeBtn = Button(240, 10, 54, 14, 'home') -$(homeBtn).on('click', (evt) => { - vm.home().then(() => { - $(homeBtn).text('ok') - setTimeout(() => { - $(homeBtn).text('home') - }, 500) - }).catch((err) => { - console.error(err) - $(homeBtn).text('err!') - setTimeout(() => { - $(homeBtn).text('home') - }, 500) - }) - $(homeBtn).text('homing...') -}) - -// query queue length -let qqlBtn = Button(310, 10, 54, 14, 'queue ?') -$(qqlBtn).on('click', (evt) => { - if (qqlBtn.clicked) return - qqlBtn.clicked = true - vm.queryQueueLength().then((len) => { - $(qqlBtn).text(`${len}`).css('background-color', BTN_GRN) - setTimeout(() => { $(qqlBtn).text(`queue ?`).css('background-color', BTN_GREY); qqlBtn.clicked = false }, BTN_HANGTIME) - }).catch((err) => { - console.error(err) - $(qqlBtn).text('error').css('background-color', BTN_RED) - setTimeout(() => { $(qqlBtn).text(`queue ?`).css('background-color', BTN_GREY); qqlBtn.clicked = false }, BTN_ERRTIME) - }) - $(qqlBtn).text('...').css('background-color', BTN_YLW) -}) - -// query motion status -let mqBtn = Button(380, 10, 54, 14, 'moving ?') -$(mqBtn).on('click', (evt) => { - if (mqBtn.clicked) return - mqBtn.clicked = true - vm.queryMotionStatus().then((state) => { - $(mqBtn).text(`${state}`).css('background-color', BTN_GRN) - setTimeout(() => { $(mqBtn).text(`moving ?`).css('background-color', BTN_GREY); mqBtn.clicked = false }, BTN_HANGTIME) - }).catch((err) => { - console.error(err) - $(mqBtn).text('error').css('background-color', BTN_RED) - setTimeout(() => { $(mqBtn).text(`moving ?`).css('background-color', BTN_GREY); mqBtn.clicked = false }, BTN_ERRTIME) - }) - $(mqBtn).text('...').css('background-color', BTN_YLW) -}) - -// query position -let pqBtn = Button(450, 10, 204, 14, 'pos ?') -$(pqBtn).on('click', (evt) => { - if (pqBtn.clicked) return - pqBtn.clicked = true - vm.queryPosition().then((pos) => { - $(pqBtn).text(`${pos.X.toFixed(3)}, ${pos.Y.toFixed(3)}, ${pos.Z.toFixed(3)}`).css('background-color', BTN_GRN) - setTimeout(() => { $(pqBtn).text(`pos ?`).css('background-color', BTN_GREY); pqBtn.clicked = false }, BTN_HANGTIME) - }).catch((err) => { - console.error(err) - $(pqBtn).text('error').css('background-color', BTN_RED) - setTimeout(() => { $(pqBtn).text(`pos ?`).css('background-color', BTN_GREY); pqBtn.clicked = false }, BTN_ERRTIME) - }) - $(pqBtn).text('...').css('background-color', BTN_YLW) -}) - -let spInput = TextInput(450, 40, 210, 20, '0.000, 0.000, 0.000') -let lpBtn = Button(240, 40, 84, 14, 'get pos') -$(lpBtn).on('click', (ev) => { - if(lpBtn.clicked) return - lpBtn.clicked = true - // git posn from machine - let pos = vm.queryPosition().then((pos) => { - // write it to input value, to modify... - spInput.value = `${pos.X.toFixed(3)}, ${pos.Y.toFixed(3)}, ${pos.Z.toFixed(3)}` - $(lpBtn).text(`ok ->`).css('background-color', BTN_GRN) - setTimeout(() => { $(lpBtn).text(`get pos`).css('background-color', BTN_GREY); lpBtn.clicked = false }, BTN_HANGTIME) - }).catch((err) => { - console.error(err) - $(lpBtn).text('error').css('background-color', BTN_RED) - setTimeout(() => { $(lpBtn).text(`set pos`).css('background-color', BTN_GREY); lpBtn.clicked = false }, BTN_ERRTIME) - }) - $(lpBtn).text('...').css('background-color', BTN_YLW) -}) - -let spBtn = Button(340, 40, 94, 14, 'set pos') -$(spBtn).on('click', (evt) => { - if (spBtn.clicked) return - spBtn.clicked = true - // get from input, arr - let psns = spInput.value.split(',') - let badParse = false - for (let p in psns) { - psns[p] = parseFloat(psns[p]) - if (Number.isNaN(psns[p])) { - badParse = true - } - } - if (psns.length != 3) badParse = true - if (badParse) { - $(spBtn).text('bad set-target parse') - setTimeout(() => { - $(spBtn).text(`set pos`).css('background-color', BTN_GREY) - spBtn.clicked = false - }, BTN_HANGTIME) - return - } - vm.setPosition({ X: psns[0], Y: psns[1], Z: psns[2] }).then(() => { - // this is ok, so - return vm.queryPosition() - }).then((pos) => { - $(spBtn).text(`ok ->`).css('background-color', BTN_GRN) - setTimeout(() => { $(spBtn).text(`set pos`).css('background-color', BTN_GREY); spBtn.clicked = false }, BTN_HANGTIME) - }).catch((err) => { - console.error(err) - $(spBtn).text('error').css('background-color', BTN_RED) - setTimeout(() => { $(spBtn).text(`set pos`).css('background-color', BTN_GREY); spBtn.clicked = false }, BTN_ERRTIME) - }) - $(spBtn).text('...').css('background-color', BTN_YLW) -}) - -// remote set currents -let scBtn = Button(240, 70, 194, 14, 'set currents') -let scInput = TextInput(450, 70, 210, 20, '0.2, 0.2, 0.2') -$(scBtn).on('click', (evt) => { - if (scBtn.clicked) return - scBtn.clicked = true - // get from input, arr - let currents = scInput.value.split(',') - let badParse = false - for (let p in currents) { - currents[p] = parseFloat(currents[p]) - if (Number.isNaN(currents[p])) { - badParse = true - } - } - if (currents.length != 3) badParse = true - if (badParse) { - $(scBtn).text('bad set-target parse').css('background-color', BTN_RED) - setTimeout(() => { - $(scBtn).text(`set currents`).css('background-color', BTN_GREY) - scBtn.clicked = false - }, BTN_HANGTIME) - return - } - vm.setCurrents({ X: currents[0], Y: currents[1], Z: currents[2] }).then(() => { - $(scBtn).text(`ok`).css('background-color', BTN_GRN) - setTimeout(() => { $(scBtn).text(`set currents`).css('background-color', BTN_GREY); scBtn.clicked = false }, BTN_HANGTIME) - }).catch((err) => { - console.error(err) - $(scBtn).text('error').css('background-color', BTN_RED) - setTimeout(() => { $(scBtn).text(`set currents`).css('background-color', BTN_GREY); scBtn.clicked = false }, BTN_ERRTIME) - }) - $(scBtn).text('...').css('background-color', BTN_YLW) -}) - -// remote set tool -let toolGripped = false -let tgBtn = Button(240, 100, 194, 14, 'grip tool') -$(tgBtn).on('click', (evt) => { - if(tgBtn.clicked) return - tgBtn.clicked = true - $(tgBtn).text('...').css('background-color', BTN_YLW) - if(toolGripped){ - vm.releaseTool().then(() => { - toolGripped = false - $(tgBtn).text('grip tool').css('background-color', BTN_GREY); tgBtn.clicked = false - }).catch((err) => { - console.error(err) - $(tgBtn).text('error').css('background-color', BTN_RED) - }) - } else { - vm.gripTool().then(() => { - toolGripped = true - $(tgBtn).text('release tool').css('background-color', BTN_GREY); tgBtn.clicked = false - }).catch((err) => { - console.error(err) - $(tgBtn).text('error').css('background-color', BTN_RED) - }) - } -}) - -let calBtn = Button(450, 100, 94, 14, 'calibr8') -$(calBtn).on('click', (evt) => { - if(calBtn.clicked) return - calBtn.clicked = true - $(calBtn).text('...').css('background-color', BTN_YLW) - vm.runCalibration().then(() => { - $(calBtn).text('ok').css('background-color', BTN_GRN) - setTimeout(() => { $(calBtn).text(`calibr8`).css('background-color', BTN_GREY); calBtn.clicked = false }, BTN_HANGTIME) - }).catch((err) => { - console.error(err) - $(calBtn).text('err').css('background-color', BTN_RED) - setTimeout(() => { $(calBtn).text(`calibr8`).css('background-color', BTN_GREY); calBtn.clicked = false }, BTN_ERRTIME) - }) -}) - -let unlockBtn = Button(560, 100, 94, 14, 'release') -$(unlockBtn).on('click', (evt) => { - if(unlockBtn.clicked) return - unlockBtn.clicked = true - $(unlockBtn).text('...').css('background-color', BTN_YLW) - vm.unlockTool().then(() => { - $(unlockBtn).text('ok').css('background-color', BTN_GRN) - setTimeout(() => { $(unlockBtn).text('release').css('background-color', BTN_GREY); unlockBtn.clicked = false }, BTN_HANGTIME) - }).catch((err) => { - console.error(err) - $(unlockBtn).text('error').css('background-color', BTN_RED) - setTimeout(() => { $(unlockBtn).text('release').css('background-color', BTN_GREY); unlockBtn.clicked = false }, BTN_ERRTIME) - }) -}) - -let pickupBtn = Button(240, 130, 84, 14, 'pickup') -$(pickupBtn).on('click', (evt) => { - if(pickupBtn.clicked) return - pickupBtn.clicked = true - $(pickupBtn).text('...').css('background-color', BTN_YLW) - vm.pickupTool(225, 2).then(() => { - $(pickupBtn).text('ok').css('background-color', BTN_GRN) - setTimeout(() => { $(pickupBtn).text('pickup').css('background-color', BTN_GREY); pickupBtn.clicked = false }, BTN_HANGTIME) - }).catch((err) => { - console.error(err) - $(pickupBtn).text('error').css('background-color', BTN_RED) - setTimeout(() => { $(pickupBtn).text('pickup').css('background-color', BTN_GREY); pickupBtn.clicked = false }, BTN_ERRTIME) - }) -}) - -let dropBtn = Button(340, 130, 94, 14, 'drop') -$(dropBtn).on('click', (evt) => { - if(dropBtn.clicked) return - dropBtn.clicked = true - $(dropBtn).text('...').css('background-color', BTN_YLW) - vm.dropTool(225, 2).then(() => { - $(dropBtn).text('ok').css('background-color', BTN_GRN) - setTimeout(() => { $(dropBtn).text('drop').css('background-color', BTN_GREY); dropBtn.clicked = false }, BTN_HANGTIME) - }).catch((err) => { - console.error(err) - $(dropBtn).text('error').css('background-color', BTN_RED) - setTimeout(() => { $(dropBtn).text('drop').css('background-color', BTN_GREY); dropBtn.clicked = false }, BTN_ERRTIME) - }) -}) - -let jogBox = new JogBox(670, 10, vm) - -// render -let pad = new Pad(240, 160, 610, 610) - -*/ - -// -------------------------------------------------------- STARTUP LOCAL - -let wscVPort = osap.vPort() -wscVPort.name = 'websocket client' -wscVPort.maxSegLength = 1024 - -let LOGPHY = false - -// to test these systems, the client (us) will kickstart a new process -// on the server, and try to establish connection to it. -console.log("making client-to-server request to start remote process,") -console.log("and connecting to it w/ new websocket") -// ok, let's ask to kick a process on the server, -// in response, we'll get it's IP and Port, -// then we can start a websocket client to connect there, -// automated remote-proc. w/ vPort & wss medium, -// for args, do '/processName.js?args=arg1,arg2' - -jQuery.get('/startLocal/osapl-usb-bridge.js', (res) => { - if (res.includes('OSAP-wss-addr:')) { - let addr = res.substring(res.indexOf(':') + 2) - if (addr.includes('ws://')) { - let status = EP.PORTSTATUS.OPENING - wscVPort.status = () => { return status } - console.log('starting socket to remote at', addr) - let ws = new WebSocket(addr) - // opens, - ws.onopen = (evt) => { - status = EP.PORTSTATUS.OPEN - // implement rx - ws.onmessage = (msg) => { - msg.data.arrayBuffer().then((buffer) => { - let uint = new Uint8Array(buffer) - if (LOGPHY) console.log('PHY WSC Recv') - if (LOGPHY) TS.logPacket(uint) - wscVPort.receive(uint) - }).catch((err) => { - console.error(err) - }) - } - // implement tx - wscVPort.send = (buffer) => { - if (LOGPHY) console.log('PHY WSC Send', buffer) - ws.send(buffer) - } - } - ws.onerror = (err) => { - status = EP.PORTSTATUS.CLOSED - console.log('sckt err', err) - } - ws.onclose = (evt) => { - status = EP.PORTSTATUS.CLOSED - console.log('sckt closed', evt) - } - } - } else { - console.error('remote OSAP not established', res) - } -}) - diff --git a/controller/client/clankVirtualMachine.js b/controller/client/clankVirtualMachine.js deleted file mode 100644 index 45c0328a9aec792bfc670f883b6643836d05ac58..0000000000000000000000000000000000000000 --- a/controller/client/clankVirtualMachine.js +++ /dev/null @@ -1,430 +0,0 @@ -/* -clankVirtualMachine.js - -vm for Clank-CZ - -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 open systems assembly protocol (OSAP) project. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -import { TS, PK, DK, AK, EP } from '../osapjs/core/ts.js' -import TempVM from './tempVirtualMachine.js' -import MotorVM from './motorVirtualMachine.js' - -/* bus ID (osap maps +1) -X: 0 -YL: 1 -YR: 2, term -Z: 3 -TCS: 4 -E: 5 -HE: 6 -LC: 7 -BED: 8 -*/ - -export default function ClankVM(osap, route) { - - // ------------------------------------------------------ MOTION - // ok: we make an 'endpoint' that will transmit moves, - let moveEP = osap.endpoint() - // add the machine head's route to it, - moveEP.addRoute(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 1), 512) - // and set a long timeout, - moveEP.setTimeoutLength(60000) - // move like: { position: {X: num, Y: num, Z: num}, rate: num } - this.addMoveToQueue = (move) => { - // write the gram, - let wptr = 0 - let datagram = new Uint8Array(20) - // write rate - wptr += TS.write('float32', move.rate, datagram, wptr, true) - // write posns - wptr += TS.write('float32', move.position.X, datagram, wptr, true) - wptr += TS.write('float32', move.position.Y, datagram, wptr, true) - wptr += TS.write('float32', move.position.Z, datagram, wptr, true) - if (move.position.E) { - //console.log(move.position.E) - wptr += TS.write('float32', move.position.E, datagram, wptr, true) - } else { - wptr += TS.write('float32', 0, datagram, wptr, true) - } - // do the networking, - return new Promise((resolve, reject) => { - moveEP.write(datagram).then(() => { - resolve() - }).catch((err) => { - reject(err) - }) - }) - } - - // to set the current position, - let setPosEP = osap.endpoint() - setPosEP.addRoute(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 2), 512) - setPosEP.setTimeoutLength(10000) - this.setPos = (pos) => { - let wptr = 0 - let datagram = new Uint8Array(16) - wptr += TS.write('float32', pos.X, datagram, wptr, true) - wptr += TS.write('float32', pos.Y, datagram, wptr, true) - wptr += TS.write('float32', pos.Z, datagram, wptr, true) - if (pos.E) { - wptr += TS.write('float32', pos.E, datagram, wptr, true) - } else { - wptr += TS.write('float32', 0, datagram, wptr, true) - } - // ship it - return new Promise((resolve, reject) => { - setPosEP.write(datagram).then(() => { - resolve() - }).catch((err) => { reject(err) }) - }) - } - - // an a 'query' to check current position - let posQuery = osap.query(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 2), 512) - this.getPos = () => { - return new Promise((resolve, reject) => { - posQuery.pull().then((data) => { - let pos = { - X: TS.read('float32', data, 0, true), - Y: TS.read('float32', data, 4, true), - Z: TS.read('float32', data, 8, true), - E: TS.read('float32', data, 12, true) - } - resolve(pos) - }).catch((err) => { reject(err) }) - }) - } - - // another query to see if it's currently moving, - // update that endpoint so we can 'write halt' / 'write go' with a set - let motionQuery = osap.query(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 3), 512) - this.awaitMotionEnd = () => { - return new Promise((resolve, reject) => { - let check = () => { - motionQuery.pull().then((data) => { - if (data[0] > 0) { - setTimeout(check, 50) - } else { - resolve() - } - }).catch((err) => { - reject(err) - }) - } - setTimeout(check, 50) - }) - } - - // an endpoint to write 'wait time' on the remote, - let waitTimeEP = osap.endpoint() - waitTimeEP.addRoute(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 4), 512) - this.setWaitTime = (ms) => { - return new Promise((resolve, reject) => { - let datagram = new Uint8Array(4) - TS.write('uint32', ms, datagram, 0, true) - waitTimeEP.write(datagram).then(() => { - resolve() - }).catch((err) => { reject(err) }) - }) - } - - // endpoint to set per-axis accelerations, - let accelEP = osap.endpoint() - accelEP.addRoute(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 5), 512) - this.setAccels = (accels) => { // float array, len 4 XYZE - let wptr = 0 - let datagram = new Uint8Array(16) - wptr += TS.write('float32', accels.X, datagram, wptr, true) - wptr += TS.write('float32', accels.Y, datagram, wptr, true) - wptr += TS.write('float32', accels.Z, datagram, wptr, true) - if (accels.E) { - wptr += TS.write('float32', accels.E, datagram, wptr, true) - } else { - wptr += TS.write('float32', 0, datagram, wptr, true) - } - return new Promise((resolve, reject) => { - accelEP.write(datagram).then(() => { - resolve() - }).catch((err) => { reject(err) }) - }) - } - - let rateEP = osap.endpoint() - rateEP.addRoute(TS.route().portf(0).portf(1).end(), TS.endpoint(0, 6), 512) - this.setRates = (rates) => { - // in firmware we think of mm/sec, - // in gcode and up here we think in mm/minute - // so conversion happens here - let wptr = 0 - let datagram = new Uint8Array(16) - wptr += TS.write('float32', rates.X / 60, datagram, wptr, true) - wptr += TS.write('float32', rates.Y / 60, datagram, wptr, true) - wptr += TS.write('float32', rates.Z / 60, datagram, wptr, true) - if (rates.E) { - wptr += TS.write('float32', rates.E / 60, datagram, wptr, true) - } else { - wptr += TS.write('float32', 100, datagram, wptr, true) - } - return new Promise((resolve, reject) => { - rateEP.write(datagram).then(() => { - resolve() - }).catch((err) => { reject(err) }) - }) - } - - // ------------------------------------------------------ MOTORS - - // clank cz: - // AXIS SPU INVERT - // X: 320 false - // YL: 320 true - // YR: 320 false - // Z: 924.4r false - // E: 550 true - // per bondtech, for BMG on 16 microsteps, do 415: we are 32 microsteps - // https://www.bondtech.se/en/customer-service/faq/ - // however, this is measured & calibrated: 830 was extruding 75mm for a 50mm request - /* bus ID (osap maps +1) - X: 0 - YL: 1 - YR: 2, term - Z: 3 - TCS: 4 - E: 5 - HE: 6 - LC: 7 - BED: 8 - */ - - this.motors = { - X: new MotorVM(osap, TS.route().portf(0).portf(1).busf(1, 1).end()), - YL: new MotorVM(osap, TS.route().portf(0).portf(1).busf(1, 2).end()), - YR: new MotorVM(osap, TS.route().portf(0).portf(1).busf(1, 3).end()), - Z: new MotorVM(osap, TS.route().portf(0).portf(1).busf(1, 4).end()), - E: new MotorVM(osap, TS.route().portf(0).portf(1).busf(1, 6).end()), - } - - let motorCurrents = [0.5, 0.5, 0.5, 0.5, 0.5] - this.setMotorCurrents = async () => { - try { - await this.motors.X.setCScale(motorCurrents[0]) - await this.motors.YL.setCScale(motorCurrents[1]) - await this.motors.YR.setCScale(motorCurrents[2]) - await this.motors.Z.setCScale(motorCurrents[3]) - //await this.motors.E.setCScale(motorCurrents[4]) - } catch (err) { - console.error('bad motor current set') - throw err - } - } - - // alias... - this.enableMotors = this.setMotorCurrents - - this.disableMotors = async () => { - try { - await this.motors.X.setCScale(0) - await this.motors.YL.setCScale(0) - await this.motors.YR.setCScale(0) - await this.motors.Z.setCScale(0) - await this.motors.E.setCScale(0) - } catch (err) { - console.error('bad motor disable set') - throw err - } - } - - this.initMotors = async () => { - // so, really, for these & the disable / enable / set current - // could do them all parallel: like this halts if i.e. YL fails, - // where it might just be that motor with an error... that'd be catching / continuing, accumulating - // errors, and reporting them in a group - try { - await this.motors.X.setAxisPick(0) - await this.motors.X.setAxisInversion(false) - await this.motors.X.setSPU(320) - } catch (err) { - console.error('bad x motor init') - throw err - } - try { - await this.motors.YL.setAxisPick(1) - await this.motors.YL.setAxisInversion(true) - await this.motors.YL.setSPU(320) - } catch (err) { - console.error('bad yl motor init') - throw err - } - try { - await this.motors.YR.setAxisPick(1) - await this.motors.YR.setAxisInversion(false) - await this.motors.YR.setSPU(320) - } catch (err) { - console.error('bad yr motor init') - throw err - } - try { - await this.motors.Z.setAxisPick(2) - await this.motors.Z.setAxisInversion(false) - await this.motors.Z.setSPU(924.444444) - } catch (err) { - console.error('bad z motor init') - throw err - } - /* - try { - await this.motors.E.setAxisPick(3) - await this.motors.E.setAxisInversion(true) - await this.motors.E.setSPU(550) - } catch (err) { - console.error('bad e motor init') - throw err - } - */ - await this.setMotorCurrents() - } - - // ------------------------------------------------------ TOOLCHANGER - - let tcServoEP = osap.endpoint() - tcServoEP.addRoute(TS.route().portf(0).portf(1).busf(1, 5).end(), TS.endpoint(0, 0), 512) - - this.setTCServo = (micros) => { - let wptr = 0 - let datagram = new Uint8Array(4) - // write micros - wptr += TS.write('uint32', micros, datagram, wptr, true) - // do the shipment - return new Promise((resolve, reject) => { - tcServoEP.write(datagram).then(() => { - console.warn('tc set', micros) - resolve() - }).catch((err) => { - reject(err) - }) - }) - } - - this.openTC = () => { - return this.setTCServo(2000) - } - - this.closeTC = () => { - return this.setTCServo(875) - } - - // ------------------------------------------------------ TOOL CHANGING - - // tool localization for put-down & pickup, tool statefulness, - // from back left 0,0 - // put-down HE at (23.8, -177) -> (23.8, -222.6) -> release -> (-17.8, -208.6) clear -> (-17.8, -183) - // { position: {X: num, Y: num, Z: num}, rate: num } - - let delay = (ms) => { - return new Promise((resolve, reject) => { - setTimeout(() => { resolve() }, ms) - }) - } - - this.delta = async (move, rate) => { - try { - if (!rate) rate = 6000 - await this.setWaitTime(1) - await delay(5) - await this.awaitMotionEnd() - let cp = await this.getPos() - console.log('current', cp) - await this.addMoveToQueue({ - position: { X: cp.X + move[0], Y: cp.Y + move[1], Z: cp.Z + move[2] }, - rate: rate - }) - await delay(5) - await this.awaitMotionEnd() - await this.setWaitTime(100) - } catch (err) { - console.error('arising during delta') - throw err - } - } - - this.goto = async (pos, rate) => { - try { - if (!rate) rate = 6000 - // set remote queue-wait-time - await this.setWaitTime(1) - await delay(5) - // wait for the stop - await this.awaitMotionEnd() - await this.addMoveToQueue({ - position: { X: pos[0], Y: pos[1], Z: pos[2], E: 0 }, - rate: rate - }) - await delay(5) - await this.awaitMotionEnd() - await this.setWaitTime(100) - } catch (err) { - console.error('during goto') - throw err - } - } - - let tools = [{ - pickX: 16.8, - pickY: -177, - plunge: -45.6 - }] - - this.dropTool = async (num) => { - try { - await this.awaitMotionEnd() - await this.closeTC() - let cp = await this.getPos() - await this.goto([tools[num].pickX, tools[num].pickY, cp.Z]) - console.warn('done setup') - await this.delta([0, tools[num].plunge, 0]) - await this.openTC() - await delay(250) - console.warn('tc open') - await this.delta([-6, 10, 0]) - await this.delta([0, 50, 0]) - await this.goto([tools[num].pickX, tools[num].pickY, cp.Z]) - } catch (err) { - console.error(`at T${num} drop`) - throw err - } - } - - this.pickTool = async (num) => { - try { - await this.awaitMotionEnd() - await this.openTC() - let cp = await this.getPos() - await this.goto([tools[num].pickX, tools[num].pickY, cp.Z]) - await this.delta([-6, 0, 0]) - await this.delta([0, tools[num].plunge + 10, 0]) - await this.delta([6, -10, 0]) - await this.closeTC() - await delay(250) - await this.delta([0, -tools[num].plunge, 0]) - await delay(250) - } catch (err) { - console.error(`at T${num} pick`) - throw err - } - } - - // ------------------------------------------------------ HEATER JUNK - - this.tvm = [] - this.tvm[0] = new TempVM(osap, TS.route().portf(0).portf(1).busf(1, 7).end()) - this.tvm[1] = new TempVM(osap, TS.route().portf(0).portf(1).busf(1, 9).end()) - -} \ No newline at end of file diff --git a/controller/client/index.html b/controller/client/index.html index f5d7dac9a06c731aa84993f5722128c1b96c97fc..b910ebae6af665a3d3fc99dbd4fbbf08becc4cca 100644 --- a/controller/client/index.html +++ b/controller/client/index.html @@ -2,7 +2,7 @@ <html> <head> - <title>clank-tool</title> + <title>cl-step-tuner</title> <!-- these three disable caching --> <meta http-equiv="Cache-Control" content="no-cache, no-store, must-revalidate" /> <meta http-equiv="Pragma" content="no-cache" /> @@ -14,7 +14,7 @@ <script src="../osapjs/client/libs/jquery.min.js"></script> <script src="../osapjs/client/libs/math.js" type="text/javascript"></script> <script src="../osapjs/client/libs/d3.js"></script> - <script type="module" src="clankClient.js"></script> + <script type="module" src="clStepClient.js"></script> <div id="wrapper"> <!-- bootloop puts first view inside of this div --> diff --git a/controller/osapjs b/controller/osapjs index de18301b0a0839f929c326058d459aedc21f7be0..81cdb84bf268612a79185f7a0eb71013ad8938d1 160000 --- a/controller/osapjs +++ b/controller/osapjs @@ -1 +1 @@ -Subproject commit de18301b0a0839f929c326058d459aedc21f7be0 +Subproject commit 81cdb84bf268612a79185f7a0eb71013ad8938d1 diff --git a/firmware/cl-step-controller/src/config.h b/firmware/cl-step-controller/src/config.h new file mode 100644 index 0000000000000000000000000000000000000000..6682b6da865746d8129722aa3889ba286828be40 --- /dev/null +++ b/firmware/cl-step-controller/src/config.h @@ -0,0 +1,7 @@ +#ifndef CONFIG_H_ +#define CONFIG_H_ + +//#define UCBUS_IS_HEAD +//#define UCBUS_IS_DROP + +#endif \ No newline at end of file diff --git a/firmware/cl-step-controller/src/drivers/dacs.h b/firmware/cl-step-controller/src/drivers/dacs.h index 6d095390582c08027f0bd3777136fed0e05edbf4..15cc2eadbca5c5e918b69bc7679669d7fc71d7ed 100644 --- a/firmware/cl-step-controller/src/drivers/dacs.h +++ b/firmware/cl-step-controller/src/drivers/dacs.h @@ -18,7 +18,7 @@ is; no warranty is provided, and users accept all liability. #include <arduino.h> #include "indicators.h" -#include "utils/syserror.h" +#include "../osape/utils/syserror.h" // scrape https://github.com/adafruit/ArduinoCore-samd/blob/master/cores/arduino/wiring_analog.c // scrape https://github.com/adafruit/ArduinoCore-samd/blob/master/cores/arduino/startup.c (clock) diff --git a/firmware/cl-step-controller/src/drivers/dip_ucbus_config.cpp b/firmware/cl-step-controller/src/drivers/dip_ucbus_config.cpp deleted file mode 100644 index e0316b389b72c91a640a75883c4f426b9e5c07cf..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/drivers/dip_ucbus_config.cpp +++ /dev/null @@ -1,55 +0,0 @@ -// DIPs - -#include "dip_ucbus_config.h" - -void dip_init(void){ - // set direction in, - DIP_PORT.DIRCLR.reg = D_BM(D0_PIN) | D_BM(D1_PIN) | D_BM(D2_PIN) | D_BM(D3_PIN) | D_BM(D4_PIN) | D_BM(D5_PIN) | D_BM(D6_PIN) | D_BM(D7_PIN); - // enable in, - DIP_PORT.PINCFG[D0_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D1_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D2_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D3_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D4_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D5_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D6_PIN].bit.INEN = 1; - DIP_PORT.PINCFG[D7_PIN].bit.INEN = 1; - // enable pull, - DIP_PORT.PINCFG[D0_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D1_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D2_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D3_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D4_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D5_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D6_PIN].bit.PULLEN = 1; - DIP_PORT.PINCFG[D7_PIN].bit.PULLEN = 1; - // 'pull' references the value set in the 'out' register, so to pulldown: - DIP_PORT.OUTCLR.reg = D_BM(D0_PIN) | D_BM(D1_PIN) | D_BM(D2_PIN) | D_BM(D3_PIN) | D_BM(D4_PIN) | D_BM(D5_PIN) | D_BM(D6_PIN) | D_BM(D7_PIN); -} - -uint8_t dip_read_lower_five(void){ - uint32_t bits[5] = {0,0,0,0,0}; - if(DIP_PORT.IN.reg & D_BM(D7_PIN)) { bits[0] = 1; } - if(DIP_PORT.IN.reg & D_BM(D6_PIN)) { bits[1] = 1; } - if(DIP_PORT.IN.reg & D_BM(D5_PIN)) { bits[2] = 1; } - if(DIP_PORT.IN.reg & D_BM(D4_PIN)) { bits[3] = 1; } - if(DIP_PORT.IN.reg & D_BM(D3_PIN)) { bits[4] = 1; } - /* - bits[0] = (DIP_PORT.IN.reg & D_BM(D7_PIN)) >> D7_PIN; - bits[1] = (DIP_PORT.IN.reg & D_BM(D6_PIN)) >> D6_PIN; - bits[2] = (DIP_PORT.IN.reg & D_BM(D5_PIN)) >> D5_PIN; - bits[3] = (DIP_PORT.IN.reg & D_BM(D4_PIN)) >> D4_PIN; - bits[4] = (DIP_PORT.IN.reg & D_BM(D3_PIN)) >> D3_PIN; - */ - uint32_t word = 0; - word = word | (bits[4] << 4) | (bits[3] << 3) | (bits[2] << 2) | (bits[1] << 1) | (bits[0] << 0); - return (uint8_t)word; -} - -boolean dip_read_pin_0(void){ - return DIP_PORT.IN.reg & D_BM(D0_PIN); -} - -boolean dip_read_pin_1(void){ - return DIP_PORT.IN.reg & D_BM(D1_PIN); -} \ No newline at end of file diff --git a/firmware/cl-step-controller/src/drivers/dip_ucbus_config.h b/firmware/cl-step-controller/src/drivers/dip_ucbus_config.h deleted file mode 100644 index 44eaa00d1fb1fd0f30118308ba436cd136cc344a..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/drivers/dip_ucbus_config.h +++ /dev/null @@ -1,24 +0,0 @@ -// DIP switch HAL macros -// pardon the mis-labeling: on board, and in the schem, these are 1-8, -// here they will be 0-7 - -// note: these are 'on' hi by default, from the factory. -// to set low, need to turn the internal pulldown on - -#include <Arduino.h> - -#define D0_PIN 5 -#define D1_PIN 4 -#define D2_PIN 3 -#define D3_PIN 2 -#define D4_PIN 1 -#define D5_PIN 0 -#define D6_PIN 31 -#define D7_PIN 30 -#define DIP_PORT PORT->Group[1] -#define D_BM(val) ((uint32_t)(1 << val)) - -void dip_init(void); -uint8_t dip_read_lower_five(void); -boolean dip_read_pin_0(void); // bus-head (hi) or bus-drop (lo) -boolean dip_read_pin_1(void); // if bus-drop, te-enable (hi) or no (lo) \ No newline at end of file diff --git a/firmware/cl-step-controller/src/drivers/enc_as5047.cpp b/firmware/cl-step-controller/src/drivers/enc_as5047.cpp index 790277ee0ffec54a471195cc21789937619a73f5..3101dbd6381133fff7f36541f831bba360ee3d00 100644 --- a/firmware/cl-step-controller/src/drivers/enc_as5047.cpp +++ b/firmware/cl-step-controller/src/drivers/enc_as5047.cpp @@ -13,7 +13,7 @@ is; no warranty is provided, and users accept all liability. */ #include "enc_as5047.h" -#include "../utils/clocks_d51_module.h" +#include "../osape/utils/clocks_d51.h" ENC_AS5047* ENC_AS5047::instance = 0; @@ -75,8 +75,8 @@ void ENC_AS5047::init(void){ // AS5047 datasheet says CPOL = 1, CPHA = 0, msb first, and parity checks // bit: func // 15: parity, 14: 0/read, 1/write, 13:0 address to read or write - ENC_SER_SPI.CTRLA.reg = SERCOM_SPI_CTRLA_CPOL | // CPOL = 1 - //SERCOM_SPI_CTRLA_CPHA | // ? + ENC_SER_SPI.CTRLA.reg = //SERCOM_SPI_CTRLA_CPOL | // CPOL = 1 + SERCOM_SPI_CTRLA_CPHA | // ? SERCOM_SPI_CTRLA_DIPO(3) | // pad 3 is data input SERCOM_SPI_CTRLA_DOPO(0) | // pad 0 is data output, 1 is clk SERCOM_SPI_CTRLA_MODE(3); // mode 3: head operation @@ -168,27 +168,26 @@ uint16_t ENC_AS5047::get_reading(void){ } uint16_t ENC_AS5047::read_field_mag(void){ + start_spi_interaction(AS5047_SPI_READ_MAG); + while(!readComplete); start_spi_interaction(AS5047_SPI_READ_MAG); while(!readComplete); return result; } -String ENC_AS5047::read_enc_diagnostics(void){ +as5047_diag_t ENC_AS5047::read_enc_diagnostics(void){ + start_spi_interaction(AS5047_SPI_READ_DIAG); + while(!readComplete); start_spi_interaction(AS5047_SPI_READ_DIAG); while(!readComplete); uint16_t res = result; - boolean magHi = false; - boolean magLo = false; - boolean cordicOvf = false; - boolean compComplete = false; - if(res & (1 << 11)) magHi = true; // maghi - if(res & (1 << 10)) magLo = true; // maglo - if(res & (1 << 9)) cordicOvf = true; // cordic overflow - if(res & (1 << 8)) compComplete = true; // offset compensation completed - uint16_t agc = res & 0b0000000001111111; - return "magHi: " + String(magHi) - + "\nmagLo: " + String(magLo) - + "\ncordicOverflow: " + String(cordicOvf) - + "\ncompensationComplete: " + String(compComplete) - + "\nautomaticGainCorrection: " + String(agc); + // seeing some strange results here, bewarned + //sysError(String(res, BIN)); + as5047_diag_t result; + (res & (1 << 11)) ? result.magLo = true : result.magLo = false; + (res & (1 << 10)) ? result.magHi = true : result.magHi = false; + (res & (1 << 9)) ? result.cordicOverflow = true : result.cordicOverflow = false; + (res & (1 << 8)) ? result.compensationComplete = true : result.compensationComplete = false; + result.angularGainCorrection = res & 0b0000000011111111; + return result; } \ No newline at end of file diff --git a/firmware/cl-step-controller/src/drivers/enc_as5047.h b/firmware/cl-step-controller/src/drivers/enc_as5047.h index 49c9aad2b2bb3fa9584295fc5ce9604cda0fe6ff..b516e4c29f5289f6900d9e40fa32f457dbdacb9b 100644 --- a/firmware/cl-step-controller/src/drivers/enc_as5047.h +++ b/firmware/cl-step-controller/src/drivers/enc_as5047.h @@ -18,7 +18,7 @@ is; no warranty is provided, and users accept all liability. #include <Arduino.h> #include "indicators.h" -#include "utils/syserror.h" +#include "../osape/utils/syserror.h" #define ENC_CS_PIN 14 // PB14, SER4-2 #define ENC_CS_BM (uint32_t)(1 << ENC_CS_PIN) @@ -48,6 +48,14 @@ is; no warranty is provided, and users accept all liability. #define AS5047_SPI_READ_MAG (0b1100000000000000 | 0x3FFD) #define AS5047_SPI_READ_DIAG (0b1100000000000000 | 0x3FFC) +typedef struct { + boolean magHi; + boolean magLo; + boolean cordicOverflow; + boolean compensationComplete; + uint8_t angularGainCorrection; +} as5047_diag_t; + class ENC_AS5047 { private: // is singleton @@ -76,7 +84,7 @@ class ENC_AS5047 { void on_read_complete(uint16_t pos); // *blocking* uint16_t read_field_mag(void); - String read_enc_diagnostics(void); + as5047_diag_t read_enc_diagnostics(void); }; extern ENC_AS5047* enc_as5047; diff --git a/firmware/cl-step-controller/src/drivers/peripheral_nums.h b/firmware/cl-step-controller/src/drivers/peripheral_nums.h deleted file mode 100644 index eed9f188afacfb0da271d43603f833f61ec61191..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/drivers/peripheral_nums.h +++ /dev/null @@ -1,18 +0,0 @@ -#ifndef PERIPHERAL_NUMS_H_ -#define PERIPHERAL_NUMS_H_ - -#define PERIPHERAL_A 0 -#define PERIPHERAL_B 1 -#define PERIPHERAL_C 2 -#define PERIPHERAL_D 3 -#define PERIPHERAL_E 4 -#define PERIPHERAL_F 5 -#define PERIPHERAL_G 6 -#define PERIPHERAL_H 7 -#define PERIPHERAL_I 8 -#define PERIPHERAL_K 9 -#define PERIPHERAL_L 10 -#define PERIPHERAL_M 11 -#define PERIPHERAL_N 12 - -#endif \ No newline at end of file diff --git a/firmware/cl-step-controller/src/drivers/step_a4950.h b/firmware/cl-step-controller/src/drivers/step_a4950.h index 0cc143a80865c7ea194edb21c118b7e7912c279f..6b71164959117ccfe9703a53fba96b01fa27eedb 100644 --- a/firmware/cl-step-controller/src/drivers/step_a4950.h +++ b/firmware/cl-step-controller/src/drivers/step_a4950.h @@ -19,7 +19,7 @@ is; no warranty is provided, and users accept all liability. #include "dacs.h" #include "indicators.h" -#include "utils/syserror.h" +#include "../osape/utils/syserror.h" // C_SCALE // 1: DACs go 0->512 (of 4096, peak current is 1.6A at 4096): 0.2A diff --git a/firmware/cl-step-controller/src/drivers/step_cl.cpp b/firmware/cl-step-controller/src/drivers/step_cl.cpp index 3af6ca356eabe32cbbaaee998fbc6c478d2cd4db..c83fb97825a32c3428398a6f2d2a880d8bba13f1 100644 --- a/firmware/cl-step-controller/src/drivers/step_cl.cpp +++ b/firmware/cl-step-controller/src/drivers/step_cl.cpp @@ -125,36 +125,47 @@ void Step_CL::run_torque_loop(void){ #define TICKS_PER_SEC 50000.0F #define SECS_PER_TICK 1.0F / TICKS_PER_SEC -volatile float a_measurement = 0.0F; +volatile uint16_t enc_reading = 0; +volatile float a_reading = 0.0F; volatile float last_measurement = 0.0F; volatile float a_est = 0.0F; volatile float a_last_est = 0.0F; -volatile float a_alpha = 0.9F; // trust in measurement +volatile float a_alpha = 0.01F; // trust in measurement volatile float _pa; // phase angle -float Step_CL::get_last_pos_est(void){ - return a_est; +uint16_t Step_CL::get_last_enc_reading(void){ + return enc_reading; +} + +float Step_CL::get_last_pos_reading(void){ + return a_reading; } -float Step_CL::get_last_reading(void){ - return a_measurement; +float Step_CL::get_last_pos_est(void){ + return a_est; } void ENC_AS5047::on_read_complete(uint16_t result){ if(step_cl->is_calibrating) return; - last_measurement = a_measurement; - a_measurement = lut[result * 2]; - // wtf ?? - // a_est = (a_measurement * a_alpha) + (a_last_est * (1 - a_alpha)); - // a_last_est = a_est; + // stash this, + enc_reading = result; + // stash old measurement, pull new from LUT + last_measurement = a_reading; + a_reading = lut[result * 2]; + // make estimate + a_est = (a_reading * a_alpha) + (a_last_est * (1 - a_alpha)); + a_last_est = a_est; + // derivative, + // or like // I am completely confused by the noise that this generates ? seems like it's taking a difference? // should just be averaging? // something about getting the variables out, under interrupt? - a_est = 0.5 * a_measurement + 0.5 * last_measurement; + //a_est = a_reading; // 0.5 * a_measurement + 0.5 * last_measurement; //output = alpha * (input - output) + output + // this commutation phase is independent from the above, more or less _pa = lut[result * 2 + 1]; // the phase angle (0 - 1 in a sweep of 4 steps) // this is the phase angle we want to apply, 90 degs off & wrap't to 1 if(step_cl->get_torque() < 0){ diff --git a/firmware/cl-step-controller/src/drivers/step_cl.h b/firmware/cl-step-controller/src/drivers/step_cl.h index fa26bf1baed57ac7d0a448ac4f142a8eaac71c5d..73a17108dc746c06d8f003740aa56121971cc6e8 100644 --- a/firmware/cl-step-controller/src/drivers/step_cl.h +++ b/firmware/cl-step-controller/src/drivers/step_cl.h @@ -33,8 +33,10 @@ class Step_CL { void print_table(void); void set_torque(float tc); float get_torque(void); + // read stat + uint16_t get_last_enc_reading(void); + float get_last_pos_reading(void); float get_last_pos_est(void); - float get_last_reading(void); void run_torque_loop(void); boolean calibrate(void); boolean is_calibrating; diff --git a/firmware/cl-step-controller/src/drivers/ucbus_drop.cpp b/firmware/cl-step-controller/src/drivers/ucbus_drop.cpp deleted file mode 100644 index 3053d2ac214c9298d70525ca37334b62b6809970..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/drivers/ucbus_drop.cpp +++ /dev/null @@ -1,285 +0,0 @@ -/* -osap/drivers/ucbus_head.cpp - -beginnings of a uart-based clock / bus combo protocol - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo -projects. Copyright is retained and must be preserved. The work is provided as -is; no warranty is provided, and users accept all liability. -*/ - -#include "ucbus_drop.h" - -UCBus_Drop* UCBus_Drop::instance = 0; - -UCBus_Drop* UCBus_Drop::getInstance(void){ - if(instance == 0){ - instance = new UCBus_Drop(); - } - return instance; -} - -// making this instance globally available, when built, -// recall extern declaration in .h -UCBus_Drop* ucBusDrop = UCBus_Drop::getInstance(); - -UCBus_Drop::UCBus_Drop(void) {} - -// so, first thing, I've some confusion about what might be the best way (again) to implement -// multiple similar drivers. I did this before w/ the cobserialport, I might again want to -// do it, but by writing more static hardware drivers that another parent class (the bus) forwards to -// so the init codes / etc could all be verbatim with hardware registers, instead of this infinite list of defines - -// yeah, this kind of stuff is morning work: focus, tracking little details. go to bed. - -void UCBus_Drop::init(boolean useDipPick, uint8_t ID) { - dip_init(); - if(useDipPick){ - // set our id, - id = dip_read_lower_five(); - } else { - id = ID; - } - if(id > 14){ - id = 14; - } - // set driver output LO to start: tri-state - UBD_DE_PORT.DIRSET.reg = UBD_DE_BM; - UBD_DRIVER_DISABLE; - // set receiver output on, forever: LO to set on - UBD_RE_PORT.DIRSET.reg = UBD_RE_BM; - UBD_RE_PORT.OUTCLR.reg = UBD_RE_BM; - // termination resistor should be set only on one drop, - // or none and physically with a 'tail' cable, or something? - UBD_TE_PORT.DIRSET.reg = UBD_TE_BM; - if(dip_read_pin_1()){ - UBD_TE_PORT.OUTCLR.reg = UBD_TE_BM; - } else { - UBD_TE_PORT.OUTSET.reg = UBD_TE_BM; - } - // rx pin setup - UBD_COMPORT.DIRCLR.reg = UBD_RXBM; - UBD_COMPORT.PINCFG[UBD_RXPIN].bit.PMUXEN = 1; - if(UBD_RXPIN % 2){ - UBD_COMPORT.PMUX[UBD_RXPIN >> 1].reg |= PORT_PMUX_PMUXO(UBD_RXPERIPHERAL); - } else { - UBD_COMPORT.PMUX[UBD_RXPIN >> 1].reg |= PORT_PMUX_PMUXE(UBD_RXPERIPHERAL); - } - // tx - UBD_COMPORT.DIRCLR.reg = UBD_TXBM; - UBD_COMPORT.PINCFG[UBD_TXPIN].bit.PMUXEN = 1; - if(UBD_TXPIN % 2){ - UBD_COMPORT.PMUX[UBD_TXPIN >> 1].reg |= PORT_PMUX_PMUXO(UBD_TXPERIPHERAL); - } else { - UBD_COMPORT.PMUX[UBD_TXPIN >> 1].reg |= PORT_PMUX_PMUXE(UBD_TXPERIPHERAL); - } - // ok, clocks, first line au manuel - // unmask clocks - MCLK->APBAMASK.bit.SERCOM1_ = 1; - GCLK->GENCTRL[UBD_GCLKNUM_PICK].reg = GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DFLL) | GCLK_GENCTRL_GENEN; - while(GCLK->SYNCBUSY.reg & GCLK_SYNCBUSY_GENCTRL(UBD_GCLKNUM_PICK)); - GCLK->PCHCTRL[UBD_SERCOM_CLK].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(UBD_GCLKNUM_PICK); - // then, sercom - while(UBD_SER_USART.SYNCBUSY.bit.ENABLE); - UBD_SER_USART.CTRLA.bit.ENABLE = 0; - while(UBD_SER_USART.SYNCBUSY.bit.SWRST); - UBD_SER_USART.CTRLA.bit.SWRST = 1; - while(UBD_SER_USART.SYNCBUSY.bit.SWRST); - while(UBD_SER_USART.SYNCBUSY.bit.SWRST || UBD_SER_USART.SYNCBUSY.bit.ENABLE); - // ok, well - UBD_SER_USART.CTRLA.reg = SERCOM_USART_CTRLA_MODE(1) | SERCOM_USART_CTRLA_DORD; - UBD_SER_USART.CTRLA.reg |= SERCOM_USART_CTRLA_RXPO(UBD_RXPO) | SERCOM_USART_CTRLA_TXPO(0); - UBD_SER_USART.CTRLA.reg |= SERCOM_USART_CTRLA_FORM(1); // enable even parity - while(UBD_SER_USART.SYNCBUSY.bit.CTRLB); - UBD_SER_USART.CTRLB.reg = SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN | SERCOM_USART_CTRLB_CHSIZE(0); - // enable interrupts - NVIC_EnableIRQ(SERCOM1_2_IRQn); // rx, - NVIC_EnableIRQ(SERCOM1_1_IRQn); // txc ? - NVIC_EnableIRQ(SERCOM1_0_IRQn); // tx, - // priority - NVIC_SetPriority(SERCOM1_2_IRQn, 1); - NVIC_SetPriority(SERCOM1_1_IRQn, 1); - NVIC_SetPriority(SERCOM1_0_IRQn, 1); - // set baud - UBD_SER_USART.BAUD.reg = UBD_BAUD_VAL; - // and finally, a kickoff - while(UBD_SER_USART.SYNCBUSY.bit.ENABLE); - UBD_SER_USART.CTRLA.bit.ENABLE = 1; - // enable rx interrupt - UBD_SER_USART.INTENSET.bit.RXC = 1; -} - -void SERCOM1_2_Handler(void){ - //ERRLIGHT_TOGGLE; - ucBusDrop->rxISR(); -} - -void UCBus_Drop::rxISR(void){ - // check parity bit, - uint16_t perr = UBD_SER_USART.STATUS.bit.PERR; - if(perr){ - //DEBUGPIN_ON; - uint8_t clear = UBD_SER_USART.DATA.reg; - UBD_SER_USART.STATUS.bit.PERR = 1; // clear parity error - return; - } - // cleared by reading out, but we are blind feed forward atm - uint8_t data = UBD_SER_USART.DATA.reg; - // for now, just running the clk, on every 0th bit - if((data >> 7) == 0){ // timer bit, on every 0th bit, and beginning of word - inWord[0] = data; - timeTick ++; - timeBlink ++; - if(timeBlink >= blinkTime){ - CLKLIGHT_TOGGLE; - timeBlink = 0; - } - onRxISR(); // on start of each word - } else { // end of word on every 0th bit - inWord[1] = data; - // now decouple, - inHeader = ((inWord[0] >> 1) & 0b00111000) | ((inWord[1] >> 4) & 0b00000111); - inByte = ((inWord[0] << 4) & 0b11110000) | (inWord[1] & 0b00001111); - // now check incoming data, - if((inHeader & 0b00110000) == 0b00100000){ // has-token, CHA - lastWordAHadToken = true; - if(inBufferALen != 0){ // in this case, we didn't read-out of the buffer in time, - inBufferALen = 0; // so we reset it, missing the last packet ! - inBufferARp = 0; - } - inBufferA[inBufferARp] = inByte; - inBufferARp ++; - } else if ((inHeader & 0b00110000) == 0b00000000) { // no-token, CHA - if(lastWordAHadToken){ - inBufferALen = inBufferARp - 1; - onPacketARx(); - } - lastWordAHadToken = false; - } else if ((inHeader & 0b00110000) == 0b00110000) { // has-token, CHB - //DEBUG1PIN_ON; - lastWordBHadToken = true; - if(inBufferBLen != 0){ - inBufferBLen = 0; - inBufferBRp = 0; - } - inBufferB[inBufferBRp] = inByte; - inBufferBRp ++; - } else if ((inHeader & 0b00110000) == 0b00010000) { // no-token, CHB - if(lastWordBHadToken){ - inBufferBLen = inBufferARp - 1; - //onPacketBRx(); // b-channel handled in loop, yah - } - lastWordBHadToken = false; - } - // now check if outgoing tick is ours, - if((inHeader & dropIdMask) == id){ - // our transmit - if(outBufferLen > 0){ - outByte = outBuffer[outBufferRp]; - outHeader = headerMask & (tokenWord | (id & 0b00011111)); - } else { - outByte = 0; - outHeader = headerMask & (noTokenWord | (id & 0b00011111)); - } - outWord[0] = 0b00000000 | ((outHeader << 1) & 0b01110000) | (outByte >> 4); - outWord[1] = 0b10000000 | ((outHeader << 4) & 0b01110000) | (outByte & 0b00001111); - // now transmit, - UBD_DRIVER_ENABLE; - UBD_SER_USART.DATA.reg = outWord[0]; - UBD_SER_USART.INTENSET.bit.DRE = 1; - // now do this, - if(outBufferLen > 0){ - outBufferRp ++; - if(outBufferRp >= outBufferLen){ - outBufferRp = 0; - outBufferLen = 0; - } - } - } else if ((inHeader & dropIdMask) == UBD_CLOCKRESET){ - // reset - timeTick = 0; - } - } // end 1th bit case, - // do every-tick stuff -} - -void SERCOM1_0_Handler(void){ - ucBusDrop->dreISR(); -} - -void UCBus_Drop::dreISR(void){ - UBD_SER_USART.DATA.reg = outWord[1]; // tx the next word, - UBD_SER_USART.INTENCLR.reg = SERCOM_USART_INTENCLR_DRE; // clear this interrupt - UBD_SER_USART.INTENSET.reg = SERCOM_USART_INTENSET_TXC; // now watch transmit complete -} - -void SERCOM1_1_Handler(void){ - ucBusDrop->txcISR(); -} - -void UCBus_Drop::txcISR(void){ - UBD_SER_USART.INTFLAG.bit.TXC = 1; // clear the flag by writing 1 - UBD_SER_USART.INTENCLR.reg = SERCOM_USART_INTENCLR_TXC; // turn off the interrupt - UBD_DRIVER_DISABLE; // turn off the driver, - //DEBUGPIN_TOGGLE; -} - -// -------------------------------------------------------- ASYNC API - -boolean UCBus_Drop::ctr_a(void){ - if(inBufferALen > 0){ - return true; - } else { - return false; - } -} - -boolean UCBus_Drop::ctr_b(void){ - if(inBufferBLen > 0){ - return true; - } else { - return false; - } -} - -size_t UCBus_Drop::read_a(uint8_t *dest){ - if(!ctr_a()) return 0; - NVIC_DisableIRQ(SERCOM1_2_IRQn); - // copy out, irq disabled, TODO safety on missing an interrupt in this case?? clock jitter? - memcpy(dest, inBufferA, inBufferALen); - size_t len = inBufferALen; - inBufferALen = 0; - inBufferARp = 0; - NVIC_EnableIRQ(SERCOM1_2_IRQn); - return len; -} - -size_t UCBus_Drop::read_b(uint8_t *dest){ - if(!ctr_b()) return 0; - NVIC_DisableIRQ(SERCOM1_2_IRQn); - memcpy(dest, inBufferB, inBufferBLen); - size_t len = inBufferBLen; - inBufferBLen = 0; - inBufferBRp = 0; - NVIC_EnableIRQ(SERCOM1_2_IRQn); - return len; -} - -boolean UCBus_Drop::cts(void){ - if(outBufferLen > 0){ - return false; - } else { - return true; - } -} - -void UCBus_Drop::transmit(uint8_t *data, uint16_t len){ - if(!cts()) return; - size_t encLen = cobsEncode(data, len, outBuffer); - outBufferLen = encLen; - outBufferRp = 0; -} \ No newline at end of file diff --git a/firmware/cl-step-controller/src/drivers/ucbus_drop.h b/firmware/cl-step-controller/src/drivers/ucbus_drop.h deleted file mode 100644 index 844645cdb3390c9dcd539aa39357a5bc618bdc27..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/drivers/ucbus_drop.h +++ /dev/null @@ -1,122 +0,0 @@ -/* -osap/drivers/ucbus_head.h - -beginnings of a uart-based clock / bus combo protocol - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo -projects. Copyright is retained and must be preserved. The work is provided as -is; no warranty is provided, and users accept all liability. -*/ - -#ifndef UCBUS_DROP_H_ -#define UCBUS_DROP_H_ - -#include <arduino.h> - -#include "indicators.h" -#include "dip_ucbus_config.h" -#include "peripheral_nums.h" -#include "utils/syserror.h" -#include "utils/cobs.h" - -#define UBD_SER_USART SERCOM1->USART -#define UBD_SERCOM_CLK SERCOM1_GCLK_ID_CORE -#define UBD_GCLKNUM_PICK 7 -#define UBD_COMPORT PORT->Group[0] -#define UBD_TXPIN 16 // x-0 -#define UBD_TXBM (uint32_t)(1 << UBD_TXPIN) -#define UBD_RXPIN 18 // x-2 -#define UBD_RXBM (uint32_t)(1 << UBD_RXPIN) -#define UBD_RXPO 2 -#define UBD_TXPERIPHERAL PERIPHERAL_C -#define UBD_RXPERIPHERAL PERIPHERAL_C - -// baud bb baud -// 63019 for a very safe 115200 -// 54351 for a go-karting 512000 -// 43690 for a trotting pace of 1MHz -// 21845 for the E30 2MHz -// 0 for max-speed 3MHz -#define UBD_BAUD_VAL 0 - -#define UBD_DE_PIN 16 // driver output enable: set HI to enable, LO to tri-state the driver -#define UBD_DE_BM (uint32_t)(1 << UBD_DE_PIN) -#define UBD_DE_PORT PORT->Group[1] -#define UBD_DRIVER_ENABLE UBD_DE_PORT.OUTSET.reg = UBD_DE_BM -#define UBD_DRIVER_DISABLE UBD_DE_PORT.OUTCLR.reg = UBD_DE_BM -#define UBD_RE_PIN 19 // receiver output enable, set LO to enable the RO, set HI to tri-state RO -#define UBD_RE_BM (uint32_t)(1 << UBD_RE_PIN) -#define UBD_RE_PORT PORT->Group[0] -#define UBD_TE_PIN 17 // termination enable, drive LO to enable to internal termination resistor, HI to disable -#define UBD_TE_BM (uint32_t)(1 << UBD_TE_PIN) -#define UBD_TE_PORT PORT->Group[0] - -#define UBD_BUFSIZE 1024 - -#define UBD_CLOCKRESET 15 - -#define UB_AK_GOTOPOS 91 -#define UB_AK_SETPOS 92 -#define UB_AK_SETRPM 93 - -class UCBus_Drop { - private: - // singleton-ness - static UCBus_Drop* instance; - // timing, - volatile uint64_t timeBlink = 0; - uint16_t blinkTime = 10000; - // input buffer & word - volatile uint8_t inWord[2]; - volatile uint8_t inHeader; - volatile uint8_t inByte; - volatile boolean lastWordAHadToken = false; - uint8_t inBufferA[UBD_BUFSIZE]; - volatile uint16_t inBufferARp = 0; - volatile uint16_t inBufferALen = 0; // writes at terminal zero, - volatile boolean lastWordBHadToken = false; - uint8_t inBufferB[UBD_BUFSIZE]; - volatile uint16_t inBufferBRp = 0; - volatile uint16_t inBufferBLen = 0; - // output, - volatile uint8_t outWord[2]; - volatile uint8_t outHeader; - volatile uint8_t outByte; - uint8_t outBuffer[UBD_BUFSIZE]; - volatile uint16_t outBufferRp = 0; - volatile uint16_t outBufferLen = 0; - const uint8_t headerMask = 0b00111111; - const uint8_t dropIdMask = 0b00001111; - const uint8_t tokenWord = 0b00100000; - const uint8_t noTokenWord = 0b00000000; - public: - UCBus_Drop(); - static UCBus_Drop* getInstance(void); - // available time count, - volatile uint16_t timeTick = 0; - // isrs - void rxISR(void); - void dreISR(void); - void txcISR(void); - // handlers - void onRxISR(void); - void onPacketARx(void); - // our physical bus address, - volatile uint8_t id = 0; - // the api, eh - void init(boolean useDipPick, uint8_t ID); - boolean ctr_a(void); // return true if RX complete / buffer ready - boolean ctr_b(void); - size_t read_a(uint8_t *dest); // ship les bytos - size_t read_b(uint8_t *dest); - boolean cts(void); // true if tx buffer empty, - void transmit(uint8_t *data, uint16_t len); -}; - -extern UCBus_Drop* ucBusDrop; - -#endif \ No newline at end of file diff --git a/firmware/cl-step-controller/src/main.cpp b/firmware/cl-step-controller/src/main.cpp index cdbdf30adda00fb8266e733e472cbb383fa7e16e..857f62a844d53ef61c101e87150a6fa433692646 100644 --- a/firmware/cl-step-controller/src/main.cpp +++ b/firmware/cl-step-controller/src/main.cpp @@ -1,46 +1,110 @@ #include <Arduino.h> #include "drivers/indicators.h" -#include "utils/cobs.h" -#include "osap/osap.h" +#include "osape/osap/osap.h" OSAP* osap = new OSAP("cl stepper motor drop"); -#include "osap/vport_usbserial.h" +#include "osape/osap/vport_usbserial.h" VPort_USBSerial* vPortSerial = new VPort_USBSerial(); -#include "drivers/ucbus_drop.h" + +#include "osape/osap/vport_ucbus_drop.h" + #include "drivers/step_cl.h" +#include "osape/utils/clocks_d51.h" + + +// -------------------------------------------------------- 0: MAG DIAGNOSTICS + +boolean onMagDiagnosticsPut(uint8_t* data, uint16_t len); +boolean onMagDiagnosticsQuery(void); + +Endpoint* magDiagnosticsEP = osap->endpoint(onMagDiagnosticsPut, onMagDiagnosticsQuery); + +boolean onMagDiagnosticsPut(uint8_t* data, uint16_t len){ + return true; +} + +boolean onMagDiagnosticsQuery(void){ + // put diag. data in the stash + uint16_t magField = enc_as5047->read_field_mag(); + as5047_diag_t diagnostics = enc_as5047->read_enc_diagnostics(); + uint8_t data[7]; + uint16_t wptr = 0; + ts_writeBoolean(diagnostics.magHi, data, &wptr); + ts_writeBoolean(diagnostics.magLo, data, &wptr); + ts_writeBoolean(diagnostics.cordicOverflow, data, &wptr); + ts_writeBoolean(diagnostics.compensationComplete, data, &wptr); + ts_writeUint8(diagnostics.angularGainCorrection, data, &wptr); + ts_writeUint16(magField, data, &wptr); + magDiagnosticsEP->write(data, 7); + return true; +} + +// -------------------------------------------------------- 1: RUN CALIB + +boolean onRunCalibPut(uint8_t* data, uint16_t len); +Endpoint* runCalibEP = osap->endpoint(onRunCalibPut); + +boolean onRunCalibPut(uint8_t* data, uint16_t len){ + step_cl->calibrate(); + return true; +} + +// -------------------------------------------------------- 2: POSITION TARGET + +boolean onPositionTargetPut(uint8_t* data, uint16_t len); +Endpoint* positionTargetEP = osap->endpoint(onPositionTargetPut); + +boolean onPositionTargetPut(uint8_t* data, uint16_t len){ + return true; +} + +// -------------------------------------------------------- 3: CURRENT POSITION -#include "utils/clocks_d51_module.h" - -union chunk_float32 { - uint8_t bytes[4]; - float f; -}; - -union chunk_float64 { - uint8_t bytes[8]; - double f; -}; - -// adhoc reply -uint8_t reply[1024]; -uint16_t rl = 0; - -uint8_t replyBlankPck[1024]; -uint16_t replyBlankPl = 0; -uint16_t replyBlankPtr = 0; -uint16_t replyBlankSegsize = 0; -VPort* replyBlankVp; -uint16_t replyBlankVpi = 0; -uint16_t lastQueueSpaceTxd = 0; - -#define BUS_DROP 4 // Z: 1, YL: 2, X: 3, YR: 4 -#define AXIS_PICK 2 // Z: 2, Y: 1, X: 0 -#define AXIS_INVERT false // Z: false, YL: true, YR: false, X: false -#define SPU 3200.0F // always positive! Z: 3200, XY: 400 -#define C_SCALE 0.2F // 0-1, floating: initial holding current to motor, 0-2.5A -#define TICKS_PER_PACKET 20.0F // always 20.0F +boolean onPositionPut(uint8_t* data, uint16_t len); +boolean onPositionQuery(void); +Endpoint* positionQueryEP = osap->endpoint(onPositionPut, onPositionQuery); + +boolean onPositionPut(uint8_t* data, uint16_t len){ + return true; +} + +boolean onPositionQuery(void){ + float posn = step_cl->get_last_pos_est(); + uint8_t data[4]; + uint16_t wptr = 0; + ts_writeFloat32(posn, data, &wptr); + positionQueryEP->write(data, 4); + return true; +} + +// -------------------------------------------------------- 4: FULL SPEC + +boolean onSpecPut(uint8_t* data, uint16_t len); +boolean onSpecQuery(void); +Endpoint* specQueryEP = osap->endpoint(onSpecPut, onSpecQuery); + +boolean onSpecPut(uint8_t* data, uint16_t len){ + return true; +} + +boolean onSpecQuery(void){ + // want: + uint16_t encoder_reading = step_cl->get_last_enc_reading(); + float angle_reading = step_cl->get_last_pos_reading(); + float posn = step_cl->get_last_pos_est(); + // ship, + uint8_t data[10]; + uint16_t wptr = 0; + ts_writeUint16(encoder_reading, data, &wptr); + ts_writeFloat32(angle_reading, data, &wptr); + ts_writeFloat32(posn, data, &wptr); + specQueryEP->write(data, 10); + return true; +} + +// -------------------------------------------------------- SETUP / RUNTIME void setup() { ERRLIGHT_SETUP; @@ -50,76 +114,47 @@ void setup() { osap->description = "cl controller test"; // serport osap->addVPort(vPortSerial); - // bus - ucBusDrop->init(false, BUS_DROP); // cl controller step_cl->init(); - // start ctrl timer for 100khz loop, - d51_clock_boss->start_50kHz_ticker_tc0(); + // start ctrl timer for loop (arg to start is us period) + d51_clock_boss->start_ticker_a(100); } -// 50kHz control tick +// on ticker_a void TC0_Handler(void){ TC0->COUNT32.INTFLAG.bit.MC0 = 1; TC0->COUNT32.INTFLAG.bit.MC1 = 1; step_cl->run_torque_loop(); } -uint8_t bChPck[64]; -volatile float current_floating_pos = 0.0F; -volatile int32_t current_step_pos = 0; -volatile uint32_t delta_steps = 0; -volatile float vel = 0.0F; -volatile float move_counter = 0.0F; -volatile boolean setBlock = false; -uint16_t tick = 0; - // async loop void loop() { osap->loop(); step_a4950->dacRefresh(); - // check chb packes - if(ucBusDrop->ctr_b()){ - uint16_t len = ucBusDrop->read_b(bChPck); - uint16_t ptr = 0; - switch(bChPck[ptr]){ - case AK_SET_TC: { - ptr ++; - chunk_float32 tcs = { .bytes = { bChPck[ptr ++], bChPck[ptr ++], bChPck[ptr ++], bChPck[ptr ++] }}; - step_cl->set_torque(tcs.f); - } - break; - case AK_RUNCALIB: - step_cl->calibrate(); - break; - default: - // noop - break; - } - } } // end loop // usb packets -void OSAP::handleAppPacket(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t pwp){ - // track end of header, to reply with - uint16_t replyPtr = ptr; - // (a hack) store one app packet, to format our replies with. do once - if(replyBlankPtr == 0){ - for(uint16_t i = 0; i < pl; i++){ - replyBlankPck[i] = pck[i]; - } - replyBlankPl = pl; - replyBlankPtr = ptr; - replyBlankSegsize = segsize; - replyBlankVp = vp; - replyBlankVpi = vpi; - } - // clear out our reply, - rl = 0; - reply[rl ++] = DK_APP; - // do the reading: - ptr ++; // walk appcode DK_APP - switch(pck[ptr]){ +void OSAP::handleAppPacket(uint8_t* pck, uint16_t ptr, pckm_t* pckm){ + // always clear this + pckm->vpa->clear(pckm->location); +} + +#ifdef UCBUS_IS_DROP + +// on words rx'd from bus, +void UCBus_Drop::onRxISR(void){ + +} + +// on timed (interrupt) rx of bus packet, channel A +// this is where we will eventually read-in positions, and target them +void UCBus_Drop::onPacketARx(void){ + +} + +#endif + +/* case AK_READ_MAG:{ ptr ++; reply[rl ++] = AK_READ_MAG; @@ -160,29 +195,4 @@ void OSAP::handleAppPacket(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t seg ts_writeFloat32(last_reading, reply, &rl); break; } - default: - break; - } - // end pck[ptr] switch - if(rl > 1){ - if(vp->cts()){ - appReply(pck, pl, replyPtr, segsize, vp, vpi, reply, rl); - } else { - sysError("on reply, not cts, system fails"); - } - } - // always clear this - vp->clearPacket(pwp); -} - -// on words rx'd from bus, -void UCBus_Drop::onRxISR(void){ - -} - -// on timed (interrupt) rx of bus packet, channel A -// this is where we will eventually read-in positions, and target them -void UCBus_Drop::onPacketARx(void){ - -} - +*/ diff --git a/firmware/cl-step-controller/src/osap/osap.cpp b/firmware/cl-step-controller/src/osap/osap.cpp deleted file mode 100644 index 4b4499c5c2cd3fbd93ca95f0f43608b0f613aa2c..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/osap/osap.cpp +++ /dev/null @@ -1,487 +0,0 @@ -/* -osap/osap.cpp - -virtual network node - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#include "osap.h" - -uint8_t ringFrame[1028]; - -OSAP::OSAP(String nodeName){ - name = nodeName; -} - -boolean OSAP::addVPort(VPort* vPort){ - if(_numVPorts > OSAP_MAX_VPORTS){ - return false; - } else { - vPort->init(); - _vPorts[_numVPorts ++] = vPort; - return true; - } -} - -void OSAP::forward(uint8_t *pck, uint16_t pl, uint16_t ptr, VPort *vp, uint8_t vpi, uint8_t pwp){ - sysError("NO FWD CODE YET"); - vp->clearPacket(pwp); -} - -void OSAP::write77(uint8_t *pck, VPort *vp){ - uint16_t one = 1; - pck[0] = PK_PPACK; // the '77' - uint16_t bufSpace = vp->getBufSpace(); - ts_writeUint16(bufSpace, pck, &one); - vp->lastRXBufferSpaceTransmitted = bufSpace; - vp->rxSinceTx = 0; -} - -// packet to read from, response to write into, write pointer, maximum response length -// assumes header won't be longer than received max seg length, if it arrived ... -// ptr = DK_x, ptr - 5 = PK_DEST, ptr - 6 = PK_PTR -boolean OSAP::formatResponseHeader(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, uint16_t checksum, VPort *vp, uint16_t vpi){ - // sanity check, this should be pingreq key - // sysError("FRH pck[ptr]: " + String(pck[ptr])); - // buf[(*ptr) ++] = val & 255 - // pck like: - // [rptr] [rend] [ptr] - // [77:3][dep0][e1][e2][e3][pk_ptr][pk_dest][acksegsize:2][checksum:2][dkey-req] - // response (will be) like: - // [wptr] - // [ptr] - // [77:3][dep0][pk_ptr][p3][p2][p1][pk_dest][acksegsize:2][checksum:2][dkey-res] - // ptr here will always indicate end of the header, - // leaves space until pck[3] for the 77-ack, which will write in later on, - // to do this, we read forwarding steps from e1 (incrementing read-ptr) - // and write in tail-to-head, (decrementing write ptr) - uint16_t wptr = ptr - 5; // to beginning of dest, segsize, checksum block - _res[wptr ++] = PK_DEST; - ts_writeUint16(segsize, _res, &wptr); - ts_writeUint16(checksum, _res, &wptr); - wptr -= 5; // back to start of this block, - // now find rptr beginning, - uint16_t rptr = 3; // departure port was trailing 77, - switch(pck[rptr]){ // walk to e1, ignoring original departure information - case PK_PORTF_KEY: - rptr += PK_PORTF_INC; - break; - case PK_BUSF_KEY: - rptr += PK_BUSF_INC; - break; - case PK_BUSB_KEY: - rptr += PK_BUSB_INC; - break; - default: - sysError("nonreq departure key on reverse route, bailing"); - return false; - } - // end switch, now pck[rptr] is at port-type-key of next fwd instruction - // walk rptr forwards, wptr backwards, copying in forwarding segments, max. 16 hops - uint16_t rend = ptr - 6; // read-end per static pck-at-dest end block: 6 for checksum(2) acksegsize(2), dest and ptr - for(uint8_t h = 0; h < 16; h ++){ - if(rptr >= rend){ // terminate when walking past end, - break; - } - switch(pck[rptr]){ - case PK_PORTF_KEY: - wptr -= PK_PORTF_INC; - for(uint8_t i = 0; i < PK_PORTF_INC; i ++){ - _res[wptr + i] = pck[rptr ++]; - } - break; - case PK_BUSF_KEY: - case PK_BUSB_KEY: - wptr -= PK_BUSF_INC; - for(uint8_t i = 0; i < PK_BUSF_INC; i ++){ - _res[wptr + i] = pck[rptr ++]; - } - default: - sysError("rptr: " + String(rptr) + " key here: " + String(pck[rptr])); - sysError("couldn't reverse this path"); - return false; - } - } - // following route-copy-in, - // TODO mod this for busses, - wptr -= 4; - _res[wptr ++] = PK_PORTF_KEY; /// write in departure key type, - ts_writeUint16(vpi, _res, &wptr); // write in departure port, - _res[wptr ++] = PK_PTR; // ptr follows departure key, - // to check, wptr should now be at 7: for 77(3), departure(3:portf), ptr(1) - if(wptr != 7){ // wptr != 7 - sysError("bad response header write"); - return false; - } else { - return true; - } -} - -/* -await osap.query(nextRoute, 'name', 'numVPorts') -await osap.query(nextRoute, 'vport', np, 'name', 'portTypeKey', 'portStatus', 'maxSegLength') -*/ - -void OSAP::writeQueryDown(uint16_t *wptr){ - sysError("QUERYDOWN"); - _res[(*wptr) ++] = EP_ERRKEY; - _res[(*wptr) ++] = EP_ERRKEY_QUERYDOWN; -} - -void OSAP::writeEmpty(uint16_t *wptr){ - sysError("EMPTY"); - _res[(*wptr) ++] = EP_ERRKEY; - _res[(*wptr) ++] = EP_ERRKEY_EMPTY; -} - -// queries for ahn vport, -void OSAP::readRequestVPort(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t rptr, uint16_t *wptr, uint16_t segsize, VPort* vp){ - // could be terminal, could read into endpoints (input / output) of the vport, - for(uint8_t i = 0; i < 16; i ++){ - if(rptr >= pl){ - return; - } - if(*wptr > segsize){ - sysError("QUERYDOWN wptr: " + String(*wptr) + " segsize: " + String(segsize)); - *wptr = ptr; - writeQueryDown(wptr); - return; - } - switch(pck[rptr]){ - case EP_NUMINPUTS: - _res[(*wptr) ++] = EP_NUMINPUTS; - ts_writeUint16(0, _res, wptr); // TODO: vports can have inputs / outputs, - rptr ++; - break; - case EP_NUMOUTPUTS: - _res[(*wptr) ++] = EP_NUMOUTPUTS; - ts_writeUint16(0, _res, wptr); - rptr ++; - break; - case EP_INPUT: - case EP_OUTPUT: - writeEmpty(wptr); // ATM, these just empty - and then return, further args would be for dive - return; - case EP_NAME: - _res[(*wptr) ++] = EP_NAME; - ts_writeString(vp->name, _res, wptr); - rptr ++; - break; - case EP_DESCRIPTION: - _res[(*wptr) ++] = EP_DESCRIPTION; - ts_writeString(vp->description, _res, wptr); - rptr ++; - break; - case EP_PORTTYPEKEY: - _res[(*wptr) ++] = EP_PORTTYPEKEY; // TODO for busses - _res[(*wptr) ++] = vp->portTypeKey; - rptr ++; - break; - case EP_MAXSEGLENGTH: - _res[(*wptr) ++] = EP_MAXSEGLENGTH; - ts_writeUint32(vp->maxSegLength, _res, wptr); - rptr ++; - break; - case EP_PORTSTATUS: - _res[(*wptr) ++] = EP_PORTSTATUS; - ts_writeBoolean(vp->status, _res, wptr); - rptr ++; - break; - case EP_PORTBUFSPACE: - _res[(*wptr) ++] = EP_PORTBUFSPACE; - ts_writeUint16(vp->getBufSpace(), _res, wptr); - rptr ++; - break; - case EP_PORTBUFSIZE: - _res[(*wptr) ++] = EP_PORTBUFSIZE; - ts_writeUint16(vp->getBufSize(), _res, wptr); - rptr ++; - break; - default: - writeEmpty(wptr); - return; - } - } -} - -void OSAP::handleReadRequest(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t pwp){ - if(vp->cts()){ - // resp. code, - // readptr, - uint16_t rptr = ptr + 1; // this will pass the RREQ and ID bytes, next is first query key - uint16_t wptr = ptr; - _res[wptr ++] = DK_RRES; - _res[wptr ++] = pck[rptr ++]; - _res[wptr ++] = pck[rptr ++]; - // read items, - // ok, walk those keys - uint16_t indice = 0; - for(uint8_t i = 0; i < 16; i ++){ - if(rptr >= pl){ - goto endwalk; - } - if(wptr > segsize){ - sysError("QUERYDOWN wptr: " + String(wptr) + " segsize: " + String(segsize)); - wptr = ptr; - writeQueryDown(&wptr); - goto endwalk; - } - switch(pck[rptr]){ - // first up, handle dives which downselect the tree - case EP_VPORT: - rptr ++; - ts_readUint16(&indice, pck, &rptr); - if(indice < _numVPorts){ - _res[wptr ++] = EP_VPORT; - ts_writeUint16(indice, _res, &wptr); - readRequestVPort(pck, pl, ptr, rptr, &wptr, segsize, _vPorts[indice]); - } else { - writeEmpty(&wptr); - } - goto endwalk; - case EP_VMODULE: - writeEmpty(&wptr); - goto endwalk; - // for reading any top-level item, - case EP_NUMVPORTS: - _res[wptr ++] = EP_NUMVPORTS; - ts_writeUint16(_numVPorts, _res, &wptr); - rptr ++; - break; - case EP_NUMVMODULES: - _res[wptr ++] = EP_NUMVMODULES; - ts_writeUint16(_numVModules, _res, &wptr); - rptr ++; - break; - case EP_NAME: - _res[wptr ++] = EP_NAME; - ts_writeString(name, _res, &wptr); - rptr ++; - break; - case EP_DESCRIPTION: - _res[wptr ++] = EP_DESCRIPTION; - ts_writeString(description, _res, &wptr); - rptr ++; - break; - // the default: unclear keys nullify entire response - default: - writeEmpty(&wptr); - goto endwalk; - } // end 1st switch - } - endwalk: ; - //sysError("QUERY ENDWALK, ptr: " + String(ptr) + " wptr: " + String(wptr)); - if(formatResponseHeader(pck, pl, ptr, segsize, wptr - ptr, vp, vpi)){ - vp->clearPacket(pwp); - write77(_res, vp); - vp->sendPacket(_res, wptr); - vp->decrimentRecipBufSpace(); - } else { - sysError("bad response format"); - vp->clearPacket(pwp); - } - } else { - vp->clearPacket(pwp); - } -} - -// pck[ptr] == DK_PINGREQ -void OSAP::handlePingRequest(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t pwp){ - if(vp->cts()){ // resp. path is clear, can write resp. and ship it - // the reversed header will be *the same length* as the received header, - // which was from 0-ptr! - this is great news, we can say: - uint16_t wptr = ptr; // start writing here, leaves room for the header, - _res[wptr ++] = DK_PINGRES; // write in whatever the response is, here just the ping-res key and id - _res[wptr ++] = pck[ptr + 1]; - _res[wptr ++] = pck[ptr + 2]; - // this'll be the 'std' response formatting codes, - // formatResponseHeader doesn't need the _res, that's baked in, and it writes 0-ptr, - // since we wrote into _res following ptr, (header lengths identical), this is safe, - if(formatResponseHeader(pck, pl, ptr, segsize, 3, vp, vpi)){ // write the header: this goes _resp[3] -> _resp[ptr] - vp->clearPacket(pwp); // can now rm the packet, have gleaned all we need from it, - write77(_res, vp); // and *after* rm'ing it, report open space _resp[0] -> _resp[3]; - vp->sendPacket(_res, wptr); // this fn' call should copy-out of our buffer - vp->decrimentRecipBufSpace(); - } else { - sysError("bad response format"); - vp->clearPacket(pwp); - } - } else { - vp->clearPacket(pwp); - } -} - -// write and send ahn reply out, -void OSAP::appReply(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t *reply, uint16_t rl){ - uint16_t wptr = ptr; - for(uint16_t i = 0; i < rl; i ++){ - _res[wptr ++] = reply[i]; - } - if(formatResponseHeader(pck, pl, ptr, segsize, rl, vp, vpi)){ - write77(_res, vp); - vp->sendPacket(_res, wptr); - vp->decrimentRecipBufSpace(); - } else { - sysError("bad response format"); - } -} - -// frame: the buffer, ptr: the location of the ptr (ack or pack), -// vp: port received on, fwp: frame-write-ptr, -// so vp->frames[fwp] = frame, though that isn't exposed here -void OSAP::instructionSwitch(uint8_t *pck, uint16_t pl, uint16_t ptr, VPort *vp, uint8_t vpi, uint8_t pwp){ - // we must *do* something, and (ideally) pop this thing, - switch(pck[ptr]){ - case PK_PORTF_KEY: - case PK_BUSF_KEY: - case PK_BUSB_KEY: - forward(pck, pl, ptr, vp, vpi, pwp); - break; - case PK_DEST: { - ptr ++; // walk past dest key, - uint16_t segsize = 0; - uint16_t checksum = 0; - ts_readUint16(&segsize, pck, &ptr); - ts_readUint16(&checksum, pck, &ptr); - if(checksum != pl - ptr){ - sysError("bad checksum, count: " + String(pl - ptr) + " checksum: " + String(checksum)); - vp->clearPacket(pwp); - } else { - switch(pck[ptr]){ - case DK_APP: - handleAppPacket(pck, pl, ptr, segsize, vp, vpi, pwp); - break; - case DK_PINGREQ: - handlePingRequest(pck, pl, ptr, segsize, vp, vpi, pwp); - break; - case DK_RREQ: - handleReadRequest(pck, pl, ptr, segsize, vp, vpi, pwp); - break; - break; - case DK_WREQ: // no writing yet, - case DK_PINGRES: // not issuing pings from embedded, shouldn't have deal w/ their responses - case DK_RRES: // not issuing requests from embedded, same - case DK_WRES: // not issuing write requests from embedded, again - sysError("WREQ or RES received in embedded, popping"); - vp->clearPacket(pwp); - break; - default: - sysError("non-recognized destination key, popping"); - vp->clearPacket(pwp); - break; - } - } - } - break; - default: - // packet is unrecognized, - sysError("unrecognized instruction key"); - vp->clearPacket(pwp); - break; - } -} - -void OSAP::loop(){ - /* - Also a note - the vp->getFrame(); (which is called often in the loop) doesn't have to be a virtual f. - VPorts can have private \_frames** ptrs-to, and when we start up a vport class, - point that at some statically allocated heap. - also, set a \_numFrames and ahn \_writePtrs*. - */ - /* - another note - this was measured around 25us (long!) - so it would be *tite* if that coule be decreased, especially in recognizing the no-op cases, - where execution could be very - very - small. - */ - unsigned long pat = 0; // packet arrival time - VPort* vp; // vp of vports - unsigned long now = millis(); - // pull one frame per loop per port, - // TODO: can increase speed by pulling more frames per loop ?? - for(uint8_t p = 0; p < _numVPorts; p ++){ - vp = _vPorts[p]; - vp->loop(); // affordance to run phy code, - for(uint8_t t = 0; t < 4; t ++){ // count # of packets to process per port per turn - uint8_t* pck; // the packet we are handling - uint16_t pl = 0; // length of that packet - uint8_t pwp = 0; // packet write pointer: where it was, to write-back clearance - vp->getPacket(&pck, &pl, &pwp, &pat); // gimme the bytes - if(pl > 0){ // have length, will try, - // check prune stale, - if(pat + OSAP_STALETIMEOUT < now){ - //this untested, but should work, yeah? - //sysError("prune stale message on " + String(vp->name)); - vp->clearPacket(pwp); - continue; - } - // check / handle pck - uint16_t ptr = 0; - // new rcrbx? - if(pck[ptr] == PK_PPACK){ - ptr ++; - uint16_t rcrxs; - ts_readUint16(&rcrxs, pck, &ptr); - vp->setRecipRxBufSpace(rcrxs); - } - // anything else? - if(ptr < pl){ - // walk through for instruction, - for(uint8_t i = 0; i < 16; i ++){ - switch(pck[ptr]){ - case PK_PTR: - instructionSwitch(pck, pl, ptr + 1, vp, p, pwp); - goto endWalk; - case PK_PORTF_KEY: // previous instructions, walk over, - ptr += PK_PORTF_INC; - break; - case PK_BUSF_KEY: - ptr += PK_BUSF_INC; - break; - case PK_BUSB_KEY: - ptr += PK_BUSF_INC; - break; - case PK_LLERR: - // someone forwarded us an err-escape, - // we are kind of helpless to help, just escp. - vp->clearPacket(pwp); - goto endWalk; - default: - sysError("bad walk for ptr: key " + String(pck[ptr]) + " at: " + String(ptr)); - vp->clearPacket(pwp); - goto endWalk; - } // end switch - } // end loop for ptr walk, - } else { - // that was just the rcrbx then, - vp->clearPacket(pwp); - } - } else { - break; - } // no frames in this port, - // end of this-port-scan, - endWalk: ; - } // end up-to-8-packets-per-turn - } // end loop over ports (handling rx) - // loop for keepalive conditions, - for(uint8_t p = 0; p < _numVPorts; p ++){ - vp = _vPorts[p]; - // check if needs to tx keepalive, - uint16_t currentRXBufferSpace = vp->getBufSpace(); - if(currentRXBufferSpace > vp->lastRXBufferSpaceTransmitted || vp->lastTxTime + OSAP_TXKEEPALIVEINTERVAL < now){ - // has open space not reported, or needs to ping for port keepalive - if(vp->cts()){ - write77(_res, vp); - vp->sendPacket(_res, 3); - vp->decrimentRecipBufSpace(); - } - } - } // end loop over ports (keepalive) -} \ No newline at end of file diff --git a/firmware/cl-step-controller/src/osap/osap.h b/firmware/cl-step-controller/src/osap/osap.h deleted file mode 100644 index 5242ba0ae6cdc77538ef57f119a6691fb46188fa..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/osap/osap.h +++ /dev/null @@ -1,60 +0,0 @@ -/* -osap/osap.h - -virtual network node - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#ifndef OSAP_H_ -#define OSAP_H_ - -#include <arduino.h> -#include "ts.h" -#include "vport.h" -#include "./drivers/indicators.h" -#include "./utils/cobs.h" - -#define OSAP_MAX_VPORTS 16 -#define RES_LENGTH 2048 -#define OSAP_STALETIMEOUT 600 -#define OSAP_TXKEEPALIVEINTERVAL 300 - -class OSAP { -private: - // yonder ports, - VPort* _vPorts[16]; - uint8_t _numVPorts = 0; - // yither vmodules - uint8_t _numVModules = 0; - // dishing output, temp write buffer - uint8_t _res[RES_LENGTH]; -public: - OSAP(String nodeName); - // props - String name; - String description = "undescribed osap node"; - // fns - boolean addVPort(VPort* vPort); - void forward(uint8_t *pck, uint16_t pl, uint16_t ptr, VPort *vp, uint8_t vpi, uint8_t pwp); - void write77(uint8_t *pck, VPort *vp); - boolean formatResponseHeader(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, uint16_t checksum, VPort *vp, uint16_t vpi); - void writeQueryDown(uint16_t *wptr); - void writeEmpty(uint16_t *wptr); - void readRequestVPort(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t rptr, uint16_t *wptr, uint16_t segsize, VPort* vp); - void handleReadRequest(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t pwp); - void handlePingRequest(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t pwp); - void appReply(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t *reply, uint16_t rl); - void instructionSwitch(uint8_t *pck, uint16_t pl, uint16_t ptr, VPort *vp, uint8_t vpi, uint8_t pwp); - void loop(); - // the handoff, - void handleAppPacket(uint8_t *pck, uint16_t pl, uint16_t ptr, uint16_t segsize, VPort* vp, uint16_t vpi, uint8_t pwp); -}; - -#endif diff --git a/firmware/cl-step-controller/src/osap/ts.cpp b/firmware/cl-step-controller/src/osap/ts.cpp deleted file mode 100644 index 1a399002651a3f22be9cb8c51e373af13d25163d..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/osap/ts.cpp +++ /dev/null @@ -1,64 +0,0 @@ -/* -osap/ts.cpp - -typeset / keys / writing / reading - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#include "ts.h" - -void ts_writeBoolean(boolean val, unsigned char *buf, uint16_t *ptr){ - if(val){ - buf[(*ptr) ++] = 1; - } else { - buf[(*ptr) ++] = 0; - } -} - -void ts_readUint16(uint16_t *val, unsigned char *buf, uint16_t *ptr){ - *val = buf[(*ptr) + 1] << 8 | buf[(*ptr)]; - *ptr += 2; -} - -void ts_writeUint16(uint16_t val, unsigned char *buf, uint16_t *ptr){ - buf[(*ptr) ++] = val & 255; - buf[(*ptr) ++] = (val >> 8) & 255; -} - -void ts_writeUint32(uint32_t val, unsigned char *buf, uint16_t *ptr){ - buf[(*ptr) ++] = val & 255; - buf[(*ptr) ++] = (val >> 8) & 255; - buf[(*ptr) ++] = (val >> 16) & 255; - buf[(*ptr) ++] = (val >> 24) & 255; -} - -union chunk_float32 { - uint8_t bytes[4]; - float f; -}; - -void ts_writeFloat32(float val, volatile unsigned char *buf, uint16_t *ptr){ - chunk_float32 chunk; - chunk.f = val; - buf[(*ptr) ++] = chunk.bytes[0]; - buf[(*ptr) ++] = chunk.bytes[1]; - buf[(*ptr) ++] = chunk.bytes[2]; - buf[(*ptr) ++] = chunk.bytes[3]; -} - -void ts_writeString(String val, unsigned char *buf, uint16_t *ptr){ - uint32_t len = val.length(); - buf[(*ptr) ++] = len & 255; - buf[(*ptr) ++] = (len >> 8) & 255; - buf[(*ptr) ++] = (len >> 16) & 255; - buf[(*ptr) ++] = (len >> 24) & 255; - val.getBytes(&buf[*ptr], len + 1); - *ptr += len; -} diff --git a/firmware/cl-step-controller/src/osap/ts.h b/firmware/cl-step-controller/src/osap/ts.h deleted file mode 100644 index 27c57cc6c72695478381e9694c4e3c7a34361eaa..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/osap/ts.h +++ /dev/null @@ -1,106 +0,0 @@ -/* -osap/ts.h - -typeset / keys / writing / reading - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#include <arduino.h> - -// -------------------------------------------------------- Routing (Packet) Keys - -#define PK_PPACK 77 -#define PK_PTR 88 -#define PK_DEST 99 -#define PK_LLERR 44 -#define PK_PORTF_KEY 11 -#define PK_PORTF_INC 3 -#define PK_BUSF_KEY 12 -#define PK_BUSF_INC 5 -#define PK_BUSB_KEY 14 -#define PK_BUSB_INC 5 - -// -------------------------------------------------------- Destination Keys (arrival layer) - -#define DK_APP 100 // application codes, go to -> main -#define DK_PINGREQ 101 // ping request -#define DK_PINGRES 102 // ping reply -#define DK_RREQ 111 // read request -#define DK_RRES 112 // read response -#define DK_WREQ 113 // write request -#define DK_WRES 114 // write response - -// -------------------------------------------------------- Application Keys - -#define AK_OK 100 -#define AK_ERR 200 -#define AK_GOTOPOS 101 // goto pos -#define AK_SETPOS 102 // set position to xyz -#define AK_SETCURRENT 103 // set currents xyz -#define AK_SETRPM 105 // set spindle -#define AK_QUERYMOVING 111 // is moving? -#define AK_QUERYPOS 112 // get current pos -#define AK_QUERYQUEUELEN 113 // current queue len? - -#define AK_RUNCALIB 121 -#define AK_READCALIB 122 -#define AK_SET_TC 123 -#define AK_READ_MAG 124 -#define AK_READ_DIAG 125 - -// -------------------------------------------------------- MVC Endpoints - -#define EP_ERRKEY 150 -#define EP_ERRKEY_QUERYDOWN 151 -#define EP_ERRKEY_EMPTY 153 -#define EP_ERRKEY_UNCLEAR 154 - -#define EP_NAME 171 -#define EP_DESCRIPTION 172 - -#define EP_NUMVPORTS 181 -#define EP_VPORT 182 -#define EP_PORTTYPEKEY 183 -#define EP_MAXSEGLENGTH 184 -#define EP_PORTSTATUS 185 -#define EP_PORTBUFSPACE 186 -#define EP_PORTBUFSIZE 187 - -#define EP_NUMVMODULES 201 -#define EP_VMODULE 202 - -#define EP_NUMINPUTS 211 -#define EP_INPUT 212 - -#define EP_NUMOUTPUTS 221 -#define EP_OUTPUT 222 - -#define EP_TYPE 231 -#define EP_VALUE 232 -#define EP_STATUS 233 - -#define EP_NUMROUES 243 -#define EP_ROUTE 235 - -// ... etc, later - -// -------------------------------------------------------- Reading and Writing - -void ts_writeBoolean(boolean val, unsigned char *buf, uint16_t *ptr); - -void ts_readUint16(uint16_t *val, uint8_t *buf, uint16_t *ptr); - -void ts_writeUint16(uint16_t val, unsigned char *buf, uint16_t *ptr); - -void ts_writeUint32(uint32_t val, unsigned char *buf, uint16_t *ptr); - -void ts_writeFloat32(float val, volatile unsigned char *buf, uint16_t *ptr); - -void ts_writeString(String val, unsigned char *buf, uint16_t *ptr); diff --git a/firmware/cl-step-controller/src/osap/vport.cpp b/firmware/cl-step-controller/src/osap/vport.cpp deleted file mode 100644 index e064991454d718657dbc30027b4d6b0f9c8b7d8f..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/osap/vport.cpp +++ /dev/null @@ -1,40 +0,0 @@ -/* -osap/vport.cpp - -virtual port, p2p - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#include "vport.h" - -VPort::VPort(String vPortName){ - name = vPortName; -} - -void VPort::setRecipRxBufSpace(uint16_t len){ - _recipRxBufSpace = len; -} - -void VPort::decrimentRecipBufSpace(void){ - if(_recipRxBufSpace < 1){ - _recipRxBufSpace = 0; - } else { - _recipRxBufSpace --; - } - lastTxTime = millis(); -} - -boolean VPort::cts(void){ - if(_recipRxBufSpace > 0 && status){ - return true; - } else { - return false; - } -} diff --git a/firmware/cl-step-controller/src/osap/vport.h b/firmware/cl-step-controller/src/osap/vport.h deleted file mode 100644 index b705e91a150ff544b2efa0ceba17f4f6b3b515eb..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/osap/vport.h +++ /dev/null @@ -1,52 +0,0 @@ -/* -osap/vport.h - -virtual port, p2p - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#ifndef VPORT_H_ -#define VPORT_H_ - -#include <arduino.h> -#include "./utils/syserror.h" - -class VPort { -private: - uint16_t _recipRxBufSpace = 1; -public: - VPort(String vPortName); - String name; - String description = "undescribed vport"; - uint8_t portTypeKey = PK_PORTF_KEY; - uint16_t maxSegLength = 0; - virtual void init(void) = 0; - virtual void loop(void) = 0; - // keepalive log - uint16_t lastRXBufferSpaceTransmitted = 0; - uint16_t rxSinceTx = 0; // debugging: count packets received since last spaces txd - unsigned long lastTxTime = 0; - // handling incoming frames, - virtual void getPacket(uint8_t** pck, uint16_t* pl, uint8_t* pwp, unsigned long* pat) = 0; - // *be sure* that getPacket sets pl to zero if no packet emerges, - // consider making boolean return, true if packet? - virtual void clearPacket(uint8_t pwp) = 0; - virtual uint16_t getBufSpace(void) = 0; - virtual uint16_t getBufSize(void) = 0; - // dish outgoing frames, and check if open to send them? - boolean status = false; // open / closed-ness -> OSAP can set, VP can set. - virtual boolean cts(void); // is a connection established & is the reciprocal buffer nonzero? - virtual void sendPacket(uint8_t* pck, uint16_t pl) = 0; // take this frame, copying out of the buffer I pass you - // internal state, - void setRecipRxBufSpace(uint16_t len); - void decrimentRecipBufSpace(void); -}; - -#endif diff --git a/firmware/cl-step-controller/src/osap/vport_usbserial.cpp b/firmware/cl-step-controller/src/osap/vport_usbserial.cpp deleted file mode 100644 index ddbc9fd308439d946194f2a75364b4613bb1f2a4..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/osap/vport_usbserial.cpp +++ /dev/null @@ -1,141 +0,0 @@ -/* -osap/vport.cpp - -virtual port, p2p - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#include "vport_usbserial.h" - -VPort_USBSerial::VPort_USBSerial() -:VPort("usb serial"){ - description = "vport wrap on arduino Serial object"; - // ok, just calls super-constructor -} - -void VPort_USBSerial::init(void){ - // set frame lengths to zero, - for(uint8_t i = 0; i < VPUSB_NUM_SPACES; i ++){ - _pl[i] = 0; - } - Serial.begin(9600); -} - -void VPort_USBSerial::loop(void){ - while(Serial.available()){ - _encodedPacket[_pwp][_bwp] = Serial.read(); - if(_encodedPacket[_pwp][_bwp] == 0){ - rxSinceTx ++; - // sysError(String(getBufSpace()) + " " + String(_bwp)); - // indicate we recv'd zero - // CLKLIGHT_TOGGLE; - // decode from rx-ing frame to interface frame, - status = true; // re-assert open whenever received packet incoming - size_t dcl = cobsDecode(_encodedPacket[_pwp], _bwp, _packet[_pwp]); - _pl[_pwp] = dcl; // this frame now available, has this length, - _packetArrivalTimes[_pwp] = millis(); // time this thing arrived - // reset byte write pointer - _bwp = 0; - // find next empty frame, that's new frame write pointer - boolean set = false; - for(uint8_t i = 0; i <= VPUSB_NUM_SPACES; i ++){ - _pwp ++; - if(_pwp >= VPUSB_NUM_SPACES){ _pwp = 0; } - if(_pl[_pwp] == 0){ // if this frame-write-ptr hasn't been set to occupied, - set = true; - break; // this _pwp is next empty frame, - } - } - if(!set){ - sysError("no empty slot for serial read, protocol error!"); - uint16_t apparentSpace = getBufSpace(); - sysError("reads: " + String(apparentSpace)); - sysError("last txd recip: " + String(lastRXBufferSpaceTransmitted)); - sysError("rxd since last tx: " + String(rxSinceTx)); - sysError(String(_pl[0])); - sysError(String(_pl[1])); - sysError(String(_pl[2])); - sysError(String(_pl[3])); - sysError(String(_pl[4])); - sysError(String(_pl[5])); - sysError(String(_pl[6])); - sysError(String(_pl[7])); - sysError(String(_pl[8])); - delay(5000); - } - } else { - _bwp ++; - } - } -} - -void VPort_USBSerial::getPacket(uint8_t **pck, uint16_t *pl, uint8_t *pwp, unsigned long* pat){ - uint8_t p = _lastPacket; // the last one we delivered, - boolean retrieved = false; - for(uint8_t i = 0; i <= VPUSB_NUM_SPACES; i ++){ - p ++; - if(p >= VPUSB_NUM_SPACES) { p = 0; } - if(_pl[p] > 0){ // this is an occupied packet, deliver that - *pck = _packet[p]; // same, is this passing the ptr, yeah? - *pl = _pl[p]; // I *think* this is how we do this in c? - *pwp = p; // packet write pointer ? the indice of the packet, to clear - *pat = _packetArrivalTimes[p]; - _lastPacket = p; - retrieved = true; - break; - } - } - if(!retrieved){ - *pl = 0; - } -} - -void VPort_USBSerial::clearPacket(uint8_t pwp){ - // frame consumed, clear to write-in, - //sysError("clear " + String(pwp)); - _pl[pwp] = 0; - _packetArrivalTimes[pwp] = 0; -} - -uint16_t VPort_USBSerial::getBufSize(void){ - return VPUSB_NUM_SPACES; -} - -uint16_t VPort_USBSerial::getBufSpace(void){ - uint16_t sum = 0; - // any zero-length frame is not full, - for(uint16_t i = 0; i < VPUSB_NUM_SPACES; i++){ - if(_pl[i] == 0){ - sum ++; - } - } - // but one is being written into, - //if(_bwp > 0){ - sum --; - //} - // if we're very full this might wrap / invert, so - if(sum > VPUSB_NUM_SPACES){ - sum = 0; - } - // arrivaderci - return sum; -} - -void VPort_USBSerial::sendPacket(uint8_t *pck, uint16_t pl){ - size_t encLen = cobsEncode(pck, pl, _encodedOut); - if(Serial.availableForWrite()){ - //DEBUG1PIN_ON; - Serial.write(_encodedOut, encLen); - Serial.flush(); - //DEBUG1PIN_OFF; - } else { - sysError("NOT AVAILABLE"); - } -} diff --git a/firmware/cl-step-controller/src/osap/vport_usbserial.h b/firmware/cl-step-controller/src/osap/vport_usbserial.h deleted file mode 100644 index 4a72d1ce9462ca8bf4ee76992d56c62a8a54a0cf..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/osap/vport_usbserial.h +++ /dev/null @@ -1,57 +0,0 @@ -/* -osap/vport_usbserial.h - -virtual port, p2p - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#ifndef VPORT_USBSERIAL_H_ -#define VPORT_USBSERIAL_H_ - -#include <arduino.h> -#include "vport.h" -#include "./utils/cobs.h" -#include "./drivers/indicators.h" - -#define VPUSB_NUM_SPACES 64 -#define VPUSB_SPACE_SIZE 1028 - -class VPort_USBSerial : public VPort { -private: - // unfortunately, looks like we need to write-in to temp, - // and decode out of that - uint8_t _encodedPacket[VPUSB_NUM_SPACES][VPUSB_SPACE_SIZE]; - uint8_t _packet[VPUSB_NUM_SPACES][VPUSB_SPACE_SIZE]; - volatile uint16_t _pl[VPUSB_NUM_SPACES]; - unsigned long _packetArrivalTimes[VPUSB_NUM_SPACES]; - uint8_t _pwp = 0; // packet write pointer, - uint16_t _bwp = 0; // byte write pointer, - uint8_t _lastPacket = 0; // last packet written into - // outgoing cobs-copy-in, - uint8_t _encodedOut[VPUSB_SPACE_SIZE]; - // this is just for debug, - uint8_t _ringPacket[VPUSB_SPACE_SIZE]; -public: - VPort_USBSerial(); - // props - uint16_t maxSegLength = VPUSB_SPACE_SIZE - 6; - // code - void init(void); - void loop(void); - // handle incoming frames - void getPacket(uint8_t** pck, uint16_t* pl, uint8_t* pwp, unsigned long* pat); - void clearPacket(uint8_t pwp); - uint16_t getBufSize(void); - uint16_t getBufSpace(void); - // dish outgoing frames, and check if cts - void sendPacket(uint8_t *pck, uint16_t pl); -}; - -#endif diff --git a/firmware/cl-step-controller/src/osape b/firmware/cl-step-controller/src/osape new file mode 160000 index 0000000000000000000000000000000000000000..763c64b623c30fa245ddecc45ac03d1c1c8f5b17 --- /dev/null +++ b/firmware/cl-step-controller/src/osape @@ -0,0 +1 @@ +Subproject commit 763c64b623c30fa245ddecc45ac03d1c1c8f5b17 diff --git a/firmware/cl-step-controller/src/utils/FlashStorage.cpp b/firmware/cl-step-controller/src/utils/FlashStorage.cpp index 24411c93e7d1be3b51ebadbe362bc952c0b3a21e..b7b13eb229cafc369f53dcaae2268d561199621d 100644 --- a/firmware/cl-step-controller/src/utils/FlashStorage.cpp +++ b/firmware/cl-step-controller/src/utils/FlashStorage.cpp @@ -18,7 +18,7 @@ */ #include "FlashStorage.h" -#include "syserror.h" +#include "../osape/utils/syserror.h" static const uint32_t pageSizes[] = { 8, 16, 32, 64, 128, 256, 512, 1024 }; diff --git a/firmware/cl-step-controller/src/utils/clocks_d51_module.cpp b/firmware/cl-step-controller/src/utils/clocks_d51_module.cpp deleted file mode 100644 index 6c4422162a01869d5b360af487756733a3f12995..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/utils/clocks_d51_module.cpp +++ /dev/null @@ -1,151 +0,0 @@ -/* -utils/clocks_d51_module.cpp - -clock utilities for the D51 as moduuularized, adhoc! -i.e. xtals present on module board or otherwise - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo -projects. Copyright is retained and must be preserved. The work is provided as -is; no warranty is provided, and users accept all liability. -*/ - -#include "clocks_d51_module.h" - -D51_Clock_Boss* D51_Clock_Boss::instance = 0; - -D51_Clock_Boss* D51_Clock_Boss::getInstance(void){ - if(instance == 0){ - instance = new D51_Clock_Boss(); - } - return instance; -} - -D51_Clock_Boss* d51_clock_boss = D51_Clock_Boss::getInstance(); - -D51_Clock_Boss::D51_Clock_Boss(){} - -void D51_Clock_Boss::setup_16mhz_xtal(void){ - if(mhz_xtal_is_setup) return; // already done, - // let's make a clock w/ that xtal: - OSCCTRL->XOSCCTRL[0].bit.RUNSTDBY = 0; - OSCCTRL->XOSCCTRL[0].bit.XTALEN = 1; - // set oscillator current.. - OSCCTRL->XOSCCTRL[0].reg |= OSCCTRL_XOSCCTRL_IMULT(4) | OSCCTRL_XOSCCTRL_IPTAT(3); - OSCCTRL->XOSCCTRL[0].reg |= OSCCTRL_XOSCCTRL_STARTUP(5); - OSCCTRL->XOSCCTRL[0].bit.ENALC = 1; - OSCCTRL->XOSCCTRL[0].bit.ENABLE = 1; - // make the peripheral clock available on this ch - GCLK->GENCTRL[MHZ_XTAL_GCLK_NUM].reg = GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_XOSC0) | GCLK_GENCTRL_GENEN; // GCLK_GENCTRL_SRC_DFLL - while (GCLK->SYNCBUSY.reg & GCLK_SYNCBUSY_GENCTRL(MHZ_XTAL_GCLK_NUM)){ - //DEBUG2PIN_TOGGLE; - }; - mhz_xtal_is_setup = true; -} - -void D51_Clock_Boss::start_100kHz_ticker_tc0(void){ - setup_16mhz_xtal(); - // ok - TC0->COUNT32.CTRLA.bit.ENABLE = 0; - TC1->COUNT32.CTRLA.bit.ENABLE = 0; - // unmask clocks - MCLK->APBAMASK.reg |= MCLK_APBAMASK_TC0 | MCLK_APBAMASK_TC1; - // ok, clock to these channels... - GCLK->PCHCTRL[TC0_GCLK_ID].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(d51_clock_boss->mhz_xtal_gclk_num); - GCLK->PCHCTRL[TC1_GCLK_ID].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(d51_clock_boss->mhz_xtal_gclk_num); - // turn them ooon... - TC0->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_PRESCSYNC_PRESC | TC_CTRLA_PRESCALER_DIV2 | TC_CTRLA_CAPTEN0; - TC1->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_PRESCSYNC_PRESC | TC_CTRLA_PRESCALER_DIV2 | TC_CTRLA_CAPTEN0; - // going to set this up to count at some time, we will tune - // that freq. with - TC0->COUNT32.WAVE.reg = TC_WAVE_WAVEGEN_MFRQ; - TC1->COUNT32.WAVE.reg = TC_WAVE_WAVEGEN_MFRQ; - // allow interrupt to trigger on this event (overflow) - TC0->COUNT32.INTENSET.bit.MC0 = 1; - TC0->COUNT32.INTENSET.bit.MC1 = 1; - // set the period, - while (TC0->COUNT32.SYNCBUSY.bit.CC0); - TC0->COUNT32.CC[0].reg = 80; // at DIV2, 240 for 10us ('realtime') (with - // DFLL), 80 for 10us (with XTAL 16MHZ) - // 400 for 50us, - // enable, sync for enable write - while (TC0->COUNT32.SYNCBUSY.bit.ENABLE); - TC0->COUNT32.CTRLA.bit.ENABLE = 1; - while (TC0->COUNT32.SYNCBUSY.bit.ENABLE); - TC1->COUNT32.CTRLA.bit.ENABLE = 1; - // enable the IRQ - NVIC_EnableIRQ(TC0_IRQn); -} - -void D51_Clock_Boss::start_50kHz_ticker_tc0(void){ - setup_16mhz_xtal(); - // ok - TC0->COUNT32.CTRLA.bit.ENABLE = 0; - TC1->COUNT32.CTRLA.bit.ENABLE = 0; - // unmask clocks - MCLK->APBAMASK.reg |= MCLK_APBAMASK_TC0 | MCLK_APBAMASK_TC1; - // ok, clock to these channels... - GCLK->PCHCTRL[TC0_GCLK_ID].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(d51_clock_boss->mhz_xtal_gclk_num); - GCLK->PCHCTRL[TC1_GCLK_ID].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(d51_clock_boss->mhz_xtal_gclk_num); - // turn them ooon... - TC0->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_PRESCSYNC_PRESC | TC_CTRLA_PRESCALER_DIV2 | TC_CTRLA_CAPTEN0; - TC1->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_PRESCSYNC_PRESC | TC_CTRLA_PRESCALER_DIV2 | TC_CTRLA_CAPTEN0; - // going to set this up to count at some time, we will tune - // that freq. with - TC0->COUNT32.WAVE.reg = TC_WAVE_WAVEGEN_MFRQ; - TC1->COUNT32.WAVE.reg = TC_WAVE_WAVEGEN_MFRQ; - // allow interrupt to trigger on this event (overflow) - TC0->COUNT32.INTENSET.bit.MC0 = 1; - TC0->COUNT32.INTENSET.bit.MC1 = 1; - // set the period, - while (TC0->COUNT32.SYNCBUSY.bit.CC0); - TC0->COUNT32.CC[0].reg = 400; // at DIV2, 240 for 10us ('realtime') (with - // DFLL), 80 for 10us (with XTAL 16MHZ) - // 400 for 50us, - // enable, sync for enable write - while (TC0->COUNT32.SYNCBUSY.bit.ENABLE); - TC0->COUNT32.CTRLA.bit.ENABLE = 1; - while (TC0->COUNT32.SYNCBUSY.bit.ENABLE); - TC1->COUNT32.CTRLA.bit.ENABLE = 1; - // enable the IRQ - NVIC_EnableIRQ(TC0_IRQn); - // and set the priority level - NVIC_SetPriority(TC0_IRQn, 2); -} - -void D51_Clock_Boss::start_100kHz_ticker_tc2(void){ - setup_16mhz_xtal(); - // ok - TC2->COUNT32.CTRLA.bit.ENABLE = 0; - TC3->COUNT32.CTRLA.bit.ENABLE = 0; - // unmask clocks - MCLK->APBBMASK.reg |= MCLK_APBBMASK_TC2 | MCLK_APBBMASK_TC3; - // ok, clock to these channels... - GCLK->PCHCTRL[TC2_GCLK_ID].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(d51_clock_boss->mhz_xtal_gclk_num); - GCLK->PCHCTRL[TC3_GCLK_ID].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(d51_clock_boss->mhz_xtal_gclk_num); - // turn them ooon... - TC2->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_PRESCSYNC_PRESC | TC_CTRLA_PRESCALER_DIV2 | TC_CTRLA_CAPTEN0; - TC3->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_PRESCSYNC_PRESC | TC_CTRLA_PRESCALER_DIV2 | TC_CTRLA_CAPTEN0; - // going to set this up to count at some time, we will tune - // that freq. with - TC2->COUNT32.WAVE.reg = TC_WAVE_WAVEGEN_MFRQ; - TC3->COUNT32.WAVE.reg = TC_WAVE_WAVEGEN_MFRQ; - // allow interrupt to trigger on this event (overflow) - TC2->COUNT32.INTENSET.bit.MC0 = 1; - TC2->COUNT32.INTENSET.bit.MC1 = 1; - // set the period, - while (TC2->COUNT32.SYNCBUSY.bit.CC0); - TC2->COUNT32.CC[0].reg = 80; // at DIV2, 240 for 10us ('realtime') (with - // DFLL), 80 for 10us (with XTAL 16MHZ) - // 400 for 50us, - // enable, sync for enable write - while (TC2->COUNT32.SYNCBUSY.bit.ENABLE); - TC2->COUNT32.CTRLA.bit.ENABLE = 1; - while (TC2->COUNT32.SYNCBUSY.bit.ENABLE); - TC3->COUNT32.CTRLA.bit.ENABLE = 1; - // enable the IRQ - NVIC_EnableIRQ(TC2_IRQn); -} \ No newline at end of file diff --git a/firmware/cl-step-controller/src/utils/clocks_d51_module.h b/firmware/cl-step-controller/src/utils/clocks_d51_module.h deleted file mode 100644 index 2e0fcd8b4cc9eb67e5135c400b08f23c40777b1c..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/utils/clocks_d51_module.h +++ /dev/null @@ -1,44 +0,0 @@ -/* -utils/clocks_d51_module.h - -clock utilities for the D51 as moduuularized, adhoc! -i.e. xtals present on module board or otherwise - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo -projects. Copyright is retained and must be preserved. The work is provided as -is; no warranty is provided, and users accept all liability. -*/ - -#ifndef CLOCKS_D51_MODULE_H_ -#define CLOCKS_D51_MODULE_H_ - -#include <Arduino.h> - -#include "../drivers/indicators.h" - -#define MHZ_XTAL_GCLK_NUM 9 - -class D51_Clock_Boss { - private: - static D51_Clock_Boss* instance; - public: - D51_Clock_Boss(); - static D51_Clock_Boss* getInstance(void); - // xtal - volatile boolean mhz_xtal_is_setup = false; - uint32_t mhz_xtal_gclk_num = 9; - void setup_16mhz_xtal(void); - // builds 100kHz clock on TC0 or TC2 - // todo: tell these fns a frequency, - void start_100kHz_ticker_tc0(void); - void start_50kHz_ticker_tc0(void); - void start_100kHz_ticker_tc2(void); -}; - -extern D51_Clock_Boss* d51_clock_boss; - -#endif \ No newline at end of file diff --git a/firmware/cl-step-controller/src/utils/cobs.cpp b/firmware/cl-step-controller/src/utils/cobs.cpp deleted file mode 100644 index a2d73787ba6f2626405e92aa1f72dc6da8ea43d5..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/utils/cobs.cpp +++ /dev/null @@ -1,60 +0,0 @@ -/* -utils/cobs.cpp - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#include "cobs.h" -// str8 crib from -// https://en.wikipedia.org/wiki/Consistent_Overhead_Byte_Stuffing - -#define StartBlock() (code_ptr = dst++, code = 1) -#define FinishBlock() (*code_ptr = code) - -size_t cobsEncode(uint8_t *ptr, size_t length, uint8_t *dst){ - const uint8_t *start = dst, *end = ptr + length; - uint8_t code, *code_ptr; /* Where to insert the leading count */ - - StartBlock(); - while (ptr < end) { - if (code != 0xFF) { - uint8_t c = *ptr++; - if (c != 0) { - *dst++ = c; - code++; - continue; - } - } - FinishBlock(); - StartBlock(); - } - FinishBlock(); - // write the actual zero, - *dst++ = 0; - return dst - start; -} - -size_t cobsDecode(uint8_t *ptr, size_t length, uint8_t *dst) -{ - const uint8_t *start = dst, *end = ptr + length; - uint8_t code = 0xFF, copy = 0; - - for (; ptr < end; copy--) { - if (copy != 0) { - *dst++ = *ptr++; - } else { - if (code != 0xFF) - *dst++ = 0; - copy = code = *ptr++; - if (code == 0) - break; /* Source length too long */ - } - } - return dst - start; -} diff --git a/firmware/cl-step-controller/src/utils/cobs.h b/firmware/cl-step-controller/src/utils/cobs.h deleted file mode 100644 index a9e587463dc4cfc6f8175d0ff48b53174970133c..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/utils/cobs.h +++ /dev/null @@ -1,24 +0,0 @@ -/* -utils/cobs.h - -consistent overhead byte stuffing implementation - -Jake Read at the Center for Bits and Atoms -(c) Massachusetts Institute of Technology 2019 - -This work may be reproduced, modified, distributed, performed, and -displayed for any purpose, but must acknowledge the squidworks and ponyo projects. -Copyright is retained and must be preserved. The work is provided as is; -no warranty is provided, and users accept all liability. -*/ - -#ifndef UTIL_COBS_H_ -#define UTIL_COBS_H_ - -#include <arduino.h> - -size_t cobsEncode(uint8_t *src, size_t len, uint8_t *dest); - -size_t cobsDecode(uint8_t *src, size_t len, uint8_t *dest); - -#endif diff --git a/firmware/cl-step-controller/src/utils/syserror.cpp b/firmware/cl-step-controller/src/utils/syserror.cpp deleted file mode 100644 index a2473fe296a6744d233b39d217bfef523aa6f776..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/utils/syserror.cpp +++ /dev/null @@ -1,38 +0,0 @@ -#include "syserror.h" - -uint8_t errBuf[1028]; -uint8_t errEncoded[1028]; - -/* -boolean writeString(unsigned char* dest, uint16_t* dptr, String msg){ - uint16_t len = msg.length(); - dest[(*dptr) ++] = TS_STRING_KEY; - writeLenBytes(dest, dptr, len); - msg.getBytes(dest, len + 1); - return true; -} - -boolean writeLenBytes(unsigned char* dest, uint16_t* dptr, uint16_t len){ - dest[(*dptr) ++] = len; - dest[(*dptr) ++] = (len >> 8) & 255; - return true; -} -*/ - -// config-your-own-ll-escape-hatch -void sysError(String msg){ - // whatever you want, - //ERRLIGHT_ON; - uint32_t len = msg.length(); - errBuf[0] = PK_LLERR; // the ll-errmsg-key - errBuf[1] = len & 255; - errBuf[2] = (len >> 8) & 255; - errBuf[3] = (len >> 16) & 255; - errBuf[4] = (len >> 24) & 255; - msg.getBytes(&errBuf[5], len + 1); - size_t ecl = cobsEncode(errBuf, len + 5, errEncoded); - if(Serial.availableForWrite() > (int64_t)ecl){ - Serial.write(errEncoded, ecl); - Serial.flush(); - } -} diff --git a/firmware/cl-step-controller/src/utils/syserror.h b/firmware/cl-step-controller/src/utils/syserror.h deleted file mode 100644 index b421cc2a08eb1d482a9f298ed9dbefaa90531f9d..0000000000000000000000000000000000000000 --- a/firmware/cl-step-controller/src/utils/syserror.h +++ /dev/null @@ -1,11 +0,0 @@ -#ifndef SYSERROR_H_ -#define SYSERROR_H_ - -#include <arduino.h> -#include "./drivers/indicators.h" -#include "./utils/cobs.h" -#include "./osap/ts.h" - -void sysError(String msg); - -#endif diff --git a/log/2021-02-15_heavy-alpha-0-01.png b/log/2021-02-15_heavy-alpha-0-01.png new file mode 100644 index 0000000000000000000000000000000000000000..12d8b5110cc775093d06e96b12dbd32a16da738c Binary files /dev/null and b/log/2021-02-15_heavy-alpha-0-01.png differ diff --git a/log/cl-step-control-log.md b/log/cl-step-control-log.md index ca800e55c0f761af34e4347ef9485fdd11394b64..fefc9aaf37acf9734ce4d773f7bf1820ec06e8b9 100644 --- a/log/cl-step-control-log.md +++ b/log/cl-step-control-log.md @@ -1239,4 +1239,31 @@ I want to try this, but always want to take the underlying encoder reading back OK, my new theory is that something is *up* with the volatile vals in here. -Confused, IDK what is up. Another day. \ No newline at end of file +Confused, IDK what is up. Another day. + +## 2021 02 14 + +Long haitus on this work but I am back because I want to bring it home for good position control. + +I have changed a lot of the OSAP internals since working on this, so I'll bring it up to date with OSAP submodules to start. + +I'm adding an on-query call in embedded osap... + +I think my diagnostics register reading might be off... things seem to vary way too much. Again, I think maybe the CPOL is off or something? + +I should check against position readings. Sorted those, seems like it *should* be set up as CPHA = 1, CPOL = 0, but I still have some mysterious diagnostics readings. Whatever, I am going to proceed as planned. + +OK, I'm pulling back a full spec / object - and yeah, big / compound typing is really really critical for these things - and I just need now to bring calibration back online, then I can get to noise-bughunting. + +So I'm pulling back data now: encoder reading, an angle measurement (from the LUT) and then a filtered value ... I absolutely pinched the filter: alpha is 0.01, but this actually works really well. Here's the encoder reading up top (where I have this terrible noise... I figure a bit is going missing at some place, idk - it's an odd pattern), the measured angle beneath, and filtered finally below. This is picking out really nice variations between 320.22 deg to 320.170 - and it feels fast enough (even with the big filter) to control with. So I'll try to start with this as a reference signal. + + + +I should eventually try to delete these spurious signals, but... I can approach that later. + +### Position PID + +- write & plot a derivative term +- scratch a PD controller for angular position +- attempt to tune, visualize output effort +- remote-set PID terms \ No newline at end of file