From 0bba9053e8bd7b1b44d8af43815bcb3efe01a559 Mon Sep 17 00:00:00 2001
From: Jake Read <jake.read@cba.mit.edu>
Date: Mon, 15 Feb 2021 17:14:12 -0500
Subject: [PATCH] osape -> firmware mod, start tuner interface

---
 .gitmodules                                   |   3 +
 controller/client/clStepClient.js             | 276 ++++++
 controller/client/clStepVM.js                 | 217 +++++
 controller/client/clankClient.js              | 808 ------------------
 controller/client/clankVirtualMachine.js      | 430 ----------
 controller/client/index.html                  |   4 +-
 controller/osapjs                             |   2 +-
 firmware/cl-step-controller/src/config.h      |   7 +
 .../cl-step-controller/src/drivers/dacs.h     |   2 +-
 .../src/drivers/dip_ucbus_config.cpp          |  55 --
 .../src/drivers/dip_ucbus_config.h            |  24 -
 .../src/drivers/enc_as5047.cpp                |  35 +-
 .../src/drivers/enc_as5047.h                  |  12 +-
 .../src/drivers/peripheral_nums.h             |  18 -
 .../src/drivers/step_a4950.h                  |   2 +-
 .../src/drivers/step_cl.cpp                   |  35 +-
 .../cl-step-controller/src/drivers/step_cl.h  |   4 +-
 .../src/drivers/ucbus_drop.cpp                | 285 ------
 .../src/drivers/ucbus_drop.h                  | 122 ---
 firmware/cl-step-controller/src/main.cpp      | 236 ++---
 firmware/cl-step-controller/src/osap/osap.cpp | 487 -----------
 firmware/cl-step-controller/src/osap/osap.h   |  60 --
 firmware/cl-step-controller/src/osap/ts.cpp   |  64 --
 firmware/cl-step-controller/src/osap/ts.h     | 106 ---
 .../cl-step-controller/src/osap/vport.cpp     |  40 -
 firmware/cl-step-controller/src/osap/vport.h  |  52 --
 .../src/osap/vport_usbserial.cpp              | 141 ---
 .../src/osap/vport_usbserial.h                |  57 --
 firmware/cl-step-controller/src/osape         |   1 +
 .../src/utils/FlashStorage.cpp                |   2 +-
 .../src/utils/clocks_d51_module.cpp           | 151 ----
 .../src/utils/clocks_d51_module.h             |  44 -
 .../cl-step-controller/src/utils/cobs.cpp     |  60 --
 firmware/cl-step-controller/src/utils/cobs.h  |  24 -
 .../cl-step-controller/src/utils/syserror.cpp |  38 -
 .../cl-step-controller/src/utils/syserror.h   |  11 -
 log/2021-02-15_heavy-alpha-0-01.png           | Bin 0 -> 126826 bytes
 log/cl-step-control-log.md                    |  29 +-
 38 files changed, 714 insertions(+), 3230 deletions(-)
 create mode 100644 controller/client/clStepClient.js
 create mode 100644 controller/client/clStepVM.js
 delete mode 100644 controller/client/clankClient.js
 delete mode 100644 controller/client/clankVirtualMachine.js
 create mode 100644 firmware/cl-step-controller/src/config.h
 delete mode 100644 firmware/cl-step-controller/src/drivers/dip_ucbus_config.cpp
 delete mode 100644 firmware/cl-step-controller/src/drivers/dip_ucbus_config.h
 delete mode 100644 firmware/cl-step-controller/src/drivers/peripheral_nums.h
 delete mode 100644 firmware/cl-step-controller/src/drivers/ucbus_drop.cpp
 delete mode 100644 firmware/cl-step-controller/src/drivers/ucbus_drop.h
 delete mode 100644 firmware/cl-step-controller/src/osap/osap.cpp
 delete mode 100644 firmware/cl-step-controller/src/osap/osap.h
 delete mode 100644 firmware/cl-step-controller/src/osap/ts.cpp
 delete mode 100644 firmware/cl-step-controller/src/osap/ts.h
 delete mode 100644 firmware/cl-step-controller/src/osap/vport.cpp
 delete mode 100644 firmware/cl-step-controller/src/osap/vport.h
 delete mode 100644 firmware/cl-step-controller/src/osap/vport_usbserial.cpp
 delete mode 100644 firmware/cl-step-controller/src/osap/vport_usbserial.h
 create mode 160000 firmware/cl-step-controller/src/osape
 delete mode 100644 firmware/cl-step-controller/src/utils/clocks_d51_module.cpp
 delete mode 100644 firmware/cl-step-controller/src/utils/clocks_d51_module.h
 delete mode 100644 firmware/cl-step-controller/src/utils/cobs.cpp
 delete mode 100644 firmware/cl-step-controller/src/utils/cobs.h
 delete mode 100644 firmware/cl-step-controller/src/utils/syserror.cpp
 delete mode 100644 firmware/cl-step-controller/src/utils/syserror.h
 create mode 100644 log/2021-02-15_heavy-alpha-0-01.png

diff --git a/.gitmodules b/.gitmodules
index 6deb882..fa16f15 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 0000000..711042b
--- /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 0000000..7f2a9c6
--- /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 324f822..0000000
--- 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 45c0328..0000000
--- 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 f5d7dac..b910eba 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 de18301..81cdb84 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 0000000..6682b6d
--- /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 6d09539..15cc2ea 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 e0316b3..0000000
--- 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 44eaa00..0000000
--- 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 790277e..3101dbd 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 49c9aad..b516e4c 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 eed9f18..0000000
--- 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 0cc143a..6b71164 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 3af6ca3..c83fb97 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 fa26bf1..73a1710 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 3053d2a..0000000
--- 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 844645c..0000000
--- 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 cdbdf30..857f62a 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 4b4499c..0000000
--- 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 5242ba0..0000000
--- 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 1a39900..0000000
--- 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 27c57cc..0000000
--- 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 e064991..0000000
--- 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 b705e91..0000000
--- 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 ddbc9fd..0000000
--- 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 4a72d1c..0000000
--- 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 0000000..763c64b
--- /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 24411c9..b7b13eb 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 6c44221..0000000
--- 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 2e0fcd8..0000000
--- 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 a2d7378..0000000
--- 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 a9e5874..0000000
--- 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 a2473fe..0000000
--- 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 b421cc2..0000000
--- 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
GIT binary patch
literal 126826
zcmeAS@N?(olHy`uVBq!ia0y~yV0p*Dz`Bitje&u|=F;1_3=9eko-U3d6?5Lq)$MtF
zV%LUl$+W-)?5PoKUpH+jag1oYGuc)08hd4XO>xBLi~zQ+e4iqP&hA`reu9VdrtYZk
z4IbW$E>2bA&CG0Es;IlR<mxL%@xAgMcjorZ-SK8hY}wP!FAaXy`EOPg?R@3=S7Ygv
zBY%$9|7rj8`~H8ix!3>yz5o9th{%-nws|DjUvWfP?qi2LDpNn+rgaAvafs?y;{1hZ
z8XyuNW3C#^`_=#d2Y=_!`v33$pZx#l{C^3~Ip1ATEkLLjeE)LkzrXM6z0ZJ@p7{Uo
z{eLM!>Q8a`;52T1h0PIJ3=cu=3qM@ZVU5ev>)SpGlw%7Gkmfkv$BOSj{=*hxd!&vz
z-@zsUcBN@gJMOT|lE535a*z73Mo@pnk=2PdqVf}_zrVkq`GB09oZOR#4;Nn8JGJd)
z#rN;u86Y5G=9+(YkN6g_2$Vwv7$&$b+o5eW<@`1Y#udh;@?F`xlb9e<4Zq*4+~jKg
zZ`)B0hq;b-7$Kq#Vjb2D+zRg?JO%~sBeD&w2-8>}@f~35u!hQ>U@Bx!U_2rV<)$?5
zVBWy+h!4u$<Zy>Ef}xNd%8gWb$Dq@&gBikY&=DwS5Ocs|ZN?|xy8lnrU;dh>vGiJn
z{?o7e@lX6;Kfh*!;+ic#ZiHX@_i=5_pTD==uKd-Ex8FZ?-SQ*#zjuHAoGpdo(x{rM
zwNJh-pYs3jH@91_V*dR*`_Iyh6WR5fPh9`5Z+_XYw(|E&@yfUBmoKQgyZ==F{e7q3
zzptONEojjc^}E~mpWN=!lmF@W^Y5Ro%g1}2?q0rr+tS~c^*?<*@V)N$+r3}n?R+b9
z%j+k_@2i`xpa1vx_aN0+t^KEOZ`04;f5ZR0S|f58T>Gh%|99&g>;E5I|NZ&b{^!#7
zBiUPBw$@MTkN-dAef=M$=kwI<|9<<kIsX2Bk*n`c`ODW$*1!L6%KQ8KPtT9HKYe?h
z`n}iwnv34=uK9gqdf4k2yElH7xj!%2=XbxVKU4W{{*$fGPu~|P--!~`uh$&CySem{
z-8a{j>-PNrRdVO}KB50_#rMvr-!pyPtJBBte&7E$_FVZRyH8K^A8AkZzw`HF<iB4*
zo!9@*(Be$AM-JBXx%!{3-JhBDYoq?DdhPgaeWz95?W><s*R|vK<J#{FX8gW!U8FqT
z{^ad_`tzP|UY+BJh(6b4JG%K#bmtmglIasDudkaJU-zm@etrJ-NdEOtw;%NuET11I
zKdnCg-mj=f?@mX@U+I7U^!5C0m)GsIv9URE_^|WBYHi-jA9KQeAZd!BVE)bf?sum8
zITn6@J9$r@X6D}?;Xi-uh`U?<^WWdue?C6l`zK=Aj^DHO@A=Qqo=|p{6_Geox^^!L
zew))h@mYY+owe?J|JI(rRix@awRLggDjlftDF>y>uW72iv-|(Vv%1>3TX)~Tzc!_-
z-h9uOU;6&9M*aV3MRNQ1pWScCD#C^^S>fH9;DS|ep3grLyl>CXKc&XL-)8^$_*?(e
z<<rwD^y9nctG(M-KRsXm_ob}4r`zxE&%O6Mcwb$e_T6dve?ONk+wuF`%dHi&zkZ3z
zuUqZ-%TyR6!EQI38t~}2@(a6f=I{4T`5u4$c-@=)zUrTG`||AmA78%TYx`T<x_h5@
zf4Zz6|K$98`K9v5YyWC~+<U*STL15K|M}VAwEAjo;rF+fvojUn^`SWaf#BV<nhz=v
zvBvs{PwwZJTa%~1-ydb)AB>X09rpeI>09@|KyU50_^0N#pBE`1mn3&JKfV0AdF$6H
zpO*Z6T>bOCeRe^fIuo_Z3u+fr4XYw_#6G=VzyH+w{r|KAMI!CxHQeU3|2Ft)8z^Gi
zU0qrEv*-2e?AMtWkCd=7FlcyzQ}gM=hnsC|Y(#$Pfa;{(;KbP;;3azKTP1Ud<NE8?
z74m1E7r%baarDHh$3C7nPoF;BeE;(6uWOdOPJNm6`ws&H!=_)qL6z2fmd7{O&0yeb
z+`)W<|IxYFO|LA1D`%^|i`!e3YOA}-C;awvb_RwCn(w;&wstemr~=hTtM%r+?czM3
zQnK&CloLYblTRM`W$9%2O6gt9YX8+zCpj1x0;Yg!h`x#=)(0!LX{#|z-f`n1%MJHw
zJ9h8cv!$*tphxFmO4i$*2NN20Bu~*|V7S6@1XR23IdZz}C`*Enxb-ZC-wt<no~*Gu
zFXFT8li6yXohqA4E?u3P&C1a5tO;E4O|Jks+^1<rb1+lkbF~g@<27Nc)2)vxy<=c_
zbv$X~griA`e{Ei|fa|)rN2$A$m<&7v3%5tDee&s3P~E?u>6Z5P{vUpQ&EC0ZPmSA5
z**!;-CRWKAItoPizc%VzZ?Ah-UteF9=kVf3%a8gzem=k6%uID7k3e}|(9#{%A0N4<
z-VYVKU7CFB=l?&S&lgozYUbbD<9KK4k%d-Y{`|S~>*vk``@T8Mxwh>*{{w;5SH14-
zsr(#~SO4Q-dwS{nZ*Cr+fBs2`{&T}DLD&IY%X{wu6)|d>TJK7%PKB1G9X7D}ad&Ur
z`KqYto?&$|)qkxP_smkz-Lx**L@LtW{Y1ZCZOSUXj9<13s(E)QygPN0`S$bYOjBYr
zjI7RYtteiw#&>c|KJ)$i%HRgZQmE;-Ja_Edw{Gf=(^*?`{u{kivih00XwHpu&y!CI
zl`p@rqjch~&fNzS5^R0@_OczBd)G!Gwm*4e#DrrPGB(vsxTklx!x|D(Q>KHHfa_Af
zFlEJFBX{GMbNW}l=Q{l1!InFpKYzZoT-8Tya{B${#<k~NEH6Gh+ASV-$%XyMT**zR
z>aPZ0R-f#t`Y3N}ROVggQayJoC+5O*dw!4Wj}vO$GOVoL-ulrVbju8sKKm;)^>2#`
zH+ZfRDNi+%X;N6>bLVAD^-blxPd>40qwb`d8ss`X{#H@4#QEyW6~+GlJ{;zEukU{+
z#HhA!wN95#aY4t)l%&72X0ZjWtohUv#<W7&>ipIpk*hDOZK<_QZAMN?L0=l<%nO%a
z&gi_(WGN==8L@50il93)r4}~tC}xiR82r@o<u&)v*y_2~p39EL%D#KOY~f^fj*E{k
ztQ7W0USV80FMGFixXH_zDO`{+f~4k2i}=5&b?r9KzbA1s*8BPHlJ#3x_~<CT`}eWG
z{>1)&U)SH+{b$yz7qj0y&==$W`Sp6d{Lka||32oVAG?|rs&RLfQ28>IPj+@SKNO}<
zpZ@9L;r8^GDUYg4-8N0R>v>}@-`!ssyYHk-ooe!F&D)vkd2)PjU;TM_m_7Mt`s00e
zqO0z(-egI=5}tZj-q6Z^gRIx%E!ldz@7;61_BrqOo^Ac!hsz>2`QChbPQ@xULNoNV
z{N<bm^dNDOxhYn@Ov=D@-QR%b*E4FY+3uRM`*!Yr`|@z)BGuKGf4#c8x_SQoef#w0
zl&hUe4x6>N;^U$%)rwt<&Scvx`#i~g(#$>U6gcFrU$`t8yTE&1pm}B8290E?xOuT`
zzA?^%udK4RcK!bM&#rp!(Sr#WEDEQW?sL7i-gcWz`oiGr@0S(Mt6sduw0isX3umj&
zExl?Qc|7m>-_X0lrP}LD_dQeky7`>c`qCZSHaVhXqhAjCTI)~k<BRQk88Ta>+|~X6
z%pZBNl_^;*=gQjcRu|6N>XvY={OxU-g?f+HovB{<=Ids+#epxsN8J1#J8#oA-+6wa
zlCw9ysHqRzrTp%ap{bC2db#`DiL+Dlo=usqV;G=v{`5Ngk|oy-AFW$c6!+v`&wA(Q
z?z3$soxjF$c+=_EiaGPEFZSLq=`;SD9Ca5phu@0G+_l3xEmwLn)4~@kxPtGmzZ_|L
z_2T_^FH%fR_)EJ=tkl=X?bQN>=3>9&d(Nz!5_vzib%)vBx{%06dgtAQD&Mslx%r4n
zx^C%y_ht2>H@m;*EZQu+LG$7o<#(TStm4@>oil&W@kq<;`323@yNkB0e57Y5KDVUT
zeQ|iD|CP0S<PL4SqgC{7-}`LY>sS6<VFmZQ^gnKjHDsKTa-Z35_2s)Ih2>|~t#_4f
zv65w%^~n{Rcx{INVxGeCGf~C6E+<@a<9;GoZngi`d+E^7Z8qM@=YM6lf3oJj`!aer
zlc)N9zNgiZkNh<Mo{O4Se8c?J=AJ4SbKcW_$M06Jc=0zosw-q?clNb@A^SfcoF5;V
zd#+>NuBYx3t5wf$UbklM;?r`1($`P>-nkjE{hg&6Z+Fb*yji!;{onO;c_ySMB?KuE
zzS%z5+!A!rblIsLZAwb7XSi)Y*%mVK+{~A;ikqdTEpvO3(|>A()19TJL7zLU=dyj-
zS91C18^cd;Zq!(%nap@s{^pvZ)z7jQ`*eaWUixL9E#`~-UKV+MQ*7I6Kli!sug|Qy
zpHjHoTFdD546EK46WgGjZ{*EN<_qqAnqwd#q5a%-<>Vd4e|xON=DwbN{`sw7ci$=2
zm+f7i=r*UuMPEjV@tfZp&d>T4wB=#IF_V@>N~>S&oRQ-p`f^UF?mM5dFOO$LF5bpB
z)&6du?=91pG2StHB~llDvwSzav|gj~)5;g+uYH31ZoXY3v-@-G%tM~#PqOC~Ta@HK
z_dKp7^J>9Ov2ruF*)MzCOjR{~I(M%rSu;soKTg8-`li>%7d={c%6DC#=j`MY#%s6v
zNiTWf^ENaq_PcEG@u#tm4wlr0wac%V#f4NuI<Hyx^wAmd_a7HN>#P?$@y5)(=l0B=
z-*cBs#JT@^ywhdoecNg4f-cQ}_w)bVphE{g?`SU2ELUCP9JW}uH+fmszN)XUCR)VJ
zJ9ebTuKv%RpFekgZ0kLjbY|K9&!0X8flIvg`~S^4HQPL2u6$;<=3|*}vFl%&{w=Xq
zTOYT#s_bn3y*($VzSoc2<1r<6E?>r<y;h68zMG!-yd?74i}P2rrfLWupVqi0b58p^
z`^%~M(?K=%*<HaU-5*|EU48sL=iv_<d5)yMJKW9>YEnIu%iQyR-oFnIomXa7toR&R
z_D{1kBI89*+s}vX@^bHgn{>_(vrF3c{<}rrx!QcMpcgga_XHhpzfRm&@lolc&5xhY
z=gY5;d@gg?pyr#*-DgL;#W_D#=gfP*==0)^b6a)9y3;G=?e~ASN$#t>b~JOx@1DNb
z{db?A&)PcaXwt-r|MCBSUEln?cINlAKQUK+%1J-U+uggpH*eRTy1!Ac<#dY97ViE0
z@NoO_&zCCoj%Mzgd){#O{lH~Asy{#T&6*ooDmNY4b9u|nyuz5Dpa0W`4*@Ukc^xjX
zx&4xvErR8dwyM|GCB`z|5^Y9uWlNS$(YQMCW010&$<%$zT~==U($v}VFoNyhuZK7G
zS(wPwDjs~cqoh#$zrEe|jXc)#G?pIWKhqa>`7f*S+Qj5dh7+G(Kasr5;l%{gSBrYS
zK7Dmyp^ZlH43oLZW(RLPyYS+?kz0a@?8T7Q9o^P>+dgkQDf6l(?Bm~M?tk7M(_UON
zW0FYflJq~1r=2s7PFJZ6lgnA&`tHRA8|w+PZlo;Dh`e>QWY3zSJ4<$*ZQHSVu3h`O
zojt|3_r|Z55Zvp1wK7I5@^9@CSqDyqcMD?jQZI!rnxcO&>3RL<iCd-$UEO_3!c_d^
z)ySxxh+U;Ad%S+$x!c>b``+WjM!t7+nd7H?S|aXtexLrE%HNO0maJeg-m9HB@9VQu
zc~??;T~;~8+;}kI#KzjZ(&H|cwkA%i{2s0A@(Z<*I#IUIY^GKBZY6t`H*x1zcJBVM
zbIE4A1?Q~7A`Q2_Zcn}@a<~25iBRcB?`BMl+LgNIP3&CXq~vB1=|@?!olmPx34H(N
zo_Xr@gC?uaJ>GOeq}*pKvjKl_>cW_HsV_7G>l98O`9Dqi<F)B87fPJ|+OhZBQQt@P
z7q8CLSh~c1Z}qo-Z*?YYo+h-^=HuUM&t}}cVP14GY*Cc*%=dNAYgE?S-j5WS>*sJ+
ziZ9hXYm?Nf4(l7Lxl26nX->VpTjssrf34(KSH4}j@K!VJcgLa?lQLtxp3e5;t@;^#
zRpjmrXQAaDd+z>P$@4SO>CV)xWr=g<uaDn<&L%9qS8wk7Gr!MxpZ;8Xd1mROx%210
z|GVep%g>ePU*9lFi}rc?P~_;{h1u(z?%dq*tl~=iwZCECS8kmdoci(y^9=Sv_HP%2
z%eOyXr*U=C#TfH<A-}vjgK{O~?w?Zn;JQ+zuzYviZ@;gXuGQQ=@}lqQwF_UbW!`%J
zP0Fr)#iJO$+Wo5^y}Pi&{r2;)@=I20DwA{8KTb`~Dw?)s#il#`ZpyFcnp^bMK6)py
zajWd|o==HRL02CBoKUL&+V1<~b9>gUxpDUMCi8?$rM+?M150P~7Eb@}zFuqn&K`N5
zR|@Z*eXd;h+w}aFA6kx(v7l=ay-OEgnRl_m|4iFFjjNMC<f%T~pq-ol+2Qu?&LdlU
zwwdjVcqd%`amB7HTi=KYZJDZ(uVLJLJ!f~~j`bfWxrNF$IzJCu9@w?abN4-~5|`I~
zoQ2D;Oy0AtkT-H}?c7*P--}z$<zD4sYrb`V`fs;d+2VV*vmF)ReVe@1dDA<~W0esh
zcS0l6O<I>-&90ngSh&=;D#QGP(Wm_KVl(OMHuKLH-(6q1>}WVAWSDD%^PavrlivOK
z@M3*td}q+UANz!!mZn(nsm@`!)Nj6A;vC<)iQB{P`2JorMaVv4S&d(@RK8!1`J`{A
zaqr&GU-ta(uh;80MXlAE{VeqBqa&q?_Y8A)H^;R1W!$}~tM6)F+xebR`uYS_-Bmi@
z*T?P6iecaGr8e2~p;4IV?^hR+UrnB0|8M6N*|vVc^4q(8Z~6UR^LmDlT2$eqm%n#?
zf0UQL&og^xXzSaHDXt!~wIZ)|tlo8o>E^y`Z*MB3+DtDiui9F;xAOW_*E@^{lsl|f
z%(LEk^MuJ&+0$B&e{9_mylBrppT%$gADtb%<>{le|Ibg0l>h(p+`c$*ccaMXM@P9W
z?d|KA=sn-GJF@lkBfV$s@^uqFe=h#{^Z9)3$jfV9zVYf>RHVeglzsX1Bb)o~SGm)a
z-+dD<pOrKJxMJDs&!0aRSAKrh`*qh}f%cZ`NgF-(>c86Yxa`{AHNSbfFFSv~H{VCC
zzp|#T?w*GyYt^2ruUYv&tN#Al8WR_{?4QJJSJ`@vJL|+_YW1GRR$n}pci0Ltc-WlP
znPPX#!`gmA>#_8t!t0*WGs|rS{53Oszx`JVUAANMU4{*w>#tYG+^~z={P^F$xTv*Z
z4`=MYtmfx<$I-6L`j4x%{Q9`Pt5T02Wm|sl<^6T1%NDNFZ+E`TRO-Icw9#hw$>%>6
z8`G6@f>T(sWv46MTqhnQR$ke^{eHQ36J&66)#I>32i;zkFzwuV`FD)YyGgqb-LrpZ
zvHI8Lz4Ps}dUtP;P2c|Gbo{?b+_!nzF8B6tF|pjXajR_iOZyF{^Vpxx*g7{toNLOZ
z*AlXyn^~4@)?XVtDQMsOZ28&C?TR#eA5?U8?A|qPVZ~2@+s^~V?&fX(vS%$5WDGWd
zms_&@diJf#y{pf>+<053X`4o9(~j=)slI>L{ESU~|Nd@P$D7%+3UiVRtf#Hszr(4p
zZ22--<F#8}X|4?L|CamCAvQ$s_oZFyoEGMMy5hckmfHlsS$8@YtqAirdLeZE__p(l
z^%UMQJP<r0JLSC7z0zy^3$7`g(La=S`0wRJe!ueA&Ea?M-am14UtsCSj6L1bi!&2<
zGbT)`<$k6o)_r`gR`;8TowD8MjIPYg+x|P^*yo-#ja3Ub|1d9|Sov*f>AaUqmvcSc
zDD|nYZ`09kaeblhfx+%mj!SR7Vb{MaA$fbEEM!2~@#Y!#*Mh}y^;HGmum3%hdL;~8
z<^29zQQWnzC;Yel{`fmb|9@U0p7;Ki=*g=yg_c^eKNdS!#(Y5K_U`(bd)~eEGnp&A
z!uWRTR6&EYuI_hu*_dBHe<}5Qp5m3?H$ON#nx1+7`PhlwcYm)~d45TR(=EGxtHj;%
z)7c)a`?e<KPG#H#zTP6wO_6VE-%r{0_D8#Ti@CST=LbHw?mgSRciS9R<HeUBzv6ks
z=k>H~)4aY_HXo~*C3!B*IN@7UWApVYf67kT^o^DAKQHmC3HdR-{9R}}Wt-bw;r1hU
zC;#~jZW8pR-uSrXk=Vg+hwq0uEBW6s&%bx#>C>e(KRzs+wwr_LNY3<+%gQD>_}`hh
z|5@kjU%6qcMIZ5H9j>v<_o?i8zpz4b^0GPQQu1~+8|wH<mEyjy_fvQ$b<F4kZ})EA
z(++=59f?)BT<87gqEFbxXM1-~J=3)AN2@!#DfbcCDW}r3UMFsQ_r3PfyMJ--!WZ)F
z&i!aM|MRU_$+nw|_wjY_uHLzS_e9VApC!U8WhGm@cWNuzo~l^T@3#2(+o#(#iw(bq
zt)BXN*X%nDEm@ko-^@zc-IMPxn170cH==omvH$klTZ`n)m%eLAyP#4iF6_T{ORZdL
zQP%m0x#=NS72Zj?)fF!Hocie9GpAc~3r{)yoal4TM)KU-<;6D@-YqCQ)AmU6p2#A-
zDIXpB7ioOmeJVy><9*Uj-|Qc+ie6ow>bCe|^3U1lpYODnpWd(0m0~yF-pp^dg6F1p
zjY=;W%Qh&!i+NKK7Z+!D?|7g{XxRIHH|3e<pKprL@tS!_rfuQZEo*0;OerdnUextG
z`R0AY`RAo~K1+%{_2%#2y*_Hfj|*dSgXK>7-~Ky2R-l~sFl*uVn&<Cj8Fz5pdKwdd
z*5Quh-W^jnyqCNWa^O`1uf;w;3o9#UzTOp^n_{}rF+R-F!tKt~$g*Yyji<K+%ik>s
zZl8JXyxNJEO4m~s-@E_r$}GR@KkT;8-4-hBdhz0+rCopYt6M(T*yTUj8#P@v`E-@o
zu3O9QxZg7?7gc!I_b4pw@xGEh%YDB6S;upDX$!Mz^Xt2h-=~=Jt4fp{t^d=bKKEb5
zvx)c0Uv=$%ebA5bjA3Y*DBsfCbyoYo-E56nt|#`t=I`DgdlvnS`1P-9uhvukr&Z5y
zEn00Hm>#YfoOHeWa{2M?rYCL}Io@$x8`1kz=V@Fi>t+7WdE0k?-+k)GRAaUG8~&=9
z)ojk#8s!%kE_X_(Tuu5{D(4mj4!&tWHM-V3?_WLR-HO*&5|^D0ocVRLuG-|zsa5;W
z_$DP4mS-(`aKq^S+cNE&7g7x*rhI$c6ZGp*-`VU*N51<>o_}yKp&-au&Ta9;um4W#
zb?jc`QY`s%-jC)0v5R+~{k86#X3Tl+TDGmqwX$7u9nXJW;$OCD$6cSzU1CCfw-)^=
zKe=^jkcP>lyj#~r%56EB;`f~MSl0dHPnZ$+xg}F?L>j%_llLU;j_Ces#mlZL<=>?}
zug`tsvw!x<3!j&mSMHk^Y9inHo_Eev_S*{Y7*;udS6sW>@BG3*`;T7^8(DQ!uD|Vi
z&{TpaWowkJAFub}Z<f!N-hTT`$~9uzj@$FBqDy)go=o{<k-EO;rJvRQhTG@P8+Bg3
z?q>P^Yn9t;v$<AhzLc76th=yNP5SG<Z|}A&+i$$@e1C6sZS7r+$m;t2aoab)cwW6X
zPV?vew`KEfrNdTFjfsz+K8<hJ*Pia&Imw;3m+wCRc}DWJ#XZ+cx7GHBE>E57a7R>W
z((A_Zgztwv)Y3DR-+eQjyzsgAhBJ2CVhWeL{A|<-`X}%E`%$IyOj!&4r8X~no>?ou
zREpFKa=YMKyz|AjC0DaLpKm?#{@0~<Jt<|`*7>U$3)ur?ckyT5jn6NwYc;n0^!$Rx
z{@NWkR@{}1E%K?m-m1V+^fWZ`QQmYV*?Vu#)m;2+-EwZ0vEI65vCX=ftNy(^n2_*g
zcj>7GFRQ*tXa<GnbnZ5K|9MBBwOZbunZdy+Yv2ENzaPK&;)*R>&z{<6zWw6g!b3;R
z&TUNjyQB1s#?fHm^7V0hH{Gkh$yylR^1|!fm6<V;(vsVz99ZAHBm4Bxv-^^-T~7M`
zR$wPjO(t*pEo&#ed%P+;c2<A8ch^^8??cnwr^G50-!Xg>wr|;N^<`JD!`)JSAFh@)
znoXHges=HB73;3GpJ97(%SxF<iEBZ3L?_C$zq1#9;UiwYGkK$~+iJb%x1XMKk$S#%
zzi)z7oa_e0cV*=k=DNq%tzX}N?tg@dx$B+W(;F8VKI-*4WwTvt-d3we>u$fjmS)^x
zHSwyQt=pTpxVU*oqz-@d`|5h@Zt7&scaNAqCH+3+m1-t(o`1`-ZFcFK)#6Uy)>4?a
zB`P=bYSNLr56^0*Ia{{gG>5GP$bVn{+-m)7?#%bGkIzkhxQ4AV#t6M1nJ{U`zFt<(
zKdT>_?R$T^#_sy0++EhbFU<-b6?aMUuyq#Ses|(U(k4cE|H-R2U3~WY-{z7VZ*|@!
zZ;Y@p`*YYpXKC?9+f>8%CU@Wd`C1zvwmMYz=-qF77a!jD$1>~_4_ou`>f~~l`-b0R
zg$-w}+jZpflWmvnIGWPGr{0@!dvW)s9sBm(i?;u@Z+^Cj$33H5so=#6x4oXf<%`yD
zt1{O<Kie&~cZ-Z>s?4jtoilywn)FW@CSEqiyYIex{Njz)^}Rm3#qR#fu=ee~cf0VG
ztk>-suU}`seSXcZaC&L(?YC=fu5a9X=aAi_=X>(@>{{QxeXn(i)Z~*ct92(|4YNtR
zQW&%EQSq&HvwgR2esm+WciA1k^4qndvY?5P-6reU7Zr8yep;o>Uav6uXO?%=UC)wg
z-NRvjkKV1hVx;tLTBH73+si%E8}-))8t2VRcDTbB;{K=Mnq}DX#+APtuKzUMamLid
zr^`AxoA2qtkXus}Ext`<oO>+$*7H|d?>;TLyYG)xnPBnl*_*CpvMfJYVrv%PzjMFO
z^=hk1x%%a6S6=zp@2r+2yGwnQMB+Bv++Y9V{QGXk=&xF3<M;dB)vT#tPrH^MJkwSE
z=EUMXsX^P%omZC4^<S;~>2dbNU192PyW$QnyrFjF#kWZYsn?QAV|M#Z_bEIcvRfqY
z_@%Sfp=GzkugaaY`TE~?hSu(TAHQA*xoPt#@BYS%Pki<~JX0q(ohLYzag}mi#A}(=
zmkln>Tvu7Y{(6G`X2ylL6E7TW+hM$Qak%9EE$_1ryqYq9%lWIJcb;0Vzk9Cc%tqyg
zPhHlRFE4*((sVv$*Q-k`h07<4Z7bL6b=RHUks5txDd(b9pKbUn*S(e4xcmL@(kK7R
zW{Ismd`hU?^|6@l<Xxrv&b`>U<Ic@_VXKX!Y`Ev{((Y1HF8uVYyK~#aZ3@?Pja}Vp
z<fG^19+E0=?Rc_kIbV)nq5kUC^D5?UTw_*$zi;=Vs+X5nFZ$_G6Utt={9B%1p}o9k
z_4<l4m2uaZGx;yoSI+3aRsD2<H>h-mdeHOy=ev=--!@4LER&l1@yi3PqjOho(R@6o
zyK8st?4B#3cb<0c*Wceach$7;J5x6*x`n3N`QMu<^11zlke;g>`^;$;ySQ(@zOy*h
zP^#B2>dwtKI<Na?y)E0_diwZ6-X$fsL~p+g{&G)m*0IRzH97a5*0McW`FV5FQKJ*j
zqS`B`v01eESsx6Uv*%~hqPbgbwF1k3)lU2^T3FsC`#(dgd7Ap%?wM=eJ^HR3dDeNS
zMRsS_+>;d>OaEl)#6I=R-*m%g^4`fAmXizbi?6>bxL+(dwOWW}U&Y*sKH}2J@@rG<
zBt4>k3hDUF4Oh9mPycR$+UklcNn0jGUJ%`HpIY3-q<=*AK%I|SM#=Ta)!fUZ<`p*U
z`ajOuT^zS0Fnv{F=rO%&*Q0ms5(C2vr$7I*>C@_r<0r4&GIrg!`)Zct>kl(E+IL?M
zIcjoG=VaKEd)q93ty(eT=G&U*d-Ensv%lzB<+=F9i@>?n7rym}9Dnw6<I~3hGp|kj
zzuS75_|EOGwcfpZ|M}{EwWF~$@65`kn8o&OekBv@7;$X#jg}p^<)*Hf3@YL;{LM<b
zwMkc?{CL6kDFrt~?^kQ_%)3AJV1?Rt&Exm)`YgF$d27a@?9wIn^G?3~8^lyEoSZ%7
z-rv7_WB5(D9-e!#_3Dnve`g+lANgKvcU}G7V|TS=ytd2kfA0BPXTr_gQ(xoLeeGYJ
zsMxCiH!oFej;FPs^?KcO$EsaBIUeyXu=-@OXp@w@Z?yE{6DCd0yxX*n-pzAgrjh#R
z(!TYKvrTo&??*Y7ikDm6pM3SEmer?oSM~-hX|$K%>6tqJYF6o&zdNdZLwz3WI^TIa
zJ1mxU*%6<6D^GoF6H@!M<i*zMhL_yTV_)mM^U2{Ud|`KSqQLIVn3T@;O-JUwYl~?=
zVa$4S$qwU<&V_<}y$5t&|2uoxPPfRnz0SZQ?9Nip<7>{hBu2cb%RS{Lk_qX$GOy_S
zk+`-v=h})H%Q~%tFCThT`uCH`xoy{1XkS`ke09gFpgXCt&-e9(-aUHvTWyI?ooJ-}
zsVjQ}QoNRD-Yj|pa%`k>rBBCiqa$;DJ2&rD&XfA>X7%>eF{RgKH^s_b-D_X1c|9w1
zTW;C3%`D%)@oTwWcR3q1+4ObX9pCv%m7!nu-P)&q=~aes<@Dw6PJgbgJT-Tvyiuvf
z;<YnEuRn_vzwu@Bj~lym-`?45w>fGpmu+x&U&K0Q=whH%&dV<@^qwsL<MxxcIpRNK
z!qk;`oI#VbbDYG2-K6r5n_tw>zcuk@d9JTO`R$*g+-q}7l49cHmp|Lt*}8jkgpOGM
z{o2}E-OoQ`)Fz*NT%EZlY;{a#OxqKyDdnrLYE7JXd(u&t%Ja7w&u+dKGx=g{bLQ^2
z&ARWp>h{0gVs<oXW5t>Nx4(3JeO@h_`YvP3p7XnZ+&ibN_R5BJgHB<2hep@DrSHrB
zE#ElzyP<3O58E>JdyB5Gu72}vbA);Rr+NJ=za{;Vxwki;zxMsc+^M^u9r*=TF|TW8
zEZ}=|uB_66?Q-vawT|7vN0;od4!bj@@}2AYO!2v`UtdR=&+xl_cZ=~v`Qthz@hNlH
z8!h`|%6OMo>6Bf+&G|MfZ%*k)=R{oJT~@nVxa;!2(>l9-z4T|pqkNUr4PU0ha+!|Z
zmk%!4VZH6o)XI0qV}kExugShUp<SuzQdpf#@V}fMnN{4SEBpn^ziAfDpA{j#L967|
zQYCwd9T(!(NW<b_@hY~m$t#j3ckVJf()ZS4`o)b7cdm+Gew0_<yVd5k9@yl|dcJF=
zPwhKr^YdcX)}ZSTtizT(J^SCvf4|P`HPxHDO!Glj1m$0QE5#@1dhuYXefKqMy)ELe
z*&qX64X+#`R2=WfvOjuPVxar3?BwNzx}Wd(#s%MN{W04s?ABYa^_xyldiiNt$Y${(
zee1OX<xi*V-WBUUv1)TyY4qzp?zcyGK^K8(C6?-nr|+xi=Xdx2v)LhSyJgayb18S;
z+Z_F1bxHobs+aY*Jk5s>er{|o&@AsvR^DlK`#;0?=A{=)G;X~tow?|dU%BoSEAt~=
zCWlVHi%@v?iu=*IKc-jLCdW<L^VQ|@k-LVkU+#3c#<w}tN7?Pp&EwDVUih*VrprOc
zO02paYL>dJoL177%y~HA*x|k{Q-qdU8O3EC=~#B@`xK3<)8Y&!8pxbJ5O1GyTYNX~
z>Q<J2-@f;z-uQT}_kTk9@ohVMqP(VDpLj1pp;=aM*><<fO>H5Qv|IvXrIU_#^%z-+
zb?pAtwBvNWucN?;3=^vz(d*yVm>&GLt|#+NU)bvA9o&ZvzQ)wv_n&h(!(`LEV`ev}
zhZ%;hNp9P*`TRG(Ws%=&dfpa;^4DibT4^rYIn^_~GiV=6_uT(y-7kfCg}m3Qy>dtS
z<BA=3B{nX2eWK#)mw!edTs8fx62IuU-S{kY{GNMw(XuHOha**AHg51}+F{Li<nGIc
z9gBr;P1%&v1@0qTD@V-cdBiu1>(MzINIF_T%rN-vJ>|;cxvHy7C;iNu^V1`0cVU|I
z$0?KE-FS0iSFM81q&b^*XdAs<`lgTd(Yk#K?*z)tPF-5rU)F5eVV$AXVGZ>YbM=eP
z-M0(Fr(~VXSSR?oOec1!%hyZGdVQ9zpR(dzMBe<P-%>1AKbs{e=IIxC=V|Pmy<JEK
z2F1SiUm<ox)<pEk+)BvUP@`#B@=J}a=_dDtH!oE8`l_-g+SB5V*X`Rj375_0bhuwt
zy|!uh^xwZ*S#niRNuPQX`KFKOKJU`o-^}>){H^|OJfr;idJib1obNQsbyy#n+q)^`
z`Y+*CtcC2ptnjpx&|Y!YQuXe~hg-9k)v9{^eDpgz(p;t;G@NsMb}&!6fA$mK-;1v7
zyPHt%{zLcaTzUI7wJ-C{_U^E_t<&@NYid@+Jw=^K3h(+ROD?k(bG<BD7;cBtvH;ui
zBH^4T5#>6odmdkZr02T?IwJcyPOs2>a^Pui(UR^Te~iq}onSwt#QEr*#mvSX*0KWS
z9oEvRE7yHh58;MJ@61Pfb_)8iUc_e5!qzv(Hpdz^W-86>Hw!w$pR(}d%!oUsm)xGk
z@*fHIidyXZSZn$Y>mxC4x~g7ZRcs1kF7mDTTeE_{WB20}wny(u9PTK-%bBut*R}Zp
zy6ZZ2D{#!&!FPeZFn!*de|C@HONb0ku5D?)_Uqvd&L_|O-WPA&@!CK5-~OA0VPBWO
z-d}ochxhG5v(^pET{PpHp8iYjDsy=I+_l!>j;y+|SofAqaWY3@YaLN6vJPLzeClNJ
zD{EV$qp=rPmK8Dt>x0(tUOfu(ji#8<yLH#Me69+gc{zD|Buj3fSMZ&qyH6dfw^!b|
z`pw^3mB3e4WfNoOY6hN~Ue10bHcmjyQ=t6#NuJBkTXwA0M~aD~q7R>*Ds`}|^s8O&
z9#$_8nrxq&U~^kkct(Qad#l&%N!bE<p2oguho4_g-0tbqyLV!D?c!IDE>?(}pMSK>
zdtbI>MfD>YMo_%)6|z73%vQ+0?9*aUq;zW^Iz9DuL(!)>zx?=-)|?zSmS5|Brt)v*
z!Ctv%Mp@c{r=}-t{9Cuj(lz|p>gC_3H|l#;UgBQ7Hu<q&$=tQc=0$pf-!qH5zHI%}
z)eKFzKleD^X<YedMfP9LtB<-q6g{<CFvn*3zRS!Y=L>?@3LKnx$M0Hj_*C_}e1&F5
zDdC-+{r$`L{c6<N{#eKCy>|SsgD!_W6>97MPWUSP`sPum^OMgN=p<T9OFZsvYc}iK
z^~LWV?RXf`Hn&1{UwPE*^e2po6Ilw&=bSO9^#hlB&UbEVc$coVUl<i57`HBleahtL
zSIVmtz{{Cb<F;w5Sxh<`a_w-=+fTdv@7%qA`mffM#O-?pbG`PIg|{W1^4t9Vdr^J4
z^5nYbA0wWYrU>Xg)q8ql_tVciPQCW1w>fRUG@QA`Rp`jwLZic9EEPdTKVM<`Vx6m7
z|FvWlx>oEgk`3^i7kvL^BVs|!0jA9hE6$ruC}0Qalzqf^<~i>pKA)%V;8G;KWxDot
z#-~p#zs{9|tX=8^t&&>xEbP#}?^_yMk`+K1R-in=E?=NLLCgMCRK3&I9ZGv*cJe8l
z&qZ3*wje1i+46IHk?hq6F<uOyU}@jM{JBz?#c}1+jc1DQvp+iL7r6=&HGc}8S~b{g
z=LBUHW#}?DPH0-GatRE{n(2OLE}z~NQ0_XxAHI(HMDc8-Fl3kvb<_g?nW=Jx<yJca
zz>c!Va1?`2(*}>AR*hBJ$Av+wwPv{yqoHYs^PNV!)M=GR?!J8B1Wru&T>NWF<TJtY
z<;~n*)kC_qKOLU>n&HzOHKf2ipu*9u0$POjA~=nzKBKckQ@VElXxLNp|DP<ww+|ma
zDDd<1x4v6z;&Xg6Xb}zzG|p>J>3jw?>RNvZuR1FF^WmvdhRVFjpn{PPy!!qsxJJ%i
zx8ru+1EqJX7M?Nc-(f8qvjUW7CdyZ?JN#{@)7Q$l=bNI{A*CF68Ghm_9f#5j5<b|x
z>~LqU+`1`uttMKAZp%1+e;a5)e}{F$s|AKLSPI*BFr&Gsafh{SjOOlA=n{PlV>d*t
zm5PTXD1q|j?b@l^{U9w7<`sNW&7K0~c^$iLlp207umC5K%!^+jK1DM(<j|`qy>m4m
z<>dS3{YY;-lUICX$J~=U?pJm_1ois7r<A<`FGopce;D+x&-R-~29KH}sPNBuc07;y
z`nR3)nNp|yyqFOZbx-l#EBDKwIzRjg`=fVX3YNaP#z|glj{hdSHRqzKTDQUC(T&Fo
zLBUi$=gfwg@*TThX>L9<{pP~nMK4}#>f4d+7s>R!z_m`{ogaVrsl2(+eG5;Ev?s3<
zT3W*?X8nJ5|B|&+R@@8ywPL5c(oQSyZb9$ueLdm+@AYBJ9FkgW->*pabx1bge8gAC
z4$3a4-(8T4z9v|HR@3`|+`1F|NAA9S=yh|gFa-^<^N*fbUgI%go2>B8FZfRB?%3Ba
z@4KAR`CKYqUb?q`HrGqON{C1LlW&<$;Dfa4H?+^&v0Jv>b>+04XHtgw$1jC?h3NbI
z{0~|u@T%{r+53%c;6zkD>rvmu;G-Iw&nUn1<Gv*OsbNR+vZfuz{7_?#W$DN+{nm4=
zI?3#d%gT8z<=UL>v6<Dg*>i5G34Qd~dFAU%=#>5DJ;$Y*jwJ{kk$uGXMH82KklFQ$
z(hoNvv+Mt&uJImU*fQDS*T-ifhi_h%s=T}pv>0ZZ=EgF&A5Sf>34lE=P!25-qb9tY
zzz%O9E;woa^Y8TeOI}y|o6q_l6!-s=>%T2^d1sjm*{>F>n>X&?SH3$rGF4{3Sh?4f
z>(ev0{M}zs+_f#{PR_m65qJJR)vrIv+Ivt1)c9#T`^Vu<D5Tg0S<?Rcb+$S<Q99h2
z$zI4FRr5wW^Z$=9yMO<3m0$gvvVQ)3uj|2&_W!;6>!&I25!n!LmCqO5ZvAZ3F|iZw
z-tBkm#GcoU6<(g%TPiPv>AZWT6g`Uv)RIdywihVB3MnqdmRLVIDEbpAd*Rxz5^@}G
zgKKSf`NXruZ{+^{JYWB;=~%)f8{SnXQ-WR;m%gn~diUnJ<7JJ_XI__ObU(YhF?H{{
z?}fpNcNO_jlIQB0so(V<JKdh%e}DhU{P({<8O5>0RbKk{as8*4uNx)mYo>kwJN?nh
z<>&Xj*+2b!z08j@+wVWA{l9dJocQc|P5Xaen`{2v?q3vFf2xufw(-U9bXwz%=B$Vl
zJ9f{z_wMUDqvgl*HgnusG-cV2?((kQ|8>Xa#io|_nX>dARB@FK>DXO#O6bwLdyra(
z6`ro48T4wSe*V$$=byg4^#(^o{oidr@6Z4Ab^G_Cdv%)m_5MHaysw{}_dCY!&%d`f
zf8VeB?;7`8|LNKM`$7BOZ~pT{Gjsnx*Si1Tp8wiwzyIX)vs=Qi{-5#rkNwH)^V9b$
zzAI|n(fld$#O`yy8gEFo{B*sM^P|S<jalc*b>>AI^OwZf9D4U?*@2B|3k+v0;VRs2
z8w8q!1qW^LHU&uDdC>I-R$@2qSj`-NuWS93iogAzbl?7uzkk~Mz535TZ~mVD6uesd
z{rBEuzrS_Q+5Y=eVL8|9>DwP|zklkz=KP<JYt8R>?6$W%9Um`ek$;2x5#OmayQuyd
zpMPCmemB0@aC%@gxWoAN`{T2kyNu#&_wMJZ2|P79P9j%U8ZtHB+HcC(dvMC9z{VY`
zvz>XMt%FUhh2`LMZF9cus#dD+qgf50+9E^$8t;)<*&m<6YQ7fjZ~6Vt_us$8ll~oF
z{(axyzcE*S>a#zt`*(8kyWjTn_Wyr7dC#|7pME_S|GD_Zt`gJ@J^@<WCx0yodD?kj
z`b5HnV=j4*9zR~WzE0uvTZ`_qzfVoCGniN)<Z(aVKIQKbsnU%X5EJ7(GSxPSOpfGE
zw%gCEI6wucQ}xC?NELlUOu6^b>FAH4@pf_+&$gTEe!O3I^LM#a{Jmc<gX4v>?`%Et
ze&00y|9_WX`&n1{y8GA1y)}O~vt?cnkds5&J%`j>y@S+T{kx-Y+4Xm)4DNhh{qAnB
z&#$@5P0jcA@f=!uN4EOSL~tE#?U!~%)&AXk!Sc|6WjT&_=7RDtV<Efm(bjKCcTc=}
zul#P+f~>;nhd>*(W>3$p{Ciq{=JC3p;QdE$mq#}{-f?_8gZHTM9!-~6a0v{q#;53Z
z?7rMo(r%;hZox|M2++(&>t2Ld-%eT*7-AXvO#qaBO7-gXty;ylB(BoA(jCqDd)`N1
z#aB$A^2_>&?2BMb=Opy*whE{y=CZHde)IkPr@y!FKiz-t-7^tS#vgx-<)65JRerRN
zNuWGH8>xZY058Jf$r@B8JOagm!n;=orf+|=y14T9x20R^YqaO@ue<%{z5mZ&x2rAl
z_xp&K?Emi@w{7>QZ=bL0KK#DC=I@`dx}5z}%=g#c{&_~c@-?XM^Y3>5r{CMxn!f$_
zC%^Kw_Q(7G>OREmudVvKLoM|6+5B&p*DVB11vDQ^n6!v@)zz%4KiVW7ovV{G=`~8_
ze)MjO!d*pv_>jY^1J|U=<LiHV?s~gJp&DFTWxf}=_5Rb}{_~&q{r{BNSpM|n>3`Kf
z|G3}!c>l@!=U$*X!fyY6&s}w|Z#I3l&wL~B8?*&V^T^$eFl!+rJ{{J-D=(OwLWvoL
zcW0V+tY(&)9o!HNRSm80Py!2Ff3D+Gc<0A=L>9Rfc1rBX-OPov-+?yi>};wPD8CRQ
zQ2xyE&Q-=EcTYC%fHcGWBJcFNEnb}JCj9xa#LwbaQ#5x9lrMJ$H<REsU)WEr_wma_
z9$cTFRgf2;25l5RnQ}CC9-m97EccPvy_&&AitqfomtCJ9pbHN$@ODgSYwxR2d7#MD
zdGg0k%nx4fbFy`ZweGAqaP#opA%l`fRu1y;Q5eP$c2GLoUDdfe`I71RO67N_&PpGV
zopGukI#Ph>z(a;@pc<@?$j&&AtdK(=-qRnx3U@zJI{f`_(CN&`pM^btEK5&KiRsvV
zdC^O7HwrpPVAG}a`uT0prd=_IJC3TbmEI3ufLD5leg1rL>YTT=7k&xpl=tnQ>sfHE
z?vLI2yHgW)cy-F2yn2(-P)MhD88bLi9w{x>`59VPH>L93y5MC`obJpO^IZ?>bbveR
z6P}x$6e<76SXo(7F`>P^-D$q6+{cb|bI`6ao(&vF!o8+sd8S)TGvG<JdE?=&8MsRM
zaqP=!$7)n`mmYcjCB;DEO@ZR&+gsj$HoI>=EpfT3m*&UjqkeCogQamw?;N0GrH<gd
zfZ7Rv(yo1-@ySkK&^)g7BSFXpw+9iJ%ZevyDEpO^s(Do!%}K4j?{)0%)-A97x3}+h
zH+oxrQeyVRntKIdo>dnNJiz^=pL=Hds4bo9eq^q+$zJdXLEVlbS%-PIRf6w`&dm~M
zH~6X~_pu{9*5<aTu*~VLJhrN*_)}*7xF5t6-x*XpGwsMsUfaM`+K<<)+<LnF^~JLE
z$xC?l$a;rs2L63{xq9=$3NO#{oU)X=b{P^XprNV-fA$zg$_bX|U4Zt9ka~acVKEKi
z*uwJNa<0#LQ>Td*-x6Q?ZLRP22@BS`Y;`lbe`rznRM=X8J>}N#y6$<{8DB8)5ONKC
zxoE{YS^pz*|Jr0o?R!5x4Akj{<o9q`_#y4Jm~sNzCcmAwO>XOT$y2)%!*AVt#`qf4
z`LdUfT(10Xo6Ey0m3a5I_idMQt7o%shpZj?nY}Erz#{gPkSn}d_~L8T(y5h4?!voz
z5N`=14PT`Sdftfc-t^8Qcl&kSM=#fVb$<FS<m1G7T)gPn`um@MT~@E$&T;Mavt0l7
z-pV^O&BV&RE1w_d&jyb;73hek&lc2;i(l6ERF=2-@XMfSh#?C$P_e$l30$yY_2|L5
zcUYt?ugRX)di~?3N7TK(1-ti8|NZ-D+N!ma?uG6VJlY$x<+@T{xp9x{pSk^y^3)bj
zo38ajuK(-}i^uc-|4G-&kXRDDjd%-Zs7?Brp?vg@gV^z7v-_7Uow6eC$CrCbH+n8)
zgL8<?=?#~KmezbUH9x##|NPS{mV$aj?0wp|7`M*n|GFqAFywllI>=Kdyr9S|Xa$$O
z>#z*;AP=CPb2$@G<)wP<<nHJ;qZc-7Bd^<Wr<7HzC;E2=G4H(AvDfa}^n{)NXYBv;
zRDb7!#0h>kk&+9jmU_Si$?g;7*Tt|;cy5NY^(vvOwP$zs#AjdEZCZZ(osjFx;IPM~
zum6-wO2^ze{a9nyyNEpb``s#DvB&i$t=_zKM|HWwou{pB2OpMbdW&4$`nYq)=K1Wt
z;QfFx3nAqfmSG^D4HL@eer4Wh%CUXPOu5%{<EMUEuK9nzT*vY$TigndKdRcx{5JB`
ztrBzbOJUL0=gze~(ww?);?cibd2B%Q4Lc8RS%97}9q!yb&m5jng=37W>G90|TZ=+&
zJrkOh^CYIocTYue*V~tCwi~_E0_Ezf-!`s3`#ZhptHq%_<>!1kDIYa{@;DxTP_S!?
zYS*h<A6@R;Jm0*m5#+gbs2LhL<+~SIPh1zYXbRGhYJ8sAw2EzMu_~AUrR}xauYXWw
zN`cK3zwEyg-tLLE`G2mWxGT)P?QsBjsI`{wZ|0XbH!^O;dpkb$wx5xco3hZQ^q%bg
z%42*cJbcT&BZ-g50+q}Ajx`r$Prn{gSg!y5d-*1w_Di|d{qsLt)k>bv3*P_zU7FJ0
zbLTdG*7$oPRpW48wep848taw+e$@FsB~CU&LdI|UCYQii>v^CQbHPNQ{M+XPqR{Fd
zb9fOkv?|5cetD@5C}pQ#K6*E6tJasDM(6LA641XOD^K-J^`(6~Rvz3rqaBo<PTp?J
zsXD&-<)d{ko}aQQzwSsNg1aJnpPrFFRhshC#;XZo0A#Qet>k!D`eR@I-<XBBY}QwU
z$67#B2jJ1(11jKvzQ>nx8P(@eYr_^p#+};Vm44_cVuuU@fi_e_xBe~!CCN`^3f*<<
z^c28-Xh@pW*sRl7y+g?!F@gp<G6XyX&M^6cfyErXO6v)(_Tl27AX<<)MKk);y9;u`
z*QPq%F<ptO722oSXV75v8D-RQt{sCKvi&>M-j%pA%w6;d<d8;fg?9?bop<<l9fnoS
z(2&ykwR2YkD0%xXKKaP6+}HF-?B~-$JKD8BF&CCsxdc9Oxw%$&=A*uqWem?C1CStx
zgGO>?mYsa0=l|2;j_Gcl#%hIk3r_9`D0}VlEF{wEAHy@pJB%UhpmH2k3m;7Mi@ejC
zm|^=jmZ^}v(&3Kd<idsU0X&AQ;0%|tF+zu{b{)KaTdwo&Rh7KC=n>f`pl;K#)=kms
z@RlIR<Vo8duYTdPM=C~HajJ#50u;~(L<P#h14EMHh|#<NSy1eAKYCYkL{^$t1X7GK
z7P41H=!p4&#^y2~If2s)`1BJ<;DIXp2L_-_@_?(u`b0N3D8y!g!hi)bB-Zc>T3D5D
zTc0lvQV7dU0_79L=YG1BwRO$>=ZXU5%RMjO?k;799GBuy3Qii35axT7XCgJV>K(_D
zXVX;+gvDFLAH6fltg7CahZv4!Yro7|*uJCr@D;~9qGzp-#O`&t;}{ns5ZAH$@{*T$
z=G<q^?_c*M=Y2D%(kTA()~9Lnx5wWr->&0199s2e_tKW;bC-9*R(eCqg+08hmYE*`
zh2nxtcmmVc<Iq2HH}le$Z%KC@?i{>$XKk9%yYeMZZBI6q$ypXODZE=yBG&lBt20RV
zCC_o8wuL?IvYDEyUZp8}wC`S;0jfPK=Fa0`YnIhZsha(*_TIDK$Bf==0guhz=-fNu
zz<uz}w|n!F`=RB-f~+d&XayvDGd<$_^r-2B)1A3$zWJbG3R#)sMgsRgr&`QBt#xaU
zxUP!K7T3z!nQqh0t$v1muNu}y<>Iy9m1ln2>(Z0@pgU;ZmqX8wx7qqnd3B;9)yx)D
zPKtv@F!`E6xo2I&j^;f(6!suR=JAa+>ihotP3!#cT2#7hNo`^Bf0=BKM|`KAMzzfo
zddjZ({aKOmt+o1>dn`cn)upL(OsmR%=GoqQmosTf<M!m2TB@t;?;_^f-))>NShwso
zFQ}Y_L^zHp2=z6ow_AJV^@*EDUDDp4bKzaLy>IU{$Cw3w9j1K;kILrzy1(U7E83jz
z5^Yky?b?)}*<Y8bnYX*&yt8ikUb|@F)z(uABu_c;KCwE#wQcX(b5=RcJD96qbnU+V
zRl_P@WAmCBu(8+w@g5s=UnNbv&K=x0*DGE#@b1PtQhU-sZdA>0UiFgK5Y)cOkOHNC
zXf`>-U06QLWbfVxbAj@yMw1sVUt-IVDtLG8{oUOumfTBTuPixf`nLO%yU>^0kMir^
z*-biHqB6JaR>_rCmOAfU;=z%3js;(QrxNA!^wApCweKRtG@px~b$?X7kLOUUOZoTn
z=iaYbdii4gxvV=kCr%V--oc!`=Gdjctn(Rra<6@z`ikf2-EaMDplz`~Kg%<e9Epvo
zKeG5$(DhBXWmYS57dt@f{+#&xcGweo(+*?qN9(+%HU4<35IXB_-|m-_UT<{XlYa2q
z>&A+^8`o^RH@p8<wbh01MfLUS*PEx69JjW%b-Ql#A?VuSsz3i-&TVnObN6J?rO9Ep
zenlyK|K4G}!F5mH9ItDPyN_IspDOh9yXuS<p+5a5XX5ui|GM1&Q=Z_O>u0@xe|%V&
zeyewfwZ_jc%RfGA1eM>K-Xb^m?W+Z)1INpdN(U+LXY6LX<aj64vqYD9y>9c%puAG^
z+!^0oE8AOc#<=OmHyxK%N;mp)?#ZiwKdB1;&SlJg@yh2)<hP`+?VV53jHcw>o-DTe
zlpG6eguKq<-HCr8Y08<E)=lsJ#my^g3B9zt%l%8<wYA<8zjpty7A)VoI43aW_pfi@
z_7b!)2r5Mj9V-;y`AuH*R?0&?_|8%GCr7`vUY&MCs$BQuZswVH?kttJf1B=;8J*8`
zaem&vdvdD96Q0XHzInmgz{`L7$}gebZJS@5uy}`F^(D;mc(%CL;qztpzt574?|!{$
zRoa~p{Cx{-CrxH&(7qqHjm|afKs3D3o#$w7zo=uI$(oHnV~ma_Z7g_Xr69lM{MkuY
z@4Md#J#aTmZLwc8+r!*X|0|EimZ+v{B_E09y53wX`_d-nv_m?(m%|;$);nGn8EfVH
z<~roP^Etw^ba}|4yj`Fcdc|z^jp}bf%bUuDzD-$Cv1;!*sq#$gb9sSVn6vElU%B2~
zbmH6Bx8T}l7NjTx_i^NApI2SSeCk~BE9+XLqq4zowUSJy^}SMUjefUs(`!NPekK3O
zw+pWy2#LJVx^fd_=a<si*RiSo{dZNnF1>E4xNG%4_86P^_f6{-U%BkJ@#DHpE3N%D
zug;k|XVs3&qN<_gIyLw8r>yJP{Rydc^%%Tf;6M&&^8Bz=`P7ZZMtRdSCfNn8JMc^-
z@P@Gd`;r|mysFsECr6wNJwMs+TGO`$tdICkrNfp(JQGXY{4nar(rb~|nLkdMbWP*k
zh1m7w3w$U42es#KD_5Dnez>%ERk!=&*gF!w+@L~&wJ@B&Fx(_ou>2{c90fPBkAv4<
zG~5KOTwpH@m;89kci)%hl{$;on!bIPr}E+ZiJh78Q|u=#xGz>OkXNe*DI(&Rb!Kjy
z{dG-LdXZtQ#}-ply<M@VbSx%^S>Md;TgIGODZ6vV+9!H-_E9Ho_DtA3ZPK-yKN@&q
zPFdUUV?3X7sN`m|!n*}I&lYdfn7VCei<-3M^cdm%j}g;td%x_RS{U9L6f3!YTYqfs
zz50KPk3be%J^UtR_gdb3%Bwd=EaV{mY2U$YT-m&XIrwMdZ<~d7kaYqEv!7on|E2Iw
zOL@}jd6OJ>Ou1R15xaluI}vTwxZT=^3x2Ac-c}j&SZ~tL9r|^9R<?dxVm#x-*~YDJ
z^3s!Eme1SguIV2&*LdfQGpSqC=dRwJs&RPT|2M{U<qD4@PyMPsA8~3&^N!1`h3rd<
ztRwy1L+Ab2+sMO~>GMR*u5Rbeh(|YPl}_~eJ^SmcKl@lF2ORnsV72yZ?Y+wFpPile
zSh}uOK3u5rP-Vit{dVpDO3Ej`jrdm?EgiXLfA;$qkCdTp7+3T*45&x&71ejI{GL4%
zx!@vD9-uW_^IQAPTRTld@7z88_wQVt!wXAp-+TOgk6-=z6Z?11^w__-_)X3Ea~0+0
zMlZ|f)v0{2GP?1d`Pf8o+b6YC>Gt*Q{Kz#2sNY(ZV>f*VpN94MmG8ee-nlA!WbS0-
ztzlrTpk~vIli+bg{@c$vzaB(QN#z3NeoZ@?s|vLf?;Gy}4XlIO?x6Kj29wP@tPQ5h
zZ#ysisu{dKhhcN&yWji1e$L_Q*nO)=w|UB;v+LI7HSB1P+9-8;ru~%H%-LyXl2%TT
z<`<SoS2&*wUGBKR>IH|aAGo=2<_UP^N&DN+Ex#UgLDy7356)|NwLrPVA{Ns*(4I8x
z^u1NheHR{<fZCr2eC{c{I}lQL!_I#NsG$#DCjuI92A!q1f)9t|>>-OpkQ}%4@o&3F
ze1+_)&w5XO>ex}-3>uHHg^fob8~AdHZWpL->=P|_6fiNe7bw5_oS+_scU^(g{y5#a
zDh`U%0`O=DcGE%21s5ED`c(B1Uk|h>fG(eaoi%vX(Op9p)bRQOsqnx(|HoKData^F
zM^&K8u~8c|_V=pL6*~5(1g?ahK78mXCnv{MJFVh~^1Qnh;1jPd2zs%D7EIWJDt}17
z_v;QNXoyV&)e3_B73vb_!3SPhIlTlsm>tvyfs9Yd!N#X_jWE}zG0te|3$OyE(HGz<
z5;CN4TomfXZqN!5_!uF>WV~)cTHeIq<Ags<K*vVLL5|YmlwDW?N?;ejwGL#crXRLq
zM+|Aj4$sD2)4Gl0_Z(+mqW&*ZVRQ7^^X}nA+rB5h_TF&E@?V+S!EfIy_swB7-syX!
z@5!s2|IT;#r@38j#OFb7q|riLCt<8B@lLjzG%e^+X_b)#PuY$MFSjxDEW7l5+x~o=
z!+zdVf*yTcE@aznJ3Y|5^OMyj?<2A&j()k85d{vc>o$egv$k?QXMeQL0@CCJ7aTFr
z0k3UH$Ga5hY&UwT6$n~l_j&(Mk6T`yuVUYx*rEbD?BVIjf@y!}f?DO^^>*KtIjiH0
zj-{#0H=h$aNv@>jlH(my|2s=f3(%`AXhb6W^LUZ2vw!C&=18@F+ov1|UlbC*OtSEr
z(K_wNXI5_YuH3HwY>U3vTc7&5yhnq*b|r6Ce*KL=3WvvLlhH-da_~sjy?`{S!sWH9
znXm7yJtiCIb@Jxb%N~1f7lxO(f124qY?P>OlJa(6X}kF2wwY_)-<Gz0%DXXj+xE&6
zRkAPppP$U!w)tVzUz>WB%~$8%xqtuk+c!ynWA8bvTf98^y7EseqZ;!mdAD!d?6H0M
z<+xElPuy!ZSoUzA`ADxz>BwD9K^8~QSPCMKAP-i%?s+z6(z}Y%A2*)vKKo3}Ys&rU
z2|`{L`z9FI|BWj;+*!Rdde7v(?|&NKl<JkG#MrD2>kQiWrMa`^VT9hfKVPdML&vb>
zz1XL)yng-losM^QI^Im>ymMIe=fYxHM}Y`?{}pEEX9twMW<o5zYckp~d3J*G@m<N0
zsj~Lco~ONqOS;d7M62#y`*QvF?()|cOZ$!TlpO0n*Ul~9RPpDJkDIQ3=mp(JpHJVg
zcx?awvwbmIoPnF+6Xk6d`}K#de(G{_EjLou@)15+vt?pZ-3HZ*Tt@P1mmmFh=xp`u
z%&nTcZ`^CM{W#?v-=<>8ty4fJU>qoPwO;V;^TIf2u^S^?zWCyaUpsg6fr}ibM|__a
z1;@=&u&;2NE9ZI}w5kW5JeVfm@v^w_=h0QpC(j^5$F^%HZ@;N(7JKffQJ%tesf~y4
zxiRQ{m;W69|7-lt1<F(S9-ZSYT&~UZLPV4uv>G4=)OdHi;~4CCXC~5VQ;mpawl^;)
zmv=7uqPhCw)H#}}r|P$hl|#FRD+{k#pUZonB<(q6S6{43czSl>_je6DPIJR!2sGYg
z%yML|bSmc^X2>FIF{A=QEdsQ}V&M&`mZI68KckHm&*r<E_G*p!4nN!e1#6!a9=V%V
zGVhgtaNpi(jmtrkDCRT7z}ZysokPD`_ime~%!SwgY+`xW2wAkmjTHBg0pefp)<+=^
z5StfWytilj=3}uYZ{PbYzI$Tll;p=}HNW-V(dL4A;PI5BbKh<$=RG3(1iD5X+4<PU
zgxMbDtK9u$=%;e|U)7bl(Ag2^ms_s!-#WMZ=;!w_IY}$Fm9#&8zWdZRw)15ZdQ<OR
z=G&4iS@x*(2V^uD<|+OovL;I*!)_}T-kq5Q-e>v=Iy7kKZSzR*d>(j4>tx#5oriPQ
zT29w`_wMPxe}2;*2JFgx|FJl3x&Gsuxv#$8({+|C``bGuc+sA1CG87!g3XRZ$ltza
zwGB2P{DNa?@Uk7R%XVKw8pOIVWfRN0h46&eVZAx!>vzHOBg*$U!K=zy)0{u<dK`3Q
zW-dhg>SFkS4d1MwX$Nd$R^E=?$#-EnXnblSmQyOhi*ME6cF&fY(_Q(3V`=ja$g2Dd
zuSllvFUofNU3m-2Tg$eKzji}eoE>r|ODFwbz&hpA&jW?fL+gc&^sIpGpL?uqXWawu
zop~hKUjZHd1*@GqZ^vvOwQHC6cPhMFpb1TvOF@prtZwhV?A-mcCeQZoY>r0|Pl0CX
zaTp9rhgKcC7ge_JSS{XReS-TD-z+c4sGqydBgn#Rl-5D>vMH(spje&?@*^7}y)qdf
zRpIQupw)vN))`vRfv=Ap?y%E1t(;zp<OZ-hUU&gr7Qu^}W{?&xgBuWYja&ogN+*G;
zP0%<cIEpc|3l{6wb%5sd&pfM~3m(P9;UBHjlivTnhTOW2dk!8kL>@_Jo&{^PEjYC)
z<oPe*Rj6G-WV87)U@fU;t<ynsU;D3+gRJCE`#k5DpFC1Yk|1QY;N_fEJGvLGnD%I0
z#xA9Ir`QYGL#HjZx;{U^_W%67)-8qeBG22|ow?-xX_1F&TAQVYK~QI8Kz|@}_^J{f
zak(@J(UOH%n>>~)=xAj=5Mym~Rps66B_+{%Uw*^h*|Gjf*47_yY_9jV|6u3;?beOQ
z<vH>F!n=bic5ae0uzq%?{A}QziSBZhQ;&W-!ZPCs>xz5%y6@I~=j^hcAtenW`uClm
z|6-bU>vZkcjGL3s)m)c3DqHzvVt8bZzfXf_Ov9_dJAro&-nkKQ=irr!FSY+%w#R7h
ziHYQ&AzS=x_cM)mCzSj5oJy)rV)A*!6w?2w?-Ad#V{MQ4mK|IC{<He7r(O@Ao~k<V
zX2$vF#joENYarA&DYkFj<5T<5j&H)eAD1J{j<?y*-+S`QvxC>BSNwnb^?2`*>-*1t
zPL;}kvf{MeTh+Pj;p=%*=DmCRrRD7b))jI`Wsl09>E%5t>(lFg|G9t3>8XcKPyNb}
zoadce7`|`8+S5;!rk{SgaK384&8IidZqA#La6nHiUNbOD#c_(qtYwp28hfS)EoJiD
zH$Bhlc5BZRA^jOAYwZ3%a}B%Bny_ush28&ZJ6#TXObL3_s(o@_%6pY>`}bcHUOMH+
z$8$fnJ;3VIpASz}H5hJR`mSpJqduEYb&2!dc5>R6PI>Cm8MN=n?)>`gu_q!l12=Ea
zPmK!wW+uASrqk@}{$k<EMN`x_o9zDe+2_*C@RK)=|C@WAZIaBHJbpcguNv<(-X-Ma
zXuM0vviW6KzbJa$6!~>)*d>aiv$}V?+h>Kd&4>cUz`IX5{ysleZgrU_^z`_q^?&Z}
z+i_cWN~o`2+%aF3m47qd#>M5Qu5$|X>Xd)qZC^co`bHtss1x6QXLnowIi~;KZ9BX8
zf+~@6k#YlbGm&xwQ@PstBJUa(!PWxUU(^jh#UFl+xo4+t>Gj_t<xeJl=l-1I?^CgC
z+0na!lRAZ-x^Bvxu$yb@i+$hUO<-9xWzx&&!t%R@6FY+zrL9y;S6vviNUif<^+&lQ
zSR?P#VQ}PeBhp^QB4?$>AoF*}c5gfR{uZ}VWv`mix31<j;vO?{R?Ba`>+<va^Pk)|
zW&Dcl=0Dw0d9r@G`SjATJ?r+Y_WK=MX5D%G?CC?xb}(FBykqf>=A9cC?r2{5@x|{y
zoq0Qh>UM0BOE{CeaEEfg%_ptyx1F5lgX;R{O!6$+@&DG}?2iT9s;Br><CaZQ(>MD1
z*?zTM!6TjJcUQCAyUx5xe9sB9-Bqzq7jM2ktG;JDub#u#XP+%WsgVaIHDd8l+vGjR
z>*^NFQ7Kwc{Wncf`TafN#HnZQt&`K+Sbg^Wy5M~+AA>HHXck8N+4mr{?CEPBk#f*2
z1oyba7gU|s>H1ao(6f;Ja`NNf|AN1}cUhb7FhEWZNI5HWW{$XP=d<JURc|fs>fc>g
z=O6oVW7OH;oc@<SHcO9moBf<Gsqt<HgK0A;yPlVop8Q++=v?WT8OYHLievY<)Qz@=
z2bU~f@;R`sfhVcbe&z|E)MZzme}9s@X#LYW;?a>kQ#4GcfBkvqjrF?{|2ca<@&Et8
zzqWvJm3yIkVf*vG-jjbPK03#%cLr3(JZ;y0&3NpNSeNyu6Uys1-IzBc;gsJb&wq2v
z?!8(2@A1a_sgYk5MV@b-v)O#6mg=ecv)#LQmtUOfKS%f7BJKHF((6ptKV7*gcF~T-
zI}R5gKlbFGN8xie@n@jSj~UzsiR$Ye>jGrXUcTmfL+upz{(_}He}9d!S(>s%Lr<l9
z_lrG0qkh{x+Bm7-`rWzrpNd|u+x01L&-C)ex0|>FY`d(xtW7q@t=D{)(83Ka$Dp~p
z6_mA4tk&74uJ-3nnW5OyFaGtpOEjLZy5AXYH|Nmwiuiw#fyXlUJ=TkEo!Wo#U2^=C
zPbt&lZ0|gpbMkgbXHcUG`(}s@yN~NkKYg&5{pj8EIoqSVtR)^E!jU@dOJbhMgND{N
z?>zI|%DYlOet-W_eXm`A-Tl;78|;7W_jBQq(;=5sCM8Uf&uG4$e?M@$w$YUcwZKnb
zS8iIobIqpL-y^2g&tnNx%ADmP@?`(%>viAno(D(L_ZjI^<3-B<x)!nr<BI=>?OpHZ
z?0*01<l0-0-swF5?D;KIW%9=FAB*Dzyf#^8)xXc2?`87wv-Q_0LQi{Bg_dr*ZY%Kk
zi{5F29aXsspG)+YtLMOqvI{&%Wqk@0!Ig-8OeDX-vuy#0>WSNIVnv%g*F|w?t+P<F
z%X-EmT%i(c?Il%pjA-Su)+$C{l_S%q-9J7V>~;6T_B4%m30=6N_kaqt{KfBRP@M{{
zjb<&}(X5Fpp)*W|7Ddj+BIO20TYn1QEn51gAl3H3jN3uccc$uRye`^#;%QOki}aJq
z{WiNRx2db)bHJ6@_rZ52y5G}3v)R^=QLPY^;mr3u((8NNUf1{NT{?!xmTuco{bg}k
zYQxG_n@=ZR>z#)-2jq_4{m^B7ms9WP-Oqt{4vL^;C-1vo?LZ~+-$ORHg@qG@Kn2mB
z!>iwm&l4%nczpBd-1oml%J<{UAYc#7ixm0#_t4}=e7QEecVrh8Iu|}~Gx24&$6j_J
zS`lXh?j&mb7P|A;3p3||4F*+>pr~ovq<_#BQZ3G^{<4Ry3Q=-F0|pY)22*M|-xV(X
zkhMwf^wUefez#bPl&7IJj$jdaIN+P=j_2m0<uZ%!I2ERgfdT=gNwhQYj;SWo4vk-u
zUDiCQ@lDkl?+ik4nI~CPc>RgyGLiCkZ@dfmkIJ@nJvyg@C<MW2qdKin{P@PNU$Zy)
z2i#fMsVH8a`;EVA_rv$tbR?We)YT7;-_y^$ME#%1w6hx@o=?v=+FQBdtLi=R^|y~d
zx*o^Sw&~Z2b5C-ses8VYW4=pv2gB9sw8HD(g*VO@krXN4e?DLLo!aEiuetA~x~#Wc
zO{t4mfBoA1<(*$2NIVr2KPUdX1yRsRY|uWvWg@uv@DgG*3i6u5rE=5!#0|ZaB~vO6
z`aJvm(_DX(7WaY2UU6FW^SRX*|9SAnb<^Jy_f91(aj9%PV`Be#la<t6F_Cg`6C>l<
zcCm61kHfd8KadOO(htAJe0FESz8mU@czd|KZ_^x&z*EyJzQ29HjayP%HS3#Nq^}>e
z(bT`Mf3423S>FTioP6#&+ix5D(YYuQcO2XnbST!FqyLQ)5p~GTqqwB_lh^y#y~<Vc
zpEAqi(wD_s@8^go2YPk>|Mhn9`q>^fOH(Gz*t_|iSeG@VE^sbvU--tmpdZ{&ZhRJF
z5&uRQ5rrRoe7koqRuNV`)t&PB#CuB>qd>1K6@^~~Z{9JSdE)%LC)w?f{J@Q4ShC(6
zp)+U3ZOwOe@@Ro=b5U`k!%FG$$FaAcl)q)2xW`RcvihjwHEtE3ZKm>@&!&i0Et;bK
zP;2#{+B)@kg^SrLlQ)LT?6KuM<g#t%&(dW(E`wS;pkhYi)IOH)CYEMAiFwO+{H{fJ
zvd+vUoA+qUR%!pe{_g%dJI!lIO`gw(uD<>BF3)nu^zi*Q3BQGod3#=ViCb0|$kVpT
zDCS<^otL0q0jPY2Cw{cRt^l=mTrJH!p9FmWb=Jvk-ns?1Mdi1K8da~p=UZ+!|LNb<
zn&<D$H%V09YRU`Wx1WvwTt+im7=gmP=wZ!9|E%uapICEa^~86^=<)y6seCdq-5gYa
zT{gO@*A;Z8KlS_NJ#U@dygFwsowZ-zF6s7zhvK1-w#no#=U&V0<=AS^_ty#3BuUeF
z2QCN}?l>F(PIV~FS%a4vFKedAD>O&k^H(zpo++xD@O1Hpqr%CdJE}CS!CSX0>VKPx
zl&9HLIZa*m@`3*mjdvH^<hynsUij=aZ{3G`niKBa1f}b)-4=awBlu0+3)91L3%|c`
ze|w4{n7i`H#Otx3Zo#rQDl?zl&wPIN-Ya{#-?7tP+Hab*_hg7>;J@spJ8mESc|7It
z)xB?gjNX2~k^0H(Z1?W#)<<KbMarwd4MC-E(cQb<PtU)<j{oRg<NMaEldQodW#Myh
zU+eqdnvMRi)_vD}cS8BSIJon3$S<z>&jO2C%ZqY;e*QT*K3}BZ_09^flNlfXvb@$f
z>Czb_?Ad3&>HWQl+o$bZ?$Rr^$#jRV#=9>X@9N?U)2ny$iyoDQ6tp67>(;QJ>8red
z9;J-<bEj<L{hwvuU#|Zy@-*hF^~Y1~!7uF2?V7f8mG-@^BEO$P@Av(S{aL_ee^2_Z
z*c35HNznF)FZP}H=bv|e{dTF}0qeBZ+M{MJ=i^I#rhra9PA{H$zI58BxP5i<-SJaO
z=F8WfO%Z)oepl0eO2tgCSuR37pO|w$?7IBtp348dmw)@Wo()Tk<I;*hRG|rK`AoTg
z`1`NV?ddhnnG3<~(=?5D7oP6B@*P|oe<(_|O(;7v^Zl&Fh>n5%7B1<SDY3R+L!<A^
zeOhC8(ylkf=$l>LIc_IUGxxvmb&I8JW<1*BuR5!zo5{cP6BFlT-`D+L%p8ffK`ck<
zquR;fF5}x8x?eQj{R+La_Ih^L?s<!LI8Xl_gy`Bf+%!zzm)(abl}p}gWWG50<LO@Z
z_eX8KxcA<V0d2{+CtBX07v8n|`C@|l-%L1hr9Wlv*9UuT7?-x*%h!81OGH(qJY#dO
zCZf9uj&6zKXhipd$!F1)3!pNFV6V!c^O6&|&_f*&z*e7oaf6H58PdpO5}5r3hRNVS
z!qq1pM2>_vdzKwX9u2|k_t`&d{$2U|apwEEkJiP*;vTbS)8GlsJ{9k7%(x>z|K~l;
zcaTB{)<xfXH1=oHHofWHF?!S6>!#U!I<a|nI%tRn8gr1|(~mRX{R*F-+sE>K2dqoH
za`(OEJCytP#Lpm3x$Zl;zbj%T6S5ThZ9eTf4Q`7DM!f)44i9%GCl}S%JgZ*5qc}aj
zsX9gz+TcfPx<ZvNoOw6Ty^viQS0{u~4W`ht%X-EGT%7`Vk~<rC=O7D8V-{&_!Qjb;
zY13Eg-#gBDNw{9>^s^fuo^LjvdC%s?FQNC{*WV_8%+_aej*Ly8|83H_=JVg5u^Rb*
zFRD6Jwg8gwor^`v4GyBT;hhTI<tm?qirp3#=D9I7^_EAI#zYfe)lMc!O;s<}NpGZ6
za>R{-y!Irheg64pws_=J)(3^E`cwCxZ=D<%cm~{9@_ZA&f4j?~1F%6RqAaU>rE$7b
zXlYGn`Tc)+yC-Z6T9lSQ>FSe|{NTV-lQTZQ_<iG4QcSJ<?;GMvZDuaLc{SVEGd(U&
zOYTe_KPb!XK7Oj_@I!+gA0Pa0oWFQSGbgV8%ZK3XP8-!z{i*Rkch?qfzrDSGT~-c8
z+iBPSU!Th>CA9+=AH6DD(fWvQ|Hsq2FTQomEKIJ^cqeCcgs?r>8d5)^9m{q8)lAE(
z%Y%#~$?&c-UfK$2^Wk;1OS=ox(!4vp<++pZZxwg>B;}j(MwC5Le}ciyYc*%gCWpT0
z44T)n`pxV6Q_HVr?mwNU{_zKU>O)>=2FvJs#HWU9nB~ysDfg9^r%bw1<A43%*Uz3C
z>oh(ZO*N^UxN`pgnd0m6rk8&|bud)JOY`I7z0cBTg9eMdxc91wPsohgYkaAd+rP_t
zi)$gfFs>B;P}1*{-0z=_MUze}eD`&BYmZH=W4N7Q*vU7#m;b%_efr0@`_dZk{{4Aw
zzuhTw;q@m>LFG<Q54EZvmA$nHPfR96soi!By!CVAo4Q%yHFrY)+m;@6&&i*f&(^hj
zpQxU*YvJ|ve_zZjclh-Gz<Iox2y0sj)O2=f)&6_l>}Q|#UE%cgf8OTTXSaeXg1m~O
zcNafC_@CL{9gnvUPMNDR`H%J6JvXEO9#7tX+UW218>#t5p<Yw|M`^w*EBt48v!GOY
zbIqzX+ipCDjs`gwpTF~bcFY}{;{A(uyzax*qo1*1@^uA!jlO4@ua$CyE4Op+fQ$$I
zsM}!cWfZvRip!+OYu}Vt?ko+Dtu()PdiTX#SUvts<6S}%E_1Q9eSQeN-~azk)U#J^
zn&qkTzd=L1Uw%Clow>(%s)ndXk-=_V4c)vq%Ag_FjGjk)&No1fMsWFkcJ1}-V|Nsg
zIv38zQ~wo)JngifeY$4d<|*Glef=HrXVH@1e_mu`8UG1CTYhD#eDmCWSEsb5{(SB!
zpgL(;r;Fpi-8FB^@BigN<eS3+-&A+N`bz!tt~;#XwnIDq!nLPG6Hh<=bm9CYce%<k
z&>-)Rg^y0I{T^$(6K5kR&vwS6TQ6g$B~G}1b@>zx{Rx%3re7A`#*V`>k@B>w$O9M$
zn|xK~J#2US!iq<OSb2Zlm32G@TPL{7Ro;DibKZ;#TNf``nEq#>K&@lu!tZAmY4`@e
zeqGKF&HyN$L$_~Xa=Xj2I+fRJ*xx_p)X@C`uB=_oEPbSR+UWKBzvc^efVD3_`Da4v
z%&*^nMq_qSq4m+uz&mr#e|2T}&;Li}sBGH?{e!mW=g3F!+f3$u-d&4SD<lZ1w?Nvw
zc`J^_&i>o{DDMZj%?_F$Szw9Q2|S?U#{nMuzi=mC=iRf<JHNhtr_^P=<so=Fg@AI6
z32oa!Ln7d&+pJ<x2MW1i^r$5O+$cL6cqfsA7$?9ywvO5c`u6c|yPqtaIm>FJT*kT9
z&qwW$hU5)8g`L1{LKFAGc13X4`{-Qo9M!$=1XV(3v#_b$n=a;BYcIHXhjX+@xx^uG
z>jyenhSu+3m~5eV1=P?5)%Vm_Y1X~_X3n=O-~Ae|tgp@78y8*Q|AHSf9+Gx^&wE_S
zr|%J8>|5{J`Jl0S@Zd?>@i{-&St5#y1U!R7_5Wus&Y2Xz^#1dA)<mV-Z+^cvs+@h#
zuH*N|doRi!fD*>K_@j68wlCiC+OW&IWUKyH<O#peI;Yp{KfiE=?z>asTS|AvJSo~~
z^JVjsiSG06g2o4VZX5+&Fx0EkA>?^EWRk{&i9w4(6g-!fTt*!!`W3{Gwu#F&(CcJ{
z*l8nQ)tSG4Hdg*ox~+c`+-29F5UE<Or@wmf#oU9O3+0Z+?(f<?Kj*sI`)Z?^5%=FY
zyA`&t`?eHm*7De$X}ez6f&$=oD`?#G&y~Pw!m3`N9_Qb?Ws1p5UC!Q9S$*>4y=9B0
zs9#+6ul(8i&_~C2>(}q={`^VLgKvI)9Bd#-oxMt=eE;elzcYV+z8!dH;p*CzkXcM<
zyB*6YYRmj6?<bmpbvnOK-G8h4ZK{Uosa0y}!j+)f<W~PRv6+v>EC2s1e|kLk@YFe{
z>~Fg~(o~&%<jvgD?FB^(zR&L7t>*u6$qwh)xju#L!H+LO`l7Ir;qtxypoZmsgY(~x
zw4`T6-H}zDsSy~bGJDsVWF_IHDO)niHWvD*UHal@Cv0I!T(8W(#6u<E)v>!3*Uf&$
zRy(S!zvy!8DYN<>heIj9zb0=xDqFJoi%Pr6q?0$a`A*DZ`5f|X`TCnb=hig3tiK;8
z{Yoz7WAPjra1$SGRv6m8M-1q<q@Pro`_%R3lV8@)OTMi?dRTXg2BfFH=fsus|IcuT
z&wqMXOJwPkAN%Hu7X&J0?wVquBkw18^4a1Ew@<H*m)lUw`FQD)OeOuxkG95XXdiwm
z3yvV<SxQhg09TtmJ9Uu;5GDOS#o1^$`3hNH*;}`H!o=@u7g*1KT5}IF1f?zaFixc0
zt5Rs)KD%psYb=ibc)It;=3X7QdD|9f$47sE(6j&V+x)c!MGHW~1nkAh&X{q7RJQw^
zPT8&DWoSR`uK(w4+>)BAS<{~Vj}<F#Tqh87`cCj7H}0F)((+RcgBD%!xn#Zmb@D?a
z7m@P6xBE5T{pv=_&Y1pyOuYrJIr^#2XyVLMYcv?YKmVLwD89~QeeOSz+n;~xy!7b|
z+IQsl?e#xD&;NgiOPzf?sPlF349a{xM$E7Tmre5d^nT0dwEVB~{eSgNf02(odoN|x
z6pjC;`tQm%_C$-8&rG@Xe&gvUxwFK}*Ozzg-ezIB;=UQEz4GHG0mFsMK1n@cKYGz-
zYVzs%=jZ=fr4p0*ug+H7UsF=|RCo6y&Mmk453f@RdG-0-o=2Qpeob0`_ITFp$4?g2
z-43`Dc;{g{f$*-&+bz)@w5#3QBxFkQ)%QoV<^4W>eZ1!B`_GT>PM`CsQFy-pM%`1E
zPrdh8XUD%jUcLBs)8yt~xz3>Rzvn%@ouDa6U1x9!iW%e&+xxs{YN&cuK05!*X#Q)R
zr+aJu+KKJgc==7<a^{*tf7V$)Z5PrH_MGg|6j--_H?I7C-TUX4)BYMvOWifa;)=b1
za&&8@=876f$_)&t<G=s<y!^b6yz1;<Z?}ObTqUK2K@+agZFcoY6Z(ic`VjwA{_Y*G
zUs*rja`bNGx#yGLT=q~)e*gIS9)&3>#d|*P=AQ%}6n_8Vm{DiY+w#|QzpZqcTp0L3
zGcZmeaZ~2siTBjtu~l*I#*7>Cn(yuyeE|=1L5mio<g0VT<&p2C<s#|Z3X1~v=W4vu
zc=ut>M#GKvL3ehhz5q{t>K)j947L^kS`;EpgrbZ@`SHEl&I_6kpJ!~Q_RYP^dOHuK
z4#7x-Eq$^=Gk;B7vsrG>boB@D*tbkhPO4wBqxkfN=h$a<8$9R8T*;RPP0`*lpM6&2
zUBVG!l)4wP2jdEHCZ9)e`|Y}{XP|}^?g=`$XWuQ}(X5G@q)-NyA#R=>UAFtKv;Fn&
zu+ATvgRrdWfNI>P9^$<J!xC_##Q+*9(1<`?Z(`61PwKxl-X)x(TF96h&-7W-$9{CK
ztw=eV3y_k+0ToD)#2TO1+Yc$;mf?zjmKjG*I{w|Z5Hy`%ON^m+4Z3!_*Y`bo_k3O?
zWRx^M1(H6YL4m~~vPWg#Ri_n(mxCrAr!54pb;35T2+uD&`XBKjJK1FW?Y9!e&4}EI
zkyd8<u-Sq#GPrqsEAh-(q*iR3%(YKOUyuH_aHx9ZpL|nB`d`gAwac^FqvId_{XXCF
zlp3e%2fO-s0kutMO>QpVyX5nO&wDEy&s^R+XWj-`6gNS7h~O6ATZ3oM5Vb4|bJ<4F
z7FT7?MJ|_2rmAqIESaJq>Jg-Q*92S{#TiWgS@Z8~_nLho4Kvp``A-Qlns;=QPq62+
zy1E3p{U^S8fAdTF|7)+R5bMwLzrf3zKzU(?URRm*=f@dB7~LuBo}HFRRqb-Tb9G<$
z8`tM<t+;)(vQk{7z2E-!@qHRkPwJdq7dP9}>hq_dj|pYf1)yTbN8EMW_0@a`+m`3m
zeW<<vtJ-9voU=u_Lp7SM*Mus)rpTY(_o@8%qrB|_VWyU|PY5qnn{=ga%eE6T`%nD-
zzF*ruPkLQf|G|ByPe*i0>F&GRTK;dx;ru_J@=73ff{MBVd04+~p8T&(*sPj4ORU`8
zQ_X9N_{n8@pJ$wK(UjDcipddKAG$f@^LK5|sY0fnPcjPTTEZ$wP!a-1SC=)9WO5!K
zVhR%5q9#3gi-)X2YPZ+RZ@vp^9AdP-R$re68=Tsa7<q#UQjz4{IC?k3WYfQUvC#ez
zXkxj?(7YWnLtx|m)3(S<E&RUa@~!o{a(N3~APYsFxGt;vmmas{m(KgJg&I@q&vymI
zeLT>)^hn~*f-VoUo7=A+t3LZa_n+ZCGiVY#toQC!SA$~gov)yIAW$!N|I!`Oy>8d;
zE1!}6^)qQcB009CTb!)^xPZeHHuHCHd(*p`Y3J1sY0ca#%0FG>l*LjT&hVSl=X`o7
zB7Z;Hz3{p=s8x}XcH(I4zkV%|@><8jcC$L~Lh~tK9ju-0<KIla^=Ms<WAyaXu6ol?
zJKKB9RX(|ScC)SF!7V=9x*r`n3!eXb^mv{8{ortTt7|_0VuOG?wndCw3=9km-*4>C
zySy5Cbi2vZ-Shd;@A0e~_ssW6S!NXc>T~s{Q;+mwGUI-)?aBTmTfR&ET-?T52X+Pq
zh6i%Lujf^5J$iSs{8nvdAKfPt-Q&tZeT^BLCZ|lQUq08odiDQ`H|3Gv-X?E)I)6W8
zCNJ*J+ayWtt7~>>&(~UAoBMyB*6;QIf306MWzx~4i_ITp`u_h~|6ge76rbh6uivM7
z{QF-2KYU8o|5*E)kZ(Hm-^=UOy)=K$|Nm1SEc@^M|F|hZpXUGnIse-I(-Zz&w*Na>
zW9gIle^2Ar?4Pdq^LhQh^gyqZ@&7)FgVjH_|K~g<NT_Y$*Y8Fu|Nq|quj}>n{=uBz
zdwI_O|6Tvze@f7&`v2eSuif_!{}p!!bv&kJ?jE+Ej2R~W(c+1-HT3@+n)>Yh_2Q3H
zCS6?gM{XXd0cZWR%jn%>&28^tE2lpF{=l<v$7{Kxcat^V$+;JPm+0DkJm8LP+oN}e
zBIW%HcT~$9js1_5PUhd%JN9#K*;M3a+(Yj@>;KvPzwMrIx;;3?{%D!}bN~5smtN=J
zbmB?wDwmZGlbUblIu>5H?b?0ZChAV(qj!N2vw0xaIv0Mo=-T~nA<_gMwzX6Li^A_j
zo_p>SmRNUv?kDHY=_{9bsvOj?U%|Tm{{F@9K4)&OlQ?Y@>m_rqO2O@Cls|YdUxmvi
z_hUNK(b(@A@8lpBq56;K=-tN}?|va=z&`;$H+1Y?H}B3W-FN4T?B=J;cQcZ#mbZV-
zx=>~I<KFwV6HI2ExS?IwZa&R(%B%g+??J1kPP~5=>@`LFgw5U4FF9{FKU!A}@uCde
zi-?dd6e<7fTnL|f0JY>K>oi>A1MZaeL&AOWj%q~MKsEL~T33&#&z!FJO=_F>5j6Tn
zir-3*rw>WdctE9V_q#xF!YG9J4Ap^wcfRr?O3VgNk@C9`PdtW%JJb`<bhUWLYk5%D
zAF`ehl+_s+z`B=%7BGYP4d4>-GHA&jnC}1%uuRZg4Vb?GoLWpk>p;PLNE)4W^xF}Z
zEz?i_F48-A;&+AC6mu@n^5ZKOk5zt`=ru0y;_+`Xn3%h)GWVNW@KU?F>*4#3{9eD_
z{%!C~_VD+*GrV`%e@)o^^u6w^o}=3LZ&xS<u6}zh?{8FY_vN@tl^;Idn{vI(Xa0*F
z6IK5Fx_2l=`S|jj?LPOGZU1JjTDRwa=<T=N&Pu{dRbuW|oeebm7;^0C|LgZ6mVI1%
z|N677vDT;5IJG}te)c2do|}^Y=Jz7ox-Xvn>)X2e)a(A)5zCU_Ki=EB{3HLp==0ld
zC+g}4|1X{&I`2pMwe@GWy?9?{4VuL+`g>0;@bu$rj@R^qKkhwWd;Ifqq5Qt9*Ym`U
zc2)ZDrha|<HBUbHc5Zce-^#mr=6x%-r%pO&^Y(xF+wHFN`&S-DN_H3g)K+h>2>cAr
zNT(y5?Ck?3&R(Ci^`yjkmAGY_dYnH_6?)pb=~vu6QE^Flb7Y<Vp0dJu##}01L7tOW
z?CAKSdN1-`+0$ysI#`p5D|Rq^cpSUCNA30Xtmro?-==DqPEzoatIj_^X|2kab@y)v
zJ-TVJ{{}}m@3-ySZYODX2i7&&tbUVUTp1Y~&tbjq?v~#t);@ao`G2;3Pip1&?^`Q#
zuiM?ft<j<4860`cSn~d?`B6_^cJKbQs7xpL>_4;kef5>K+qgb=?@0Rh_h$9$n`OUe
zD4(u1o2tUqHA!>AliT)}w%io^dp9rr=FxxGle1nwzV`h8?5ErOK|R5L>5iXD_n!t0
zF-`gyvU&g6>7Uj~3%mEPT)S<r_VFw0wo4zsGJ8`=*p#AOkJg>t_TsZ)=?p{`WQw}!
z_DECpp3d5sj_Km__1~LH&R(&jp)0lg@AIc8pQubce0BbFamjfuvv+;pe%`-m&&(y)
z#gihnjQu;g_B|_mt>C%9dZn$0k*1y(zuNWncemYuwzBs1Wd74X=zH(>=QYpgX*~7Z
zacbY6pK7Q6*X%Rf6E9L;QFU?Ix4k>}-d#86p6bk+d#Q`G-<?W&@|*SOx*KlS_pd*j
zZM}Wo^Wr<-yXPj|`}FL!SfzWU`{Uc?)8?H2R2XRO`RaX-hQ3VxnYnN8Mc?0cJ8;@$
zY4LxzUE?;Ly=S-ic22il{&r`j#&;DFckbSLvZFM{FE8dyeyU;EqANc4);-(zhwpr+
z%GPpet2&?Dt#4y3mzC|kdrl@eU-SE1>7%i;b1%M5e&ujgto$kWtz9vCMLT2Uenoyd
zp?p3Mw1OrhdA`q)-KEFRYV9d5{FP~Y{y%Hs#<l-q>zKZLeZ2nXeA68#D(WY03^Iz!
z(XO8!zrsXAbpF#VlYX8MHmzO#=k)V^Kc>IFEpK0w0Lqe(Nz2xp{r}HB$~*q?boE~=
zyQ6+_%@Zq<&sJye*uV9je%GSJNf~xY-&!BvUR!YIh>@(QeB>8*^KVyu?xlH6nN_FB
zaqju&=k9myy{4P3e|ztp>4b^q*UtEBb9Q%Mt!<uj*=}lOq4<>dzqfDyX}JGJZc*Uu
zy=PrCRWEOUbNl|({{=>?^DZCE*}m1~-rDP;OHW=snmar9;`6s<QD;-1yu24(IyXNu
zyKnZ=S0A6w5H|r00Dgb|!*J`>ZRJmA-1=H(J>PO!mT38jO5>TnrT^z|zbW?DZW&)F
z>hevW#gnJc>Yn)JH*47E?w;gH_e%}D^Y?H6C4Btd)Bjzo^^N3X_lMnHq``MZ=jxw(
zj~4AddDlVKTIFDG_s98f#ecq*zVq<qkFwvJ<g#=w{`&Fp<BC_UvHxWAvi`i~>-ijM
z_dZ1PzkJ^3TXLH3jV{J~2%GwOj{4*$v3}p59Xlqz^{IVQ&sO<Bo%iQf>^I(d{`T6u
z>N+{|TRGj1dD}lnJ-gS-{atKTs?W#&@y$C=eofAro%>(9Z{_(LdGl}gCBNGGhi~Vf
zyj`IyEY<V2>atb&yxn>0(YuTNx27^K69X+K-whgoPVlO`6#jkv*0Wu^&vV~-)S}Yy
z#B^3n?aMrc#7%#T6eIqv-u|t+yli8S^u4Q>X1-CFZLz;O(0AHadCRQLb!)e|{#?KP
z*8BdOo;L4pdfwNZ9BXyn-pYJceSGfs?mtTQ6JC6MEuJ4PH}BDpveRo*3%|1dGk<^L
z$B*#ZyROF~FU|b5Cwtr3?A-j#pFu-5DZ4|SJ^thOFpc$m+@ue$ykEZ;DSztv_KoU9
zgCBS9ADirPNnf7(_a1AVtAEcWy?f(7@zaU2-49<auKa!Nc2dUew>mcyl?y*!{BrWs
zhvqe_`(3A%Kb~4%aV~CO&B?ld1x@Ssp9Tlg`!9xHJ8!?Oc{U^J?mgFok$;lgw(ZE?
ztjkvJBin{DDt@5j)9;s3b3&e~3;yc=I>kTy&yE9k_lw0ZTC;8+%TL#3N8K;1+wZSw
z|MTMWdEbxzzHGB_V|D!e4bObzQp;EU-)ROah41VQ-t_bM)?FW-zMQ>y=NjpnJ!|jQ
zZJZvyUuO1s{daXU#o~|D{&oG<mv26I_R-k0|KsD2EdT|{ZhimzGAC>9{^{$|fA>cF
zXE^(lpYrh)cKY%s3jW%LnEt-vEPwsg&ob-zPd{7Fo#HcTlR(C1UA8TE_t`k!oqY23
zJ9qy}e||jr{rY`x?0NfVP3PM?&e+SP6#kWsTqhrVJEz*bf93i6c{0JPZ`=HLe|Nrr
zYgYGev)f4?$FDFVwFQ4{Opdb2Tz&I+@2U6Ft7<xbUKRgZH)l<bn9-*a|D(TZy6&y{
zQE{k1&!}%xW%M)g7YqLvJ_`Sy;@q`+^Pcsq{Abmyt=yEj`)`tR_r&G3m!2FC{&MPl
zS7FWWmw$FWdRH4->-79Jv%lG%o$F;%EWf&ZcWCQhzMwC@Yk3XdiUy;tch9L;>i^$A
zJ3~(7K~!P+ofFYdJ>T}*3V!+$XJ=XR>8bY{{?jYJdB3rrKjY`m*j!YP?f>~BtL6M|
zA<cKcI>F5u@D79r?tJ;KH^XW#UCW){zgGYKqUd9Z|4QudPY=A@z2eilzDJK45AQtj
z<JFEib+(mz8y~$}9sG02$^N9r&u_oo_vq#Pr|$1$?&n$UU$<j-nb!OZKM#n1vj6e)
z>C?%(J_qGHuuhrycG}6Zz?d8L^;Jt(AH6H?9_hFL-{X+rn`MDh%4Vs5x%YeL_CFCJ
zbvEb0i4mG(zyIBq{Ob94@3?xInUB`ZN2=!JN~`)mzn2YCp1C}Czx)f0*%iN@TEBkw
zGS2U4`OzQief1Uv%@h?c{aw8I{ep|Og6H-<N?G@;Wy{%LTW^W^?(=@y9zWrq%+Y4=
zEI$w5cjEDO&))thyZrNJ`5jSt-mK42uW!Fv{fYZk^mH5kY0kSVYPRm3T^k-fTi@gT
z`!Z`UD}B2zu_K@2e*TD?oojgKZP>lJmzT*{FZ<kY-SFsp@b3HJXWE~>FaA5@R@&|V
zeaWkSz72bBE*orq^z!`p{d=E1e7{3``_YE}m9=i*_9J+$&xej2*{AA1PE9|0?GCH|
zKmC9A?TTin{;L10>mT+f{N{XneZH;y$6tID{xIvGchT&x*;{o_EuWt0zvcIDmF=H*
z-rTRU{l31@$t~(TQW*p0R9Nr3TaqVM{*?9p@x#pP?pCbIS$zH5nZ@PlcmM93oHBD?
zg64kr%zfwn@80v_a&L6~{JvXdyWgs4?t5}?_TIaH7X2~1owVWh+NZI(yO&fPXfU6=
z{qWoCb2s_?zgzh<_RZ(5bI!j5<(A*~3w=!Y-z|~}wx53?ZuyOGYqx>?WsBsm3t`)S
z9o+w7{`pP*YL8Y<)Y*3bzux5SH?L1V_NVFfv6G*w^zMD#U$lS!ojuG8{#^fbO}@}L
zb@POc<*(nhJW^TnE`HMOHSw!+KkDgk|EIe9Px$@m<<_^~ZkY1&#P5n<x32Hk*Eh=g
zr@Hg(wjI^m9X_h;=zsg<N7>~av3I8af1hP!|Bg-LzW40wWp5Quzx3E6eS2BV|7+#x
zceU1?>NbAM8vfJe!ujt(b@mxwzt`UjO?$qMEBJOUXtNKa^{nOP`WJ5JbpOlSzBxzi
zvGno7=l?D{8JoNNy2GjW8s7PKwx9mZb!=Dpv1_i3{jzPhzO9o9-hD4mCYYQ3=CYMb
zq`DRC=f^Esx#Z=xAIH1QZZA52{K~^c;O+r<n^?xv$DB!T_gO#he&lkl+bsT{P4xNH
zHB)-l`)hO;t@|bG{`9csI(>&z^^tQtXJy_io^WSR_2Zvi!dKqEfBWYr>)Eg6i?>AX
zFT1^H&+C+Faq%~%iElkPUElnDSY%wrzCHUZl9Ik2RJFgEchn-YZhqdJJNNQJw|DP8
z->zBn|I+WbNjhGY^5wl-Yjdxk`n2fR)4xX#7n{UyihF(Tu;!=2Rdwzw%I2J6=ct*_
z-~B$~Q<wG9wq18WeazpHzwM@&?Y+FGhUaE4HJ3YZ<-xfdpRBh@<vcE$lV>OM%De6H
z@hf4s?@dk4x_-MiIZO7fdunuEx1D@&dl#apS<stX$UaBPKgDi-_TDw??5u)gHq`yU
z;R0IG+ml-PH)WldV|eX^qj%Ls-*xq8Ry4YJe!L~E-W&V7!fVMV)t>3#MJPXQ{np1{
zkKTPZYF+&5+`xGS)j}?wAMe@xZLPR|>TAH_M|<y9GR6Hgocq4qVCxOBwZ~3QefzEO
z_<_HZ9>f)v|NZ|8G-Dj=WwSf<$QDp@etv{4my+kD^X<<yOeg)E-n8~++3w$g7sDQx
z{M~Xh@?*mM$j6tK+23BfCt~ld>3ygFymNlqX@6Nh`q}5F)Aj4~H|ze|eK$((vDWdn
z#X9Ogvu*3kKJVD`XNUBfyB0fZeQKZmbgl2_UAt}ew;8wccK<z<{Az8nU~lx%*xk7o
zpC`XEK-xWGvi-ls!~M@sAAPx&=~c~?ucx29dMJ`S)8%Dv{a$-ee+#r~xLv$uQqGtA
zYm2Mmy(D7xm+8IS_t(8@zG8L!DH{n<^^HGS9cJXLlIPsL^X{#+@vCzStEQ())Kunw
zE?NIyZ^=4Y&{*>Nd(r#$zu8}(`FHN*r(w5q=X;q*Uhki*efz9OVY%4d|JN`7I98VZ
z_0~Gsl)pxz`)l$~P5!8I>5V>H*Y3}e=Z^QP#D7~D{dkJ?y7+a^oc)hojxaN~m%DlV
z?J~`Gr!3#Edj)QI-hVp{-0@v;&~RN*PR6&pk@5fM+n!S6?7sB!pT*qs>*Rx@bAE5T
zz3BMywqv*7J~Q0<wCs28@et*svA4lN^8wO{o(k$j+uSys8Db~Kz3ukp9Hoy{zgVyR
z-8S*WY>!LbO35BK^7<{kj9$KUR;=nvX1={PSSI*p-hKga7aqI^`9Sd8d#c~2p1D;w
z^LPI7vg!+gmo9An&U%fx%*XlTG5vVEE{<)tH_y43{886VBx!?%*@nATM-8XG{br36
zJ2qF<gz9J2{N@whaChDl@VaMT$qSbpC#}@KIIBBqTeP{^ME%Q0K9z^@3La<M7Cqf!
z*`~X7np7TGFwwxiZ~{E)U~xSTc}o{atbq-4z!4<QaG)H#X%0L@0Tuw)u{LKx+pxiW
z@bLV+w2iigj9@<4BmSFj%$ot`QgMU?Y~BD{FC~KBMeMivbON-w7nyipCkIYdpwTkW
zj`$}C;;TV_|0&RNHzYBrY#je*i0?2BT;E;^4rjSa3~kpB+kk@{i#uK?;&TSLz(sd?
zzs;wr8Sda#2h>%_R@$C{>{mecE5zPCa?c=n0K<LmBhp)|FeVYK=br~B-~*db`buE2
z3k!BsUt3!P8tShHt%3v#K8UGCT9U&87K5aZ5tI2=KiQlJTMK|z3}I$O$XE?HnC4`!
zN7|7D7IJ9D?8Jj59$16Ul^B)<+Jc=obJV<6?oQi0^Xqp`28M=j;PeAILxaJ@y^x)O
z;ej5w^Z;*>XJ9xRc!!aJVMjN(YykKB7#xa4${83K-mSv56wfkGg_HT?sqS*nQuh;q
z-)|j`id**YdG=Jue$jv5L5uh0PwzWgZT&X5Q|)p8{pY>vLQAVHO@G|n)$~a0_2Y}q
z{dt=g=D*(m@9TR0x6bGF_RHN}CsKYse0%Tq+iwrwy#4mu%H;3I<?C&>?En9Def`#b
zcVoYtspWiE`R&hvss}UM>h|4GM_B`5pb+i(0(Jt2p6a~b&y#dwJj?#xiq+Y-t1ef|
zQ{;q)W}w!Dl=|P_Q&t=3-@heNF2Dc$bb~mrS!zP8^E8$o=`Y`E?_ZeC2U=e;OR}i&
z`-?fAh30!88+%tp_bbk^USNCd&KxX*Lv?w!-(58Q4~2evdfq(n-}BF<KhxbK{XPll
z-m5)*Q!i!BlodB`UthGoAjbXY{q0)s_$IOJx?esaB}k-|ee-ST0wVJ_kJj<Ozgr4j
zIT~;$@q|QiG0IlE55d-zyl#(r#W(%^SH3!6O3<U@zaO2yCRDk-Yx~|K`-GM{MaKUB
znW_Ksjy{*Q{r>88nT6$1Cu^Q`&I&typmt7roA&10&B$vw3|eYA-!0s6c!DAFtbfaM
zOO-~Ar76FrnO5xGw?muTEPv98-<hh3vmd?d`=fVoqRzIo>obWkN8KWIllSwV?$PcO
zb7uWHqd3ta_|)6U0ng<5Cm96XNoBuzWb&WgpVYi9CF06KYdd;hF48zXOXTpkfIACy
zyR3N<!Fzi^C&FwwJYzP}tiYLDdT#UCPhO0<7CCwTX_dK8`Fm!lv|F$L?O8be<n1q?
zAG`$(Eg9|q2VTu{*){OKzK!O)3u4gec*tsFwB;0Od)Ke>@2dU#PoYcS?^9fjOqlPa
zS=JBgg6_zse%^LweueZe`J<0kEsOZGz5e(1Fbm5ay`U9WpiQ?(OPytp-H}0Lun#uN
zKY4C^EM9qipW5WNi)uc&=<L4bQ+&U$JjU<y{p!b>+m^cPJLTs8wgVkJ;cN_z`yJrj
ziW%*wGwzo`XQ3>u>HL0mzxVT_$FrIv?n&3?T#YF#x6A*eey6U!>#h0!AN~Jtz*g#k
z_R!AwbX>lkrwV*30w^FcmYf_aUh5QFxE(gtoc*zZWAf3t|1`JRAH}wU2DGHS!Eig$
zYM4J45;ZSRRL@%V`$T4BpYPMRk9R)-FVedJTBNu7{`E~eZtJAH(UjCJ5m$4)mZ2Ek
zjGPDwFSq$~#c`4YXeHu(Ij4zBjXzEi(vPW~Qg!=i#Fg##+3ViQmS@kb_L^co`O9r*
zjk2T6hJPyZ;fpZZ0`J_twXU|}{W{P}o$W~L&M?>YNNngn8tyek%2Pmf`}{jqF{fNK
z15XLpn@#^2lV17QQ7nCD{GF-g-)sLy<Za_R8vJv9`^TV5CKEL@_D8?pdXU-h)<e+Z
zmH^N)L(GL<NQ>flEZ00ueI>3s6MCk_{<;@Ov~mg<%imi+za?J&{Bz`{?@P}#U%Xn)
zt>R;*YrpI^4`f|N-y^>7fp-p0A-L4&?4OUv<-?9QKRPFevEmHLAqhedbJtnUe(YG7
z&VN+aNAeergF<Mu_-lq9<nWpHZ5S)caGkcqFd4dXM5G+F8U}emmBF)ZXj=f`%ML+n
zanO9X65AF-yc&=fc_6RV+GqdwrN2nIK@t&5#t5!mL|(gAeC*f}&`~tRtS%$G8WR@Z
zeUJFg6Iv*W>^)MJP5#NrsS7F!yz^HNb;%;QI|DiMXToE*Nd^MzZ5*l^TTZ(5?Yb@p
z8ho&iUv2Yo`No{Sulqqu-2X&;)4dn{ZQqnigI!hm%AC(uzVUyyof(o~`yTPx6WGq1
z;IM7dh2TY3z`G@5y=<hrgS_?>sNVdVUB2<ht6y7Jsst)1F9j|8`1|($<h6(P)MN+V
zsr}Of8c+IJ&HeX}g59jsR>r$^Ei88!@<qB8x)-uL6I?t@T03AHXq}n)<S)^V)A#zi
zYN|d49}zT}d9Rv!2zcGnHstNnu+zB^ZMsALZ=aY-behMV`1bq$S|{iUT+z>6XKkyv
z?fphOP;1K7uk%4WO}nk1)Y$KjUY}XG-9P1#X5d3F(CV`2sSRg|U5GyKIrQkQYY)Eu
zdXy*seCb?s&nJIVHsvhd@mdJfXhJ<Q4RddCMN_ca?vi=+TS`SvE<1T%Mu^kI^_CrH
z>b!SPOYFKYZpyVizyG&iwfVir#BMi8%N1XIzB%P_yM4-}b2foqCsi!(RL))bC@=iZ
z-RGWL40r#VBXj45K4>XkLJqcr&JaP_6#0JjtI0|6`|Ud(bx+<SF5ezH*@dtCv#&_G
zyXWCODqj})zJ2}w)AapY4xMZS?+zvC-Fd-3m)!W+y(c?<^2xG5y9%XgvANIuyLUJ5
z5iS2#`Oxe4ms{_DMeN|Yn6LLPZF8jlcjd0#{}%0V4#&McyJ8vWAP~^@lhyUp&vo}-
zW!t!C{;Vf|7woX!>n-zy{T-;vJv{&S^ZI|!!|;aUN*t~GdD)_`x^~Z1nf&P7_M6dX
zk0-CUjkuGV-FfV%<L&qy>ARWVHT?J>X9=W6e!KGMUBCUm4g2o4_h8v;fYL($vG8!v
zGG+fOUwnf*-gdV;_&k04SW(ovvi8Bb?RS`u#%`PRQ{#WF<DWR2x!)?mPJbO<`27rY
zS1)RyG~6__mw9K)z<(Xfs^%Xnn^hWxmezFcw{21KPJgs={eAWAu|2LUpWQe79(wzc
z-sJ6>bsN4tj#a<i4BG~lzIn&*%k%$zx$@nw@cMe##vD*v=fIm8#`jIbkvGerEQ$r4
zsb*7>WHLRpa{JvvP2r_3n*M)o#yl&Y`?Qxma?aDb!ti@{%fD{CldCc>Xwj7jwOjX1
zr~f>?>S=8K_d=%?pgkb%&vL}d?PaaIcGs=E{SI_~P&MuYD<C_t_G_G)qLHsNS!3$o
zug>aWiOt+Q0>aGe{dYgglmGp7|NDpPS6;zQpBD)(j&sVPTl@~ZnE^h<1CjWde6Vla
z!=dv1Md4M49~%4+HtYgzGluS<!?!Qa-G4=l1+DkR*;LoP@S3&EZw)&!8xuk2nJmD)
zH<Icb6Uo?Y3F^iZyEikSd$-ze(W7&%N!)emdrcX%FID*2jslcpk{H!^Umn@!eO~9?
zwbxs}e%*b1>7#YNhRM~t`6Z#9DBox8ir^|~*5Vz;NCOB5RJ^#s8zEtP3XrxpX7r(*
zP6a)3;{sZ6FWzCi8pnoVgC{#Cs_-1q=ARI!khp2$;&)ryx9;)zd;YqX|DQ~q*~x$3
z-*lO$VL$Ef;`g5?oN&?P3_pL94{6Umc=0r3E9BY0J2OL3bM~gGE%Styx(T^-E_oUB
z=w<}ujLvoOyStBuUtf=O=tBPgc{!rbQtux=de<+>-o7IEPH8u|JBYUPwaa=lwlZqx
z*E_<XrONU1FKq4nWIuoXX?yEaMT=ZC;~(AKKIg5|F|W>9duw%naUCz6^8fGRqjz7%
zPU`$#_+i<O*J7Z$cGhCZHe%Qo>(fss8Je$nhjKdT*2&isRPI$M-hN-doy%2IwQi68
zzZ~6(<*O@hi<cj6-L&i9=gV=IcE*d8)zxi}JN@Y0j?Ppo&~<<N>=*6W+yM0r?4%3m
z5vWKfT~y3-7U~G{T9zN#eEoIz?%Fxi%kHU6{C?T%(6ytnAB{mPc{Fw_^*>q{4Q|W4
zoB6v&<~Y7H-E0m*7RKDN>Por%B%QC5WmZt${1(sw8CLV3E^f&Vy#rbs^Pt=I=v+~e
z^26HiuD$;1Y=8Vev;Frowfj!~`*G%P*Q0gTdbm!6yjEuT%f_Sc*`{-|{=}%g)cOB!
zr)SZQ&%4~acCXiXr}I`^q`X=CUCHgKkJd?xU>?Kq{r^pCXN9X%&FZ&zKhaQee>g2T
zdTYo22fHlR9WKm1Y96ZnX{U0(bJ1D9tLkQ}C#-QQI(zL(*V3%B7Aks0DyIMba-ZOt
z%(qb3>gAHkpsx~bKYb_V#qFB!c?q=5b=yuopM>etr|t`SbN-E!NPNZQ>6?9m7q`CQ
z{ybZ}{Qvv^fA<F|=zem%qxkNC%n{ie2ikveo_*B)=fhKr2D5Tj@BrRrv+J##uO92h
zYHs_lqQCRKXNtAI_`Hska^uaFh1bm<UJ4Z`fBVY4V|Q8e4rb{e0rm?cYbMI?lVQK`
zY@Gvmy!F<zT?USGWl})<2^|)N|4sk+r6&5V!KCTtllMG3dbj@n_xkBfnG^lzE?V(c
z*#C&^6xKp^vkwdFoHqYZvahk^TW~hE5j>~8<!otUQ&nVZ<)b|H?u##HmK}WZ^Vr*s
z(?9g=UI)6huF<l?dP5`sSK(Pl#eY6LUC5C8j_ZhQ<&%labJuYT-#J;Q`8ZA?>yJ+7
zx6k37Y+h5OPJceGBx?QB(x$fY+p>)^UVm+m#D)_Njd!W~-3x`5vI(V%E%bQQ$>QZH
zu+DDDy|R1aQ!CHPfQ<;9ELqBHBv}5I4Ub=#xZfyAYN&dBO|gjfkkMD=I^XU0W!WaL
z_1mm<QbC(yP9zvjeQDDFbZV<kUy#nbORIl>nz#Hr=c9AHpo=kP;0y3Z)o<CAQv50&
z`xTn^^`vdw6Q^gjk&9QYVBwl||75{#Boyff)I7RtKo?*bu;cT@2F^=L@}OHr&N$v_
z<gHmT|ANlG6a4Xg%o)Yu3gBV!+~U|73^`3(POulY?_f4A+b#QuZ_NYezb$DWUF&`n
z$vDj3%><q;%AEcB5KDsa5?4Er|E}CNGy9!9_jlip&&%~2>#-yTCb-?Na;0bg-FU9n
z{m#$J(+}9gQ{WEGcbCkkJpKDO_TK&b+JE&bpG<sicD^)`2%V<)-9aZ-GC$j?=fhy;
z81)2nu)5>k+~m#n*LJ?|u&)0l^rKz>)8Xll8E)MXH9s1AHTvx(hG=QfnQ1ZekUerE
zd-ltcsO<VR#rFlv-@fwBU5^|_cV@j;1|59H_&G*gjbXNe?x)E0*FpY|$eLZPBL3)I
zA+Edt@x)|CQPAxz9o8A!^tbNCo@*c~L6P)kEAJz|oUQJ+U#pvR!(HD2I^ov;Hp~Iw
zED(2F;oX6->Me9M(p$!C6GywylK2S+0}dT^<Ewmscm2~$n;$jnxl#=JQi^x{EjQcj
za7AI#b)(<kzG;2@@_L`|<M7JW4{czj7$HY<t7vmFBXZoVFRq%Zjyonj`LuVp2ivPp
zdpGK&Ilt6Y_2NzaSoQb4%IXg)_q{rI&vj`&y?^_Jn+5_)r|>MA`?a_cnwG0`n|Clr
zzrFYkN4fbf-Imv7rNg1nPfx#|ee>m4$=rQq6P|i>1~GS*&7AW#=9gFJESq}K+H}6x
zH(x$iJ$g6WL|`e?%p=o(PxG+h^jlPr|2>9CuQgTQJb6CRzv*Ahwwv=o{q~azRkr)L
zO^Yn>-LrSz`X27o(x1O>uRe15VB`&6zwp<R-MhsrUug&Kol|@J+|uP!zRZtXGmn3X
zt6jg&yH#C0NA4y!?Pyl}9fXuncIWPkTR-=GdN@+KUi(JeIne9m4@<*}`h7dBV-1(9
zNa#L!nyZ>9Sy&zcnjo2M@%;JoH5ZlsTh@qzb5Zv69ntHrckG^qY{8+^(;qYJ&h^`C
z%#J7uOg~IJp*L?{UhdnoDaoI#f4A}!FS+wtX-|a5q9r@L*RMKVJMFIDqJ2W567S|K
zf(xs+Lgl5~*ylI?23?$5yYel#E_nF#bYa6?v*q_@HpA-?rrkNu_ny~3c`xKz=gId=
z&(8@qih9F+FFfc@=Jr={MNhBYu?9QV`A(x`hjqp#Sk~H8W68JS_OmP2#RBCxs@TtO
zH)L&@P@8D?Xx(biokt05kN9T2@xJ`>%FjBd>JP3JKZ|4%wx7Li7ndW9$apLIx0fuv
z@o(~;C;QYVzO{+1P?~i2?3rgrW3PIycwKzo3|tU17qZ8`^nM_}k3&DckNM5E%G<}g
zbCJr<(xM4R!Ko|m>-?jaKj&^e>=Ad*=Tlb2vDkZEo5dC0y=mA{ZBuxB$qK1lf%4zA
z7nQl+-7aUDWM9kq=dd_5obrEHZ1hEx+zaBu66fu>eKM(}YFVs7<-Wq|H>#rHQ+dO$
zZ;lAvCb)`k#UqP%e;jxU*;6x`cdWiu*0H;+aYyr}A4<@$%9YpO);ar;UafQFz5Dl{
z{{6f6(tFV2g*;G!w`20(pksR-uKb7;di(t4+ZD-`|00$osoS?N*S~PjL{IaqSJ&>x
z-8QkiSLyAQdjIn1tDg>co(7jXJUtAy(cz9`IJg`>lx;V^x=<#ekN@#ev%>6s{h(vv
z*v}Nl&Ug^_ZIgsnV3tB)nqZg8JdXuaSRTG|ewF*YHgM+kGn(4(`aVg4GO1c&(Z?#K
z^U0vhzj1rDok00dSnTb(1gcX6%S*3WW~kfsh~GZqTNwT|Y`4jQYi@FtPfVvj-(}Fq
zS~ihqiqO(3qdB@Neba?npS!A81xGFozb!j$d31QFLi5RxWtVNHg^O*n@Y=Y;d;Po1
z`KN97%FX$ntGM~$OS8L<?>4`G$6Pp_A5@yBDZE>tUCa3g6yZnPKPJuIfm|IWbpDN+
zcZ`|ylKzPW`imoV)=%&Dn-gBCyDVesb*)G5G>&f<k8C^KT`PUcq;BeVsdLPa^dL1f
zG`QSFT;r~k9l87X;bD}hX2@yUaT-!d3zT1&x{u}G!|o5Co?0A`kw1o#&Ju)=#DeSS
z8I3!d*L_j_z#rc-UH>@avmXX1iJD=y!aGRwlIMtQ$x?7F4oVdU$3cEV6eEl`SkOEU
zO^ueI&}Kn2L=UKS?1r>S9tR$kE!|v=NVu3veH=co48G$U_~g$IpI<DG_<UaMIV>j$
zTMMuWQVNNI(&~&W?RucQiyt@c*vyS=8^nmMwU0V?G#iyf-kJGD`^a2SZUIFMYhk)L
zqJ7!mJEP%Q^N!EXcc$)K)a4my3JpR~2sL3E>v-p<;=5BFl4`D3p|NsYxf65<>wEPZ
z%-9TulteGQ;+g(es1#mreauiSP+sN;Z(=jvXyMGj8Yv3z-ZUW!z73qh7a&0h@&lqY
zIWyC5`Ieooh+>VwERkszEHxewQ|mqnZ3}>65T#MhgfMe)Ug7u0$N7)kZN}5UQ(FMZ
zT5fkAtvk2P`Oa2u`B&JRBO8t+Dt8xXIR0Xl<WY^uc{1VqJy6nbKL34{1KVQ{v-Ur4
z4y#QnwEt0&zyHDB>)&*xzT5wcyC8p3=ic=qxfu=5f=iiR9zL>p^&`EmMPB>cckJdr
zB75TyN<ZhQZ{hTP3w7SVfB)&<zqps>paadfSFYn0j!=m7l+XxVrGEIP)1wN_i%aS!
zr9AYSbo%={CCL@1zaQH)gLmojDH^6zj=sMBCPj2!%WZ`z8Iq@sW_iSG20Ci2K9X?X
z?q6KNziRH8yw!`QOmf_^xlRw9NM6s|vHF%=$L`+_cN%q3o6IQ9!5#Czf*J&z;U}kG
zH{X2u_2trEw;ZP_t9tRO+)6Fl_IdJz**5iE`$9PQly1iE`>yl2>E*9u``)G+23h`|
zc0$YM?d_c8?=c39XJMH-0WGAlG+V!KnmqsTJeI#Zb2i&Yw}PDgrK&Dhck||s>Z?U@
zs!|%D8GxT#pZxryYE$QD^xpSL<r<fjoi^gJrQd&jF4=mw;^)^@`yU7PwS%rH5nZ=t
z9zQI;*&gxbJVa^tKe|>U5329^XFT6!;8^=c{IK>TUH;fRbJyK?{W|=)Z2u=I-Y3sQ
zi)UHvNl_1s?|k)?<G6JKa<a6$;-4WF|D;|2IOCR`+KAK}z?|Rt=F!WS*RJ35F;m;W
zIsQbz%I?)4?bfgA{(Mh<{=Nn7-G{&W2p5(sa^)UiF@cqj=+S|w2M_4ou6+O5dz1Op
zttXj;j=MbaED$SvnYI3xXhponl%n*qi=J}N?()sHIUS++ZWa@`t0Pd39^i-yf5Yk1
zUh$gW($B43H-FDbZxf5!m3?BH{#V>>+F`x#L~y+4y(Ed<U-It>l>Y~9wC2Jch)4~9
zuOFwa6S-YKY5JY-Dx2ocXN@X*8lnB@-H(k-YlCbh&xr{g2dBj=4s5PJ(`Pi?VkGFy
z6_cBF+`Ohpd3;&*UuWLD{ME8<pFU0dyYr^;J0G!q71h0|Ry^n8?=*fnJ~4+cU&w!o
zhUwJOgYW-cw*MQf2~O;*-DHl>&E`LHw^rfZ0WqBMrN7$1|IXVKL#xg$37={TtKWqC
ztv>b4)BbR1D)-G(dq9Ug7j3B6<Kytz@lNRCb&hI}*6qb-V1fGYr9IV+D?V;kxpn^X
z?bzd={%rI(>Q~3-AHQI4W{k$!Nzb#xuhz!(evjGl<7iY`<Ei`Gr>nozZjR3NK157{
zfHW*lMl&dNstakTI_~%-kbb)|KIGZf)u3L+Qv3h!{=C_fuxsDO{FiHYDM!9B{%v!L
z%hej19h<9eA4{uux$_g}h(&}$G((bRU`1TXBJ-)CTF3dk!Kbqt&G1RJI-C46Rk1ro
z)N8?%75`iorRto{D2n=^#9?3D@BVYoF8$){++F#57oHK@c;vLlp@W(7hpxVT{&;FD
zw2A=tt(700<3}xgkW#zQ@2xhy?CK|%O<94|#%R)Yi+}ocL*1l6``tTS%H-E|?0y`0
zFK(JposQo^6^XV@H*QTYJFfibofN1COVAdE99T$$JMe;q&)IRM4{&YdFX9R^HzI3x
z{{4MdZ^;Xm*Ws^bX7H>4H=ON{mwt0UGFKkg_!Oe@ypb(^MD|8j|F-Mc%N4LYz_sGH
zTWp2w+iop}bTTjpoS+Q?=R1viw>jQvT>CAf8hOa$(Xt)h_XDPV|6X2MU%&p#ZcuOH
zw$1fc&I4-TG_LsW0M_0tO5+w0fN!vN?6H*Z3Bs_FWPPqcdBSSjTXD!^b|?)^e4cH%
zYu3N$#Lv1iR*W_fhL@pTo|Wa#5Gf4o^!e_h<(`ui-W{ldjyCM9bNUSLIiU2iz-~Fe
zxNG;@vfEyT;;w>^)-6?dx8UTyE6;v$o_!2ysOHTMet!m|O|-kLbGOxP=E8D$NLP-4
zCE(ZvwZQS3-KfeZ9ogaxYJ?|fJWNt<-}C+5^-m^pHT%L@jU?PRSw2aZH=Ee=`{42F
z->mQVZp**;^gcJ6QQx{Zx938O0A^!>@(U^PzrMYl{rPXpw+ApkY_HsN!wgZCB{Zg}
zCN6MUIgcluyYul<m&yAyma1@sPm0-BE`HJ>cAxpQqd6M3OI=nj)QQ`lroQ@v${n_a
zE~g`=U3B^7)yd@)sT%q%S8;Qqe*JwNq^b_qbAt4|?>+mNbQ{qkKlpde@<t6&j~!n7
z_UxNEH*WsA%h&lf$!G><DO}W>ym{{YmOD>=1}|HBDOcd+yH9)5e~SBDH~+4Cx81X5
zXMX3A$(LVm?!8-l&_x4QvBGS7eY{^jPKJF(GfI>AU8=f$yDjIh;+tvp+dvZw%`d+G
zxfPX`F8F=b(>-1$0gFO3R)5Yu`T3=H#h*DT_hz5?9MKshT&cI`)w|HTG^6$JXUopu
z0Cfya=byK>6>z?@GrxHqsOb&voE({Z`h9o-^P_Wmi28R$|KFqv*F8@ccJID?wW#**
zt38hc;}$p0h%wyGHC4lO!i%r-YK_}F1MEWCLt^DS6yM$1?sy&ARA+z0x6AAL@$Ot^
zP~+tZc-#^;SWycfteCoMht&Jet9Dtu|NHSJchwdPk>`17%b!2zeYWZ5{*xaorW}6u
z^2_$7m1}(GO%7*LbAmRCrH|Y#+PS9mzMw}P$ni&HOQx>t7r)Jh=$E|NH21sRewFHF
zNjkO9=1jVnRA1-2pXoifYF=sW?Y~nJKYTrHEn#=^+NLema)Ra89q!o9+Y!A!-@aL>
z<d(v_Ro|?S#O`*u;}|JWej#+1U0jYdB2;j;N+#{N{nsWob~&4n+v&?)+aLaX&s$#?
z`$ef8v^-FQRd`{IKzYCVyBQ*(ux>?%^$V?7dHrp?i1Oje@#tMaIsZN5itbN7QC2rC
z<L1=lwH>?9W*YX)3C-dE=)$yAWkxPne<SA#S#Y_H&#aS<Vv9FhR9~$Z^FP1+DxY#?
z<>`NS-bj|Wc6;Zfu@>cNf1W3_blE07i?;f|*Xwm5PVBHYfSGxJfBpAG+dj*FtthEQ
z$!`JrKUeR1mttsTds%OWP5d3X-%~HI+EjVzd_m|<>F}p>zr8&rS}U5UGzDHzfV%33
zr{8*ay0F0#<mFx>hdb7RhC4Xm!yVI{9m_t|yj`{H{OXVMy2WPP01eEsT;9|E<h{x(
z?VY7ZV<Ts9JOzzIg9fF*UBM4axBV`XN$>+D#>dEw>4SUUq#A}y`Yy9mrM53-$FB)h
zm~E39#qyKgHec7jxvgbVbqs8H@bVqMKR#~%{CGFpqjR;=CA`pn`;0Hs^-l2bTP(+a
zWNvI;*X~u@Z!KlqW(L~Jz7tew>1^muSpd3+_hHV*(x=z%g@nBfEo@&3zO+!%XPMF5
zXB+=)n&7H+BcxvGqS3Te6HDC+!It?uk1wu?yE}d7)^Ex8e;H}rGWRwRJhj}f@cOgQ
zy*rBUv&BB1cr<pBh|Ok^sO!@Y*n<+RKzZ3t%)yZ6$tl5JAs41!)R}huw5$5L^K-P_
z>Yv?7{HwCKuHav#!rwxb+0JFK_Db^1-n=)nRpEizuk&u(?X{mjzZdSX*68-Ef7$fs
zf%U784tH*{A~JY_Fg%M+KYF*u&i&3-4#;d(EXGIxES6%$%9qU#KQdPyI+lY~A@Y#H
zyW0oE1<C`&j>wjX9+?}9s00|yzzOage_^=W83WB#;OP0m^oZ|N(~jnK7y}F~uwj?E
zzs)|d9+92$bmEb_C03>T<|p*$-``hxvHUg@qCh#I=F{@YaOQ>j-{00=dcXB&jWV>f
z+nLWC4=O3-Jnxh~M4J=@Yg(!GK%l&1xBFtho0C*HAH8cds8w6~8eExSP9uVKfF~Dv
ztd7pj1T}sgufJ9|>Bl+|VIX)4)@=oa%C0#3g_ZD$9YjsVc%!8=z^-HWyUyM3@9z)K
z<3AExDo{?Oj_O;?h2gSCK!Mb{?z(@5Ts&q^5*qS+h3shx@9u1G)Gyf!Zlqw$O@f9&
zK*b=qjCsC~w`Sq%ufnsAW0{L=@P#M64(so^54dC3&%a=Ub=vF@q6!5?#*3=IEzht`
zn@zLGNfG2z1<m&@Z0YWm`E+l0{OQXTAAZJ(o=A{6`E0`c+8ZuL@7U$vzZKu}oqPR6
zp1it=?VC1L$l-O$9g*^v(x*QC`=|H*{rjnP(``PTD4q=-?wmBWr4cdQ>HBNZlt~IP
zo<%?J#cEx?ggH3EavybY<jJu**|1M0b5EJH7hJKfoycx{Gs;HX2PNI2MM>V-?}DJ4
zJR3lRGk4BcNp%D@wyb_~`t|IaFTcLDs(q_)dLn3A_N|fS?Vp|}eCOG_#%r;#Pkf_y
zzj|8z!IId*`P+@&$KUL?24^K)5n330Cv@*sJ>CslLA%$^KHaJ3Q=o7C)AEhyh54_;
z*CEZV+>AW3H_LLp5bu<jd%I@Y%vY0r{9NVpJ(qdMy{61M@p<j)cSSeO`G+&})$N=1
z?`|~S1dY<}4v_zS^g~z0X=m~B<=WqV?F>J<*Nr()Yr@TCPwL)+F6IcCm$8KbT;~!_
zY*!9MEA6hR+Vyp-`Q+Y{@85_Ug}i!{wdefmSC965KfavvWJaOJ#{AAThyL8I%7wSs
zIu>yhvWMYJZe=&mRnL!~w0Gs2-n>*_m3b`bg4^x)FN<&d&id9YhS|h2LmpgOt}>kK
zXMIzyWA`&?Zx?5VhqXK&G702=65{oXU$waPjeXp9{daNm{LXKiEpc~O^`ra$-rn~D
zyD`@El~jt-yIb6#YU+m*u3`jrTIG+<+fCZXqr}T+Up^#p{nNUDQl?kG?riUsx39aR
z)fFRu-xO4GEXc;6&zr0)Pb4jIS=s2a{@3|OFMn>km8hbhe{=q9+sEf}9(FI5F*oL%
zA|$%bOZM>o|G)Q7Z|V%NTPFPd&HGZ&I5MbKJN!lFecA3?zd${3T;-bM-Zh783b#)_
z`r?bvZsZY>{hwB!dbj9u?xu&U?mbRb3aN<$HI+78HVXyK7H`BEW#yaVPwf!zkh1q)
z^w(zZ-BO+N^4%eCo;?5Xh4t3#V?`P#{N}BX4gFqedT;Z^N8&H1)+<NKyt0+|Y3Vx8
z4VsfEgY<U~e+AECVNTqC-!%Pb0BCB{s5?Lf+?3-8mk-LfwvYW;_VZRKsJyr|zrMV#
zEY2WS`rYHGWnP`H&Zb6x{+WQ}hYsrvSLN1y7rxburB2vzKyOlG(4r9kw#}_aJ_arN
zu;+zKzSin5t9Bd?a`Wm8YUEK1p6T~FqAv1;Qe^A$^vhq>g>;i6-6mgd5_kMDv)bm=
z^Q*O%+po!qE#E)8I&?wo3=Yxx;^1lVE#PVKc3d@=&PGsSS}-ZctCQ=O(X6ANs&>9O
zQmJ|)=}Txl|7&&0ug#y&Gr#OtzL~Lok66d<>zgBVb{e>fg3O=3%VpwgM01K@RfC96
z^sv~S`|t5_{^!4MilR0Pu<F1%p_(Af#&+~MD`?Qq8ZveLu*!a+EzS;iLI6B*AvuO>
zM$7r$S$q9;Sl4cO`#ObpQC!Gb8DYtD+yf;%JYDBcFYeqOzrSv4(4DJy<vMo1Ldm<J
zsS3z+ElTCl;42{^0*U!9$2&;%Dq^7Gj!1cE{#I}1oLtb3+G0?ZgQ?3PxBqV5^P2dD
zvOg5|Oj7yy$YOy^hxKlhF?@#E1_l~-`k-+uk!Dbvc3(hxJd^!L$BLQPc5ahrpMpNy
zgYGm?`>RGEu4DIc7PNUGkjm+sm{+~OzrVanp$%ksEOQ~K<-u6Up8C<TLh+rPFnTKz
z6sM>7R_wBacan?mv+ZjD&DbjJ5h(BX1a&2l`n8BO)0_k<9U<*g`4;g<?+jo5s@Rx|
zGNf~0!H+$lY1056aAbnor;nOHINh;T1NDoLx`GjpHcWK2n4<8vh^I|R&#dS~_4_(q
z|HlWPSBEMzgBt5~-x7sS?vSt9vpxR9y&Aqvku63%cK`1g#GEkOST6_j`a1q2AV<N9
zY=w6VbnH0vkK9eZ^c7`1qmdO<{$Ovfs4$oQycZ$1dEu8SLQC5=Rs5Ybcg>;652Rbb
zg@^D<ZB;Ff)KrywLXoZNFR#yc+0>I9>BGKU|HHq@IlA+?L0M|)n}$`dnGHb=$rqrh
z_0Zq4kJiQFbPaK%D_@p66`+i+RLXS+d9hu5cl!127b@@Dy7yi!J_ri%DY5~jwK(E`
zGTPVye5B>?tF55ho+Mq?Kfiv>$hvz+xbE}NMU9{hpL65A=lM_W`&c}wG9Nr6?)zlt
zhgG|a)BbzLZL;^Cm%3)kiUQSqvGeTA&5u3@l{sAf+9&~v?-E{62!Q(=N7)~??x^-b
z8(shnx@i2wnBs9+>5w+N>C9m#H!sipdv}(!G&+8)T<LvBwbN5Rd!D;kIcV|3&-Y4@
z#&U<X#^Jo}pPlLy-pL8e|H_+<=nOdW?or*;y?l9ee6{h-8Gp{zDLOCJTX*dDo>hA1
zs_ScJP3RG8e?4>dOct+`Ds_`<Z6;ql$|Qa`Q)hktxBj^xOEs+*y!zGhf8tTu$&0ce
zMTx?@1w6~XE_|CTbL4LFBj@|MNUJtBoG!cf`%lvw-_+b44K6m8o?9;-H-7#_`@_Bk
zciW;r%scq<)t>%V<3lBdT{ClZ*6W;xN7tc#wCw6|$8q|{h3~g<9)T}eyzw-3>3Wgh
z#?Qm9``>%=bWcEwly1uZkGpIOr*AKC+hyVU|K-vT75|>b|63};!}DpS70B)KpaNhQ
zqI=k|qgn4Us;eQ5qCH0y``j(%gm0cZe@Sn5(Hh@E^F1O>n%Ohiyh8NT1ADnw`8mYS
z|Gh2n>z>kDsB=Nxahc=i&hPgJg-VC@3nRNPcg>KNXJTs_-TM6O%)G+z9Uok^-W>`(
zcRs)4pz;6D_Wy&q*w}uC$Og>(7Z<HQ4-~f-Oywf)Y!oUi|0VPTG{)A$U%MUmQj~K$
zrQRLM483XdGJVIYH+ojFAIsZ!Xmf+oWKs9syzrObZ&`hG0gnV;OfCHW_V)JOzpNjv
zvxfA=`)adiz}5o99&6usTP?3^_ZQyO%KG~0-@kwN+7CLndFNTs3KG9>-jd&$0w1S)
zZkfNlC<oMVasW4+p58=lI2Av9BqTjEcCT!i>cSxL)i-W6Lef;@nqSqqjNpiIn|}1J
zZEdXPk=W_To<ylKc1+)^)8;ir%414o3w&~E0+s=sgkAe~*1x<j?GnHKiI@2DA2CO-
z@qy|@@0*+{SMO(Y@9W%c6dq!TJX+AOqj}w?+i&;0*q!@m*^bp!t7D}SvOy<!%sO2h
zJL3S;ZVxuE&LGHKp?Bw@&x?fju3U3z^&>))PrLq_!X}^m_v?QDvTKr~#K})Z_qVVb
zzH3Jcg@fjW*V}5pL;BpHfeFS!_SmD-LBWsQy^BcNKW+KP2P!wG2#J14HR*o(wdi7J
z$;J++FX`uGulXCjVt+oL{gS-<Cd-uX4`=PLKJ{_O^a`^{bstLaud|JQ53L`BPpsO1
zT?|q|T+xia_PTU!Zn=MaI9K8IrQp>qe;n@E%I!l*!b}@DK`AJxj4AT#_ghThVy)LI
zwHrKK(fD%h+uXHC%QvTE)P7UuI)we*yR88!dxOUTj>5(Pgb*1V(xRBYN%+J%e;dK_
zcei2n7-)zAvHTfj^#;^&H@|kKUq5=cZvXl()ur!tzlW4n#OjN^`fWw={aSWVl7tLX
z;BnqAmq2*_1cl`RaZsNHzRX(>WxfRz)hoS4ww6BXBq0Pwt$;S%2qhKb0}3%eb)1O#
zsjHq(Dr^37*9h#5vgHRCA+d{AtQGbL)#opy?(eT(zxKTHJGpMqAQ^nQg*T!fLi!xl
z541Tdwcp#PR{D2xwHeLyOP%#Fvvfn1o`l2;70;mE8d<N82!oR9F1NY0a)sX`P?LF4
z@SUak8mE8%-o0o4{_tP1pfh)KK`XGoZ=T1tC`93**3VDB(#oo8clpIzpC|(N+;{t&
zE2|SKn*7}V;&iTqjw-uPf1md>-XQk=z5P!jk9m0-+%_o!SwBTGK=GYGdA}c4i&57Z
zmVGL|F?oUg^xSXhs{^L&+9O-4i)Gc!n&sejRn_m;F7xtZOSjMTTrj0atZe<7-E7Rv
zvf$3>_OnGh*Q~WydiQ4mXao_SH7Ct}wC>f~vdo6Hy*8gtWb2(TO>FvgL%(fN$UOL1
z(XXqO#~1H`juu&b-yk8m_q-SnPl-VJ_me$VzcXXs7WV(CEO|90repW<MX1I{f35|U
zO|}W3z#}l9m9-~2{L<Vf_XE=G(~WjTJV=tzOUeGyv!}?w-~xDvw+=d^yA^p!I#Njn
zS%7=uUdT1KBAtm9MU%1?AN}`dRvqg-@h!ItK37bg-~8otl|tf{DHd@jE>{#(ovmo(
zE|!pZ@`dxr-PkJ|<4d<6xBc||;>zG6MSKYpy8mTPbgX^l<moSTF1c~vtlyL8d?z>M
z9(NJzUA@1vr*|htG&DByfkrvL-G<ESuLUn12F>a_*yhetQR{!t2nrj>UJ|r<EHUUj
zmeMw(_nJGawBOA%J2`D#(~jN#X<&D@2X*Y;g<>vfsjY)8Xt^^|PYdhn-A(r9)yL-E
zJS6_}$mHzb-#llhc!xXQxvOsc>c;wAx1BYQ#NLJU<S$<P1=_p=TCcfa9%!*MQmd>g
zvem1^avSPc61Vr0Zqv)5sr|=YCf#{{V`)->f<5<<*hmSUSD+qT!v0*y@_;DN@&LiO
zeKPD<E<d|sZH&nDuq8Hy_clMe1YTjIc)sjYamBAsZ+w$2MN-tyUthQC_a3SDJ2MJ9
z&-ySeb!lBaXa4$BDUHCrJ9BjB@v}8sf%?Ta@}X-ku7TEEfLD@!-D3Im91kMI@0^Yk
za|W$@JEh|^@rW=dXt24~WAEEN`dXjS#+L5i*uHtr>6_b23cFsNKXJPK-~ucWi!}no
zZnzo+cujeAvS8Z;i#RWldE#?l_}Yh;*y^Bc$C=)$GbyxUSJpcFiQwgabHw&s2<!4)
z|L%8H_S@s{S2wm?40=?dxH<7x&ffVmLG2%q6W-a)3_M<U^{(9a6Z74d`<-mvQLO{1
zN3n)2WQ}k0W|iPYO|T6-g>jtQBx*%(9{%O&_V>Y`&knypOCaCaJ?Y;4_@hSt`i*DY
z{&v?&d+oR(a&K9*C@6Gy|4wOpTkADx$+vGi-2d5Fm3rwNxto0PE6%jSw1KnPajv^q
z`RAX1@@8H<icMS8`s>gse17CPBp$X>xyU=dYLj=Tx{2R@Ecf&Ciz}Kt1<LzfL8G(X
z`j6I~nfh+schNTuJ2s<h1Px&tKtsjn{O_WjCHvMtkb}&E)gn?HgIS`%3h)G|CB!EO
zE8C3}-Yr<I@a_%L;(m}Hz(whqmBHH--pO&Fvz`KKXR;Qi%OlcMgRcb7s}R|Mx8HxC
zgAF5G(To--?`M53dkWN0Zo+ivD!vsp5*?7$04q=o2d&e-jc3DAvm-VqL3ANcXd?UZ
zl-QBG$uK{H7FSDSUC{%IY3n1hGlG}rINq@pn^UgA{D^N?7ysj<+t8N_B?N#c)rwzD
z(e2oMyy-JvDril^$3&DFaQsd{tQKIHZ6I+4T-wjEO6`8x^6hxP{ML8YOe=qb)@8T9
zzw=nI@O#IPOXasw)^PK%mCh0<&z)PL1fFJGvHARU+l70#uiyT)_)e(B`vA81C+v^j
zef+Q#r8f+YE^x^Nt&9uqE#%n;Ubg+v8?{#sTQ&Stf{0ba+dWn0v4GZ>NS$Mb$I)g`
zYX_8U7W&j?YzB7|I;?*q8v6&BPI?`3Ky;MUY6HDI1=gwTta-0Dsc~0LzE1befGV%f
zAm_+Eb!Yv;9(sP@b?Th9QD<@Im#IRcEt|Yfz0Vf%KX*u=@VZDUTS%cy_^-X&{GgqH
zD>t7D;!1@C_7we5d7^fH{vv(Rre=?_>F;e%?@!pJw|%{*&SZtZpWN=4x`r~g?{L0j
zt5o`}5-Dw=<R4sniQw~H`?$6~`Ke-i?7Zi*y`47wQ#DK{raxZ&PAIaqaYcgCWWz`6
zJO#@8HQ)V^30Zv3u75|h4k%VJax-X}D`3hg;rz-MkKUCWjf>xJ^}b@t^$Z0sR-@Z9
z-kyFr?Y4tjq0(xB!s{xadSXU!`uzOeJ7%AM4jO>~Hv%#8ev?#%cZ#^b|Mq>~(l#0X
zocq_Q%_}yh_j_e%?40laeyF&(bsv8FCPnwML#NdIyu+?{Ou>^I&#v5jep~O|j=j5}
z!vml>eWbGDMymDu+B(N?%Ql(qnra&RGW2A|M)-W!o!2*)r+?_R&s*(!$MlZ6KzaGY
zO|}B%XM@w{uP=6rUKStATzGx%K9+x=1xcG?^!C2kjl658tTOVY_R)W5c3%BD*}Sro
zZMpuHi%#F<*GCJL&z{NhDu`p6aQXk=`~OFC!Si|geD^!HVxU=Loet|4TBtqPre77_
z;azX-PkO(r7J`lLh!$?Q)NT9d3NkErqHZi(Vfp+s1vllUGvColI`;MFd!^EEKQ+3t
zvaOHA{szq<fi`C<yp!XPM;&0pwvl)HoAYPq6^3v5a5S^9yYbJNKW~j5y_^64=X~#j
z@Z#pp=hR=xbN{}Q>e&4bw5$nh7Qb@Zb5iQjyMAJeFB`vYI{A6}>W6xsM`!E(^$D9A
z>zVOIHSc?5IS*SYs4>ek{cYop?0HtdZIHG|3Y7P^>!XYrJpd2hH1&%{@Be4B_wLu?
z#E!>>;QdAC@0p-1xLL1Pw{d!|jQ5<wH7i_JE<E!%;!#C)s7zQRsP^V7WCtY?!SeoQ
zen`tO@R`M=C%<B)FUZ!s1dpX)U(Jbcv+!FjP$Ba2{C;bDYyBDPwBH)9K4k_^j!1Sv
zHZxB`X`f?ltfWqj6D^N81wNPXV2ak|Ou5tg+>t7)1DKY&V4Dp4x&2yP(~fMhBX?_!
z4yRThDU5mf{fA7*a&V@VL0KF;9m|Xe)=`?zUK@_SaC!?~By92DX2L&<NoN&z^LOmt
z25u3TY_!E`1KL(tof1g10Gn$NMKME8(*{VFV-9L!fb1Pd>T+!0Jmdte{oZ`;*nRvU
z%03WI<hBe4H?*<_R|M?x$oo@Nkt;xj;pRw9;{{H46yM3syqg!E4Ju~%P?lsP_4ygh
z93x(UD&&Ct+gC2izrOQ5TjAX<<o(wuLqjZy3&Ab7zuRW|E#La>xYhT+QXSUjwJQ-_
zEr#58D5GNnV$lA<Y^_P$h2JeumT%)Q+!4IgIvc*!I>3MS`s>-xf8S<BZbm{~PDCds
zq4Tht*u#LPFQ*M9yms6;q4<99Z_v{C`R_v;d5%rY;rn^B-B;yt-G`6&>JC<a2JMJ2
zdsY8u?*jWtk$<%EP3N$;wDLWAXE$@AO6S#Dr#o9g6VB&c<Fg=6toT_Z6W~8P`288g
zEC%V5RRyS%RZ}J2+&+F^+CxHDwNKngdY;Myg<FyK;-Ewg%IM#YFcn@0uNn}Cg+8J`
z^cdH4E3Dyh^}2Sm8GJL+;>j-EpuNl(?T#G@Rj(~Yt0Q?n|GO6_2HLZfx^a889z061
zclmly$~dC;BAJ|&u}{wz^+DQ;v~5zRzJO`nzpAVEKWePM=rAQnXx*E6{GiC-D`ZFQ
z=A-x?eN23T-M8+A8dKHpeY$Y;?#r&d`|3*X8H(mNo-w=n?QO}_1pjBzyN~xkiy+id
z576}UisfflmZzbN@2_aw?o#&gOUdi(d^PFG_iyT_thjRYYQ_BUt4Ax}_xlT9xcDd_
z@BXB{Ig2j7+*!GJ=^I^nYiP+e_pV?4F||j0h3U|pT%dXKhN@e0s?sqQ2rE<vN6yw!
zDD+X8H%F{TLigMA>(H60>fiZuTpn~Ld<ibg|JE-L$(RSjC#g*QSyLB|GH|nJk;bP-
z76)XG%th*k!44IH4yt_q{On3bVIk|B+`{q+XFq@1@+i0BU-jOXXQyWV|JYwYg$ZN<
zWZU=F?d<cLZ|8pa`@8&Y=@HpS=b#&cj>OKiy8i4jXiwue#CWn}?VhFDN59Q~qWayo
zGv|4F=d@VMYrA&*K9y)`_xEn+zJjBwq3R3Pov)qk02&g>@z<G^!EeWYbV+ziO8#`$
zJBsfh`^_BhIEFjkxrwy39NSpSmfK-x=M|=J``{`!`!d(|>qj2U1l_B?)FI-9&88i{
z|NZ@a*ND0BxqRmS2)*g?aqf7G|GJ6m^ASWl<|?Zacr(-f-{DjDR=UQ!3W!<t>%4m>
zDp~5IBT$}q^Zj@E=jm2+>wZdtqPE-U?Zmh3A7)@SZmn<Xr{3Xq>HVB%>HG9X#60_X
zs@o^eKYV$5dcM@@g$mY{`^rM^KEGOV-u3*7+h>-_YrH)BnJrD5bE?qQ*{82P`sn~F
zu-`EkJ{K>Psh=}H|Ng#OsFk~ZUsC>%5wzU<(YhD!mEY}~H-C@lncBs@kJi1e<wh)m
z#kI)iefOz7Wm7@>6uvyaKX?9I&~|`txu8}ymzq#I%l&tI6x^<+KZ#`qB?ad@2h~6S
z{FC)t>79VbHitWRkLPWltkE^+z5C=6&pV=DZ@P<@|Ni^$^s1-*AAaV|-tl>19iqBN
zo}#)Qo`-F0Mx!xk(J$dnP;cvG=D}`-Gix|z$KCz@_1dle`{B%-i<chx=#+N&%gri#
zWA3Co{D+*DziL?Z>ecexM{yGaj~`(wd_FDz{=P`d<KRUvbIRvFEz-2F`%|z_-uIGd
z;q*S<b$|a{JQ^!=Tt2*bd8vZuDm(sN(p!A*{0y*1)G;^*aQ@CLZvQ&D=hwlX&mp_!
zZq}X<FF*b`aMJXpKJ9yv25?$h{jM^G-eybs{-wRz;m*&)dE2$8sCDfAbX?^4#y`Kl
zzUHp~`}I2eKA(vHe?I%awa`B)mo9zeZq?pv-#+)-|C?~X?zeB<@3-6ayT5OF`)bO|
z5-l&yoA1B({@H8MXMfIHu2AOsKK@w2@|UabT>rN4^rO7(w=?I@TvYe*_xt_Xk}pH=
zW=;$8y7oG{d_~FZZN1``?QT4MkJKk>@D&iVN@WX~E_`Ae?~!*e`M)>p_}u=qXlC`i
zO9yQqo%?6FH8&}4>ZZ~~ypPuT)c^kXclYPwIpzCi3#1)?yj)|Cn{d)*?MLs9_sh3F
zUvm1<x-<LYS6`jJdfI)f@O>AyeN4Libuk|zJQ>VZTD|-#3EoEd=i#j<HhZNGZOgg&
zwk&>~ows^n>6W?Lh12(b{c&sOTdVEoV!v6O-g3NO-hSVg$y2K3v*N>?OiD|mXYQ-{
zxn_ga&eC<WcFf(${YcMqlK$Us_v)^j6^1X(i>u4iTmNdG4S(*gT;uiE?nIa0GKnh*
zw135b$N&kGS53aREVF1s7icf>T>F^GJ}<8dY&#k&8Cafwd#6x&>{{MZ`E==dmJ#3H
zr>^(A`L=B9y{xje+v2XBShkL3kLrTpk4erh`P*;b`FxADaC+^x+<S#3j(1{z?+&$F
zK0WgKx>sSVWRq(4-@hJ&)%q`|Z+)#3*?9Y{)L;FCnT%JT?##aI@aEpX0{#wbdkw4l
zmrL#}+hIIY;bxBYk-4+?O`f#&<+`JHpH2;2meQZNGv->=(IqcMqrb;hW-OLpKL6y)
zlB(?uKfk^Xe^>doX~*exr{<Q+#0r!Liah=IR%`y{r$s+M{&w9Sv;E;V-^shC=&cFd
z=0AJh`d#~lH~lxrZZ=qpvWk2<^P6p(V)Uf{>L*Aaxm&kCKjl;DTKhYPmAiI-5j$Vq
zcR6&ne7}0;#Jm5apWAv0t$w7}_jvcOxhD-{A32FU)%|wyi^^I~pL4n2?%d4iueLiJ
z`me6+kljq5tl#RvRZqjdb*;5|SfT0m?%}N@&1KKC_TN9fJ^y|l*NnS);Ss;pCZC+1
zK5yy#w`M2%vt#r!7KQv<+Yu{Jet&=c^>c}$H|OSdFVZ%Ty}NDa{rC32_PzWbbaQ`T
z`2D?K_fCJNsp<+_3n07tN~HZPHslyLYVJFI^{`&}E$@}t33K?ea{r4P<d+_g-(NR%
zU#$Mz8zFm-mhHZq^?QQsoBH41-afYZ|M9r|wR1=7_WwVz)`&shc;g9czsaE-yA|H8
z^R>H_Y%ExGQ=5NN?!4>axwT@S^1^qOYRAYNUwW?4>f`P*nVZ_d?{as)(apNQzy5#3
zRfDyO-@kp0ex!H%x$nPa-i76B)#4t1zh6Hcl)Y!anE9>y^!fJe!s&1Im&J6g-7<fw
z?RvGZHnB5Js*i@<tMgxeIq3M@ZOQk(A4t8u?0Dj@+KF}3?+F>)e82n4=2_SFy{TM#
zDJ;}J{QH*Jd!a`v|1Q=mEZ_OQQhQHaoqp`MMw=<W{`j5R79M%&U*&7#_-FFlwjUEu
zO}VnRHT=}Ixqs{GuUi=BFYJ3`VY6QE>DRkPZ!eo7XIV|-n>)WQjlX_)#pRmY+kNj?
z|2V_9WOjwwytl=P*_(2VHttYOTj#sxmfky`b&HH<=7d^a-)6@hs;2e%=bfnko|B%u
zJD>b*M$pAT_3c@4Q_pWZ-QFA?sc7`xX3AUf*I#e#+_Cynm{)DxHvRAR+QoTu!-ZEC
z<ZeB?r!MZ<wY|~5%Pc$B-?H!ew)~9lr<av$m42@7+8up7rX>5z*40~2ee2)zFYVCU
z`h78JH-EgDIq4er<nwc0hQ2U6zC5&VrN;UfmUU`R?kd&4F2DA=RCoS$vtnHHj0wV%
z9o<i@Z4A75J94wON7~Kz-{aMsxBchN$QFoly%W2xE8^)X`RMSccdQraSjk7OTIX~l
zt?>Kx`1+Ig|Nr|wd#9`L=l%bFdH?(K*?;x(Us5k~O(IwQdHeqU{^-fNYR@<1+`cLF
zIrLY~)P32rBBy2N&Re@xZT`jVl<-R3=*x9~f2D>pg<Fd6|NpOg>HhD}=htT)pY!+l
zskN)K^R9kAef#F7`<t(C^387coV{E-J?yQ#SFE@}YTiWu^Vw6+m&HC>r}6!kz00P*
zi_a8JS^0C>^C$P7cZVG;xms{p`)S_QsLP>QtFJ9wRJQV$f1|hF>sg-Fu7M$^pKm>j
z(xhdWy(IpU+I!QV`sEkjt9yQWy8rTaw)^|*{{AX5J-GEhQ&_FpjJ1pzRvg<6EsT#&
z+p#)%{_3vX+03uEb?r9#dHvSvSH?|wbF-y?=iK@}`_<>|JN9%fUD^3U_hi`9Rr^n$
z`C{4hz2=zjEt|LVzx#Z7cktQO*{;u5_i6WhKJjnz$uEE6m491$|E>zOH~-sbus8Mn
z@qYR8ul?Cf%g$Ua{`_;#r}W#cJ9d{Hy`B1B<F{-=@SV^|**%#){}Z!~{5DJt-WHqF
zvso{7y=Qgp|9^kiozE7ZzqJZ;7XX8qrttzpNfr^#Enlnt8U~o`+*@EYGh=eso<C2E
zB7Y_BGE@Kdl3}@LVfyQ`U0T~c!ekH3`Z9md{p{5{w3SoW`P#h`jZa<L_f}iy^$UBm
zbFRToAE)hDZB)4HjL-bQlJn_zo>V5hykDaFPHl2$_#?gF{>!R=2ZrS>o%~}_U0&7G
zw3&~!e*d}dz3%D(qww>!|Nrg%l)n4b^A%Zn7bTu=s-N<9@-ox=B|V|Xzc=~%<li<~
z8LM`F(wbYxUyGGbPqw>kSNu9GbMn56s%R@=FX_L0^ZMngC{52v61+WKZ2EyBwK1Wo
zMgeD}9dxIAzb#vSzwY<iFS%RH)C=^E#9FP`wdd{*uiw`V1NUEJ_fgC6oK%x}f7A1=
zo`vCQ4fVMKHSe2vT+fG}I$S2dH$5pJegE$7d+uFcH+}2oQz{>fitXl0-+wf9(ppZn
z+<E_c)$;Vu9e$R3Jy)RItM=dIlTYTmY*#yZJxp!y)$^C{pRY@g<LXhnZMlAZ*h}ru
ze`T?c^zt7vOg8kpWq(R<OQP00pI=qKcIFqo31XdWt@TcJ{<8U#SN)Fo5}T7er?j%W
zCb)FXspm&g#%q?uU)Zk3@cQemj7f1NPou3m@4o-OHD+b-vmLp7HJ3y`#Q0VPcg=e{
zMaXsHwxBt=df^UxzvnO2mYltBzh+^0YQy~L#rgAh#?)>+b!w|!p`~W_t5X|GrXD?g
zd&aw|ZPUYNEcyHRR=RcW??s`#zQ1og{ocs^Zs#oR*^}o@e^Z(L>Ds$5yDu!^tNs1W
z_us$o`|BfDZeLNhtaeG(Uysz_%jeB@=ghue_xo(r?Aae)U)R6+wyafqd0e#b){g8;
zSD#!I2tCGo`|Y=9g)V_1S*hvQlcz_=)SZt#oKjPj9k_m#w)gVC+I^2t{Z9L3eo5-$
zk;?xcA0I!i_2%Vf8{c(NB}nHv9#DHJ{$*`r>&uicx9Yd*t8)~}TrXPcH}f{z?V4<l
zP@i@CiuU%Wda|!dy*FPjd+wukrx^CXFivEi{O|p%uoG%KZ2m1<&$4IFt7FGhEN<Jc
ztKF6>cX;pl=p5yn=Ucj0FM7Sp>X{tp%(%>}&(de#e0F_(e0k^0=(l&Sl)o+8z4vC`
z{e89Be?v>w{c^bY{jsg~#Q(p(o__uQx=yP2;%p}5`MFayp0oG7zoqc4Xj0(y`ts9v
zxE?=VU{-seT5I>G0+0*;UyfVKe?tV^Tc})9#F|*8nsn>`sx@jkRd2r6-P?WQ>C}0?
z|KFZWQ7V*)j+6~w8En7j&vU1HZ!1FcjCBsVcRmifv-EAm_0YQSb^X@@n{S;-F<QCw
z@BaG#|DNtX=(6VS;j-PPuYzO$>{~zk%S5f4?>|qewhQi8dw1&xj}5X*XZ<qDe>5{V
zbsp=}#|zBnI_$W|KmCg8yBxnGuV!7b-L<2*^DXD?k3YU{d$wn_bWNP%jc0~C*Zh8I
z9~3j6-J;fQwnY1x=bxi)-`V1SxA^Of^;arIbAH(bT|a(9Bz3;_T^7WM;|AE=ma7O6
zb6b@v`rb47s>Od_oBYsZ+I92a&lmRTf7!GD@)hF{pLw6lY<^XrP6+0Iny>x6Yj^hF
z<Ih~ytmC}8_J70g3fHOYW%_@;-FGvc`(~cMJZo@Rn)%<J;~HIiY}Usv?R@|DWJ=KL
z120$cy!%>p?z>{GS&Hoa)_r}N>kHp!JuhuQ95_V6nR~xXts`62ADVHfMjhMKqjo9W
zD@5Rw*3P~8^843=Hy-b6ZN5A`HD4>cxyR_r$JTjM<+tU()H+l$)i<6!GPnLj$z9Mb
z74q8Z|9(E7zqH=Imf>@J{a@ApKj;6~tpE3OxlI4v9ZsLGi7qd-xzG7Z@xA1n(s)}l
zsopvA+jIZ@c+CHE{r_M3Kfk`7{^tAdW3T`9%iHgX6IhmQ^6_uP_xm^Uw$J^;9vi*S
z`Twui`q}*^JC0m8d}`Vywx}2>Z^4Jj!Vhl2xp5w4X?MQo(zR!pRJCS!%n>X(`8i@r
z(53pSja7QDemIryEQ-0edBLZOEskO~Y}0FNcHgzTvew#eV)*=LpMOsOmV4Sof?-zj
z?z?4qe=fcLnkAjTt@U8SgBtl+OU@(}_#!O<K{+1q&}H!g(5XJPLYd7Taa-qrk3;23
zEv?h7wBucN?EKB!Z-px5v;(u0&bx-6*{hc#q7nE|>-lqS&Z}E%SN6TuufIKGT}h~#
zac$b!qMdK<G)T&IpI#j+Xk9mPZLZDXRgz`9WlQCwoTnd&-Sxt`YHLCGx8Jua%lGo<
zD*b-ZW`;-{_?Iue`ltAA6`#hZFahn!+i$<M+qBE(1Iz!NF_BwOo!WjOZ-wjGNpYG-
zcJAx#-yXGnqW!-g&ei`?qfhpk@BVdu$-#sNZ!2zw-QI@0ZU@U&IHx7GaiQYR_uAX>
z{&DYi-dY>u?|**Z>Ah0xt=8@T^IGAz&Wh@A?>%RdnAjQC?WkENuysY<rK!R@cYQRA
zt$8PP#r<BAr?1`n8)`3=BVyjWM|-%YA)TYp7`yFr_tbSg;`JUX^X7#0%IaQPy&F0T
z7u|N(^7lOLZ=VWn8CEpE*}ULgt;LSBIv@HECVY6Bb*}ms$6xL)57$c{Z`|>^+wb$s
zf5Eyq%@Y08R~Hx0Q$F$hme%u|yXAK&)LeEwAM@Tlc1rBW@7K7#A)UJ07#kP%%WI>3
zabD@)C%$ouK09Z)gBCx<P2XYdAu~@U(ct!-n*aCzecK+iL(bsJ!SC<y@4us0eLh$9
z=6@X{%SN4>jyYG;AAYH_owt~|wdVJ?w~OcRyf@ul;ji4smG7ocEKFTD;nPc*gMX(?
zv|ji9tJurU$+dfB_q-83x~%(vDKBC^1@-)3d+*(EPHo)Uv3sx0{Pl0R4_$r!YAfpw
zIffq&>#t8fnW8lLq>J<dn?p~YeELx<yW*D0ZTD5Dw*Rcr^PFU1KhNwy?t<%{;h&55
z%BS8kTI#K>ANTLFTI>R)qhI%hF1`L*vc7%kqoZH4=B$gcW&O5O#yCdWTJ++x^H(xV
zULC2scX)mLey`rIb$@?7t=Tt?9m$DL6uQB?NB6$6?_U0#@r}Wx>5zHN^lcxG2KMFa
z3-O+BUX-cBemMEZar=LPT-TY~ro1VB*>`;Ln(MFoMNe+Kotr$lX^~^+`A2!X@76^!
zzN=WHw@|J#r~c;q?^BB|eSY^yA}?0<V#<E`UblOG6LLPhzP|oc?V3!z{I_qTY){%1
zJ(TjCwB=j%!=kA#r#vl+T=mw+zI$bW-@}~^R;l@(IojL8MNHpL*4y!??)%qj&A!J$
z^RIuo_HY|gE(b640&g0ud3yWF&qv>Gte+D$_3Y$2)$pml*Nk4z->1O-dF{oiWub+(
z2_7f;etph(m9=D1?auOr-DZ=^_r%uDD4G1^>vS#4mnkQX8s7QE|Ep?mUQYb3y3pXe
zHNU_4*8TbMu*TkJM~u(oiZ|1CXd7GRF80{FCuoJ2^pf0kE!EAX8&1x;C|a{3yHv;L
z!n49-sr$bz{JTyzdFJ`mCoAr<A}TWY$&Z%q9ZR?G?tA((d1BYxKPG!V>B2`bw~Ouf
z2s3&+_uoB(s)^gB&b!W53#<%hdvfu}zLKYNZZ63%cvp4*Rv&L+dF8)YAHGdZM^pFr
zFY0i$vPs;2yL8#Sl=W>!fBn2NZzr>^ySpkw%kxsb%8WSPscW0>d|Pik*UwtN{#Dh!
z$msQMd+r?H78hBqpDMpU;QE{=aX9w^pr0nW&(1&3`h9m$+xZ#ZVM1(P_5bevyjgkh
z%eDFs!3US82)q=QyB#9ia>ej~(cR~}*!SLy-o5FE*1N8}sU>^!bJgF^nOZyT`qLDR
zzQ_8j-(9`<e6#k$d%M1B?v>rp>6yOEf8Fh^r+w6fbH5&2c0POk_0w;?bLTFIKlLa(
ze6?uc^R)|KKHqxg`T7^DBqr|<|7NZK{=M$>)2C`Ttl(dMqarP7^8DWFaM^t3(z|Lm
zkA0pb%YW^zdyFl!$zOHXvNwgjyPm6sqMoJD7^}j(6minb!=K!n&8LP|h2BZj1Yc~!
zHhHDb@=BfkIw=#^IB`x9x;o!uOHZn#uOD|D%fs|{A2sHOe~-NrwR`T|y6~^5Q+{t>
zW>gy`Y5)G6SZIFgM%xNaW6xF5GFx7rTCAoiRGvFGV|!zE(V`rC-B~<W4I?!+Kf15#
zdq-=YUG~M&+hsEsoeT~BUGP@2Fn8~x7uVOv%WqwGD%7>~p46;u=`;5SZdt#b<zVXV
znQ;rJmzO>@^;zd<BFJL)D`;}9v8eL8-@k09>=n8?#mw%xp0(VX-EW_L-Z}YKgnRX_
z2Uzw!K#sdg4_xNLS}S=rsd8^j$)i0&IflQqHlYvJf@Xm%E6o4hQ<xOq{e0nz{M2wx
z?~S&OJ4>hDRxRa!m*;EuYR6yo>blFfGiSwgZp>JeRjhFH$>-Cb!gg)eRb0=xVbk#l
z6G<=Eu&S+Xy^jrQKh)jZcja#0?YG~O4QE;1*1H|PNaIwjr14w#&~+RqzwQ57bMM5f
z*|`GcmE3%?{blRc?A(*|<<|F*o97=qy&4d@PD|_a-GH+Ddi$s6eSK`QKO;VWtK+t}
zKHoN;*=b~1CtO(mmP_&S=h?L`Eoa{^JD9NG>+!pJ>V-1m-)`>O|Ne4S*wbt8w89t7
znq;SL^uGG`Rj%(hKRzhiz4nUVvgC<ht72dO&{*#u_E$Yl8YQhTm}yF7g#6qatux*G
zX5RL&FxAbvf_bu^_a3jyRVaP^{_XeQ{4*!2c<O#yk})ZzSYc+`J*h9>s`mCL`}JG@
zjlKN8>iJ2J$;qDKhGv!TO<%@5+h!@g{b}glyGuLUKbT+S&)@pEZ1>rzKT_5DUEfB1
z|GdBJNO17><k;08)#l$1DOxiB{~ML-U%GaD`R@BK4Kx%#CG4-C(c8tT>+YPa(~q4u
zeb4RS>b>{QY9H_3m%QogwJqnT{H#_xUVmP<a@qfwGhW@BOx1qR+-K7sdfcKk{_0e@
z;;Dr$cei`;u{H0We>UUS-Pmu%<-C*MKeDl$_TB%5if7i}dD_w9yVwwQ#sRhK`yS-S
zvW9<sHGSE){ank!6|Wk0=s910bne<!$5gQd4J-X+lQ-E^CK_q@-LF3XWYd`^t52o8
zxVJj){mh1&@2aPZ_)fcJuuyX||8~3ErSsgQj|WU$RPQk(#&oW2`AzL3r{V<DgN%c3
z7M&N>ST_H+(bt7%L|?w#sa1S?)!MrJ-!^wQ7cG5R{$y=k+UFU$-xsc0lC<WO#iDmt
zU7mmb8GAm>=ljKDGme(nWE9DL&hiR#S@!?M%FmJYxv{+0#1I8B!|a&fP5VtJuC@BP
zdGCKScFXH|Z;fozOZoWp4ga1mmYh{_?AFr<U*!tZtsb7({ddb5mMbm>F|UnN&qZE6
zSQ7iTmizMRbE{%*hF*DB%B3EBF)&R&FIF_{`o=p#{=OZ%7yV29^z-bgRd3QazA4`3
zbM)@V3X^|wD}I$<x?SUYKK176ly^7(XV2)Eu<O=hu4Um{((JXr$8ctL?>ZX$%U}BP
z`NXSc>kh5mmt9n|?Ofu_^AlfMo-g{z|KZE;Md!Y`-wC~QOHb{Da{r#!;Irc=pVt4f
zC^~i17S}sBYo5)0xmMRqeP8JMnoX7yc3-_$+Oa!&`}8~2TQ6<BEpobJ_nWo;l`+=&
zsq4~K-1@#=w!1T8cREA;`?n1@Z!gf-6v`;&RG)nN>gpP?yxMK~U)S2?*hsHAch%q5
zZnxU})j7KR{-nE3)qdoY_i>x)%DttgRlA~Az5KbQ_G^r2-rM|{=L5FczRu#GTs(W~
z>(pCI*QGay{@gd$M{U#HyxwEZD?`kG`ouij`Y<v>&2-Z%%QHdG!k)i*`+EDU$Wu!t
z_NL$W{qNbfWA%=$u|5;r<tne6gHMKgDPDE+{%WJnb&u_@Y+GliZTxYArogJWpDB;?
zXWK=ey_Tdho%w%s^X2GprF*}kuRm#h8@+E`;McIVMlsgyYHv%=Gu#XLle7JHOy`gP
zH?5;3p3mH7%in#aNvA7hl51n6sLq*J%)F-$A1c~BRqLw$iju>ric>$;E#UrJmy&3=
zCCjmRvu@^tO)Hk1UNcFrXIeaKXZhS4=l)c@DV&tN#JOtT-no|_fBf<3%*&q}=l%*m
zUYs6$-RIPu=bLM}Cim@pch78V+qC>3=QZp4W%rexzS7I&?<+QW(-zYsubjk#W8Uq2
zcWbrOG(ENNJEh8R2F^75=vbcfZKw6}uNPNsi=0*UZqx29;XD5?d!Hho?Y&*H$NI|!
zXZ`6;>}m}2Wz3~~3L~ADyyJ@%^%1wepLf=Z<z_7ZW|{X>Uf#0I{4}d}?aJx4@ny@e
zD3v^O7I9TCm(u;c_uajpSsU`rX5U#i-8KH`>XNoDpVwD<Z1twU$tzlCeQMc^GMz~(
znr{Mj#1&huO57OnWS;V6L3Y>Uw|qJ`Nj{7|{(|jpJJ;lX<$b-oOIRYkWP?q&-=1II
zm%Vddm${wzUH{i7Qj9ch{CEBA^}HEY8&-R5_nXgQCBEBc9k-7DwNGB}SnRjGQ}!iq
zTC&^edgS@by-u5~pDo+nIX%{Wn`~j$@mq^l9^93#WV-0K!Kcg1cuucdxx(jCx@oVW
zuWk9u702Jyp1kIGIaSlA_tb^&OY;ogU2x{#8^a|#gQ4cpFQ@Xk=K_zL&Y0Dad3^th
ziOI%R$5LYV?pi)|M~~g9K8=kxzn+_382-JlBs0#x^v&uuYo9CUFSm-(laVgTlw5!P
z^)0KYWnU9_>&pEMaNp<iIPl`u8$DaHlDM|?1*<JRnc;SS_HC1oG5OnfU(_sJtNm>9
zl^EO5^S<vLW1n3x4fuX;Yp%oheV-2|ZM5iqeolPb+k>mV{Qi5XKXTc7)5~}7IZw~M
zn{a1gyIj>y5i0}6A4k5n-cx(5XMOj;mWxGqer|oaXLd}rbg%XG;+cA1YWe0anQ-iG
zS+#}fN%!;@H(c_Pc%_9eE6V;Xk12mOtLaJBovVd!OUozu)vhp*JX^8u*xj_vh4a$x
zn(VSjs^ZtH&5E9TW6gKAr*keBKX1O6@g(=w9?s1-*IapGUb%kh`>4qmD;J*Lh7o**
z?_SNSd+=$i;q9NMv9HfQyY>3rnO#1i-va&5Eo`pux^OJ^+aEhC=i_rPFFO@jzJBx5
z8E*rwh%(PIy6l_mJNN60EA3p9FZS#!Uz%5R@N=<YR7q-55r58o?+N?ab64$te#Ufa
z@MXhiSAP23%YG@OvTNH}(<8#jDSAiQk65w)YcKD(xVEs==92pDpIamE=k5L**?cTj
z+%R6|`N5Qu#{R0LLpf%fZ#8c9bdoN=`TI$-RLnJxtfG(>-@oU}>|V|Km43<dduhJ!
zyhf|{t}`n$jAwm}>D}#pXp1vnp2@~yU5B|d&Zv3z+Rr_Cy)Cx!HQQr8+b<VRFTK#n
zc|d*LvcA(LtF3yi@2-nF-aGA$$Ug6kJ+I%nUv-;(_R1Zzo;AgL`*vBMzIkqmezCdf
z+S|Kc$8XEKmYOm9h;n>dl=QsDMVWzSizN-;9ZJ5X*#7I(j9uKh$DZt+Rwr<D$Kf5$
z{I*}Xf?gb8c_1AASkH6P<lPfp1E>6sp1b(MCBX*Q-Iu4nWtd)8=X{@8e$Fk|w=Z9=
zEK)bP`!H{3%(T8uQ95FuzI?gz>hANBW3j@^lDFUfy6alBRqn2{PuGR)4KDSuve@@-
z?Mc3ErL$MK%4_Ag8H>H$P>~}wv+v2#KLzVIYu=2Qdu_d0Pk>!{*Db};H!3^<>^I9|
zcWo{(3rjz{<7-uHw)6*?17JrMX_h1~edt_Wc-`!hV2Rl?R}t6nkD@|#8O?>}Gkx}~
z`&!1gJJ(Nba+JHVS>~OYJ$7qvpV5k1b>MpY#K(7+JIBA?I#FuX!q1Eh1%AkB{z*{J
z?zdt4C*L<b{dCjT%iIg)ZYA8&72{qXzkjmI%G}HC+u}YOs=bc<85Mv2$d1+3y{8}F
zt$HnWHe-_{`?0z4mjo-Ym^rD(dOBaq?B(K3^|uo4<eEvpzx?1<T>tggrEi1(&oY`(
z@;cK@)PM8qJ6A1d1(vVPU0?m2BTa*$K~|#t#lrSDy;eRS2D_aqkNF(h&+S-zxMrV8
z>YbNjjNf<GEzGogC3E%$+hidIh6f_Z$`^iSz0Pv%?$b+GzFgh*=HB$!`gP|n_DGa7
zFkC3xaxAv0K{q}={?pg5PrpQi%Ih_8FAlI2aK)-~gD*}$Fzv$MIYuRaYe8v$x6|GW
zjhqie7RJ8-OBPhNyn8-nq3OGr<+qkH?GvhcvGDpFkp2ggwe%m=|D0YgxHRN-`Ia2%
z|DWss`3HKP{QI}|!=5?9|G)qL7a!>5x&1cpyy?Y{@BiIhukNM!)BgYS|19TETYmKa
z|HXgNlu7?T+W&L^ut#KLgie&@-rx5Bj{n#2()_vp|JVI&AZ6$O|2Yp*_GSLRV6d@o
z_y08y^g3B#!#8hw@uT|x@Biz1nQqs6uKF?m-`V|wOQ-zV|Nr~{rsqpFZ{^*2`Rg|*
zoXT6P7BUMr_#3>N#s2slZ;y4k!Mi&dy9=*hlZ`cecjv&4VrH1|E%sxwRWBA!_r|Uv
z%z$X+a8u18de|SYt3^(IERWY!!el^hf+{1%CBxEaaB^c{00+M(kN-E=T7d8gpymZc
z7E&C5%Pfch11Ngi;~YU%E>r|uerkIxWEO@BKmwf=REBI&pSb;~3)|gu-`54qednO|
zad(YWcFn13n~9F@Z%wU?B+jQ!6_J^3b9!&k{pVIo^e_H?_;LRGjXrEM_wcF-?XTaq
z;7(cPY`*GCo}aHtpSrT@&YN}TSLxW@SDnYR@AERNZQr-J*~O*W*`2vv@lQ*B>y&7v
z^WRgy`g+<|?O#=7onSnDVUSUsru8%DxW&~km!2<OuKqpn=FgnI+*$mUbNh=wzWjPP
z^nK{ExlOw^r<=Z>cFo+h?xgJhk5VUV*MFY7{a$T|V!p2S_On59?|<8uhLtX<fAlNo
z)S|slziGbz7}9og5AX76@7MO~$iH8D|L02Ux&QXMte5|p9B%w_+P>i9pNdNUr0x%X
zd+J}%y_ILDNx#2RB-H6X_t5im`*d#o@w2r@YQDVjc#^s&f5q41Lb^$v;uCv*?{0G{
z-!$cj+hX%c8G@&kq`c!b1LtnsBQv}Fx1U?O!K9NZMMoCzNwJQ5ow59~?1>UNZ=3n=
ztS8oXUTZw9cXsxx(-u)4GUrowy=VBcc<bD@lV2mJ9*tVGPiW~bqZ#M!ehL#m+1+D(
zbC0fy)Yr1Py&t<BYd7n5Pd&41H`^zT@cU|?eoT7H5nr)W^x8zD$M2r+eAllWImc%H
z*^R!RCvSh3p!L~enybmAxX7AK7qrdZUGmHIf5-jmcFM=Hf|^f8_evjq`?x*oUQ}4#
zeM6(Qn>U_W-n{pu$%LO5-KA!4%E;fDn=1R2|NhEr@7K;xH`e`KVK>#W{QLHUe>U7x
zJ^y{tlu7q$9cyRnJX!l<Ud#*YtE=AVKb?E4WamdeUDZza>fm)Jc5K${HrpS39=Y|P
z9TxmjLv?Q8oYx)8=bk@q-h1qI$^FKzl(~PaZ_SW7mpb|9?{$+ePJFpqum1gRH@|e1
z!fndaju^et2yAw~n|AX=O~92EcTd#pct0htCT@Og<R16hz*WkNEi88|->rX8t#Wn$
z(<RDYr73?V$^7|Sy6gAvl$Sf>-ndtkEn9zUPi)!F)E_mIe||`x;yJN!x|H&9*{-kq
zdNw`ZY`Lv)+T_?C>vwP7JPu3WwB^F@2~W3#+ignOJ@vic+k$oSk`v2hypxv4-n$i+
zC%;KzTFIaA&2vwhRsFlTO|#o<`t3Bm=0)Eh)|IS2S^YZMQ0L{D^(oha7hUm~XS^}r
z{7|t*@!O2U-1W<&rv6>JCwR8rcHQ?^j4tg8PP%h*itFn8E7QBK?eON`@bvX-?|u9B
z&8h2_t9sFTm0NZOLr%qf{-wcYkDjI0EGqtWxM<VwCX48&|8uW1Sk3vj>-TI&^~Y}m
ztGqnRx1IWXd)?xs1g&dFpLhH0k`4TRey9HY_rLY8KfTN^3(Ao9o@`w1QkuTW%I<mH
zmgM&zed~L-ZkTqzd0j~rYo+m;{A*v6@=bW2vj(5x+wr03_GeHAE4NSGcwcwr>Q0;f
zDH^5q2?9CWZ_i)(?*6jwvm4KD{%1QOZ+W=D{J4}o@7L^;eo?dUxY5o2rdQv8KTZ9&
z@%5WoC0Uc7Pt;iY<e#PGukBwBpVWw7mL8nvJ+tgo-|g9IGtaH{joh;Hj$ORkrMDta
zb?eWj>Tutit@-o&>Eq`Xy!3e*I(<KKpuL?|o~8I(uxReYo_F2zif3=i_-_3*=Hl1y
zhVL#ozvuc2DiQM~Oyf-EPW-W>IrZMjA2Z&&$@V<@wCAOC-`UN-yP|VacE!yPjeOI~
zY}&<rZuk3=**$DoGtSloT#{TLreAhky63~54@K5H_^wWV`RQ?WRmi^N?a_yQzxKH$
z<ZS<B9Hd&?mfM#r_)=qX6JP#3lXImh7WI?Q2XDN%BY1Y*kr$$Vfj;i(FWl9(@4Qp;
z^ylY$8#KE&>ui4;q&9a_-)`1Q<Fx;OB#$ifu3vs@%3sqx!LK#8&)@WT?yOXEr#$mn
z?^0tfsBP2gHm+U1O=fN3bE~U*q93M$`cBWjfV>v}Myht#`mJfl?)tNr-&c_IdHTI%
zMr293!sDN>7AViC`>GdHo-XToz97UqSw*_Cw@g{$YQe&}MJdI#VW|`A_Ugvir|AZ+
zPwm}z-sRfI6!X$`tIto*-Fu_-6T8vh+8rOt@;*=D*55AcJu_A8gTCy<kAFk=ub8}X
zYQ>T|x3jloq<5X!7JW0%UN!Q#(aX1PT(c!@-W$oMi><X!yt8!ft&5Lijy2E!bxqn&
z)ozB^H)AUuJ*($-W!sK>6l!i4G7A2DZ|&(vcTVMMpL`a&=<k&;50io&wT*R+WP7Lg
zeUP!0)7iBD_M8VFVy6G|+p77yyKeclh`ign@2}KUzUMvn_jr%f<8#Y&&b^ykCHDfQ
z`67Pl>q{P~(A{n>AGgdaDL?w2@7?eBf0a&YZRYs2_|E&~3sSEK-!iT1D&7A6_aD(W
z7jD?JTdyf?+n@S(<^Q>7K?Ux~iIbjP-a6|+!uPZ9T&A&IzWwIa(cOREE&u*3{o%Xg
zzyCVjx!L+gf6tvR4byif=dT~M-C$`}a#QxrzME4|UaE09%BcS8RNl*mx&OX5J)d0S
z-1f#QWR}%ali1ZypKiN*>ijG}ueQ%u1U6`P8*6QEmc3$a^k?t7Et8*pKlJ@(Y4Y^R
z?;}2J?mY3NTDkj;R3yarr)!p9i_hB={5f^s?-PHG*KWN4Docy2md_J})a>B)@YJ6j
z->q|J`kH%Pmp-MNG%s?+_uU&mSxwGco)Nxge(V>w-!D0zUq1O`!u97z*EQR{t2h5s
zVlAC?C->=F)%};B<exp)R`&H#Xxd%Bhkldq?|!i~`)EwXPSL{BV|Q<R*R`L!&u1+?
z?b_5{op;tjTNDp}*ITjo_+P#G=_w9BwYI-qzGvzAyBiV~H+UPrvx|FbxjlII?Y;@~
z^Ix7@c(~d1jd}O)L#}V?%g+3XT>bXa{gq~^^)ugJ`E|Ot{FUH+Z{<HdUPpFht0Vj7
zhRyr4+y3}PKmC&vJ-=^Jw9DhW@9O^UEAh1se7U0U@0W(pFH>YbZQNm>vu9dEVfl&l
zU6-G1-x#>}j^F0{e~srBl|OtMcI2vLd8FNCSu0twC*?7FZ0@eCPJcCbBIDDgcZ4F(
zev|$E_^!78)g9IkoW;Jk%P;rw4BNanGkk;d`<3@?-`{h6`DG7s-n<-h+xlyI?a4PK
zDLuQ(nhM+Hs$M(=_Y6-xkKPhp?opa5bbB5D7sd4#{~nxGI{8Pe-S_OHU+QO<EJ~7m
zYhC(2db4RpS6K`9`F)1VGbh}NnI9TCW6jc_!p1LEH}Yc^Wls3DMx6cf9#Gm^vF+I1
zx~vIjHy%9wYC=h4RrciL7iFT{_xe=MUVAldvqM$&>9@|0PS$DNQkb;;&KKL+n=I}Z
zdAmQqF(X<2<CAKZfG^)N%lFmV_?$0)`95U!ru}{8tNs^VF7$nW<@(=u=lA#b6~;Z*
z)9p5{TfPl>fJ%JQ(~|24!fR)){Zm>|7XPPz*&Q{{kJs;S*?8%{?)%&G&m}&5CZT(e
z@%$I>O`zQ3x~n=e(Rue?>z%pV)8Z$+eeJ5`naFHz%J7Z%J-7aLC9mGyTMmEUTj?-u
zQfz8(U#{f3#hd;9y$hbS<VJ$$^}ty=<^SiG{poraU0v?JRd@T=GvB-Kl)If@%Kh~A
zl%qGN&3?LK+t-@?2OZK?&d>hz*lzNYinn`8M1H4e-hTUZe{k-pe^&Qa{yUw^{{G5*
z*;}P=PTyOlbMD97TS-W*v>eYkt(uGX^Pbk)P3e1eDyQ^Mey2@8pLFkTzHravO3R6U
z-?YEqPJYSJ@FjcaR}u60J?EBO*OZ>SA;0D2K9$>`SlV+k`R4RDUsk_=96h7xw$77%
zw}0NNef#15Wxuv(-kW?Q=g8=8xX<}+_Z+=Fcepgn-(5=I?(n(V#9@~B?Bv;L%H6-$
zm3W;}+gtbgVr1&E&|8+;Zwi)LH~o8}8Y^#7|8IU^YNA`{53TK6|H!?u+HlviW>a%s
zu-IGO?Q8d(t5SV`cz#u~(W>0P)e0}AQVU<co4DMaE%#aT;i6q1%2$Qnj6Y?)^<~lH
zxx3PpS6fWm(Qq^2`n-8ZHy-(z^?&1`W#C3@JW_D1`Ek$jOy1i$%-?u-p8N9k!TXa%
zO14XvOwSE?cXsC=DfgGpL~inV{7NlUDGZwM{NSFFFK&O|NUu0vdHbKvg*EcMNyW8g
zsT2FGB#++g%e}QyRz@f9p3ch3zzr4u>y97!b4)e#RBruzu5;lf^YwP$`7}kk+<vyE
zjDFSrSzldNp8LMS@OJWSHB<dh-QVAvpVy2?i9OwUR<rE8=6<(~hqYej0v3JkzfGrE
z{hk=~JSuPZ@B9e!+*6B=KApDjvDM-oDa>lk6F0t;ie^ilb8q>jvkUo5^#07v3jH?y
zlV9$xI~B`cY0S~ejugwSTRu-4sWdTL^G*3dNWRA8lS?KXpMK`b%-Z&^6}Mb=S-RHC
zoK)Iv9DZ)W>HL(!qUDFa*3EKDSGfH1-;GIb$(L*13$6TR)F&o%ym%(xrP4Wd@^R&f
zJ0n4jh9$i3`goRouDxe<RQBUC&-Kow-z%**GRIl@KCfVz>>3$yce%Ib_V<F!%YB=I
zkHvnAeA}xOd4#*uE!C|D)FR)UTv~20wervA%D$l3nKBYNX-~_FR;{>Nd+ME;^{xCj
z#ztnjw}SIB(@le?+llSI*uF~nZ{Ww>sYa19I{(1Q!~Ar4%)7fE6uTe3yWv+K@+&T`
zrk`!|ZvW|j{nl=-y?C#@IdrG!zTmf~-fG=nnVLJ1=~R#P?oAn=t-snFM2r|2Jpa4<
zV0~Bfxy+f2TmMdY`q*HzrK^A2<sDC6|6RW4c(CL*tNYJi@EkL$*NuyQ{yA6ivE#QJ
zok!k(3$A*tP#Jw9<-%R_q;lDYkAF<<Ro85Rb@oyW<z$}Z3hftP-+IMl_EMXB-;FD8
zU!DH_vFmGplWA*Dy|tb8a>Mfd{?mi<;(B(k6|uekJ<xM!r0i`I=}5bK-u7o_zw*ep
z&|RS~2O56bCcoaueuZ=D_srwRKN$-1TVLAU|72@PRf_cKwFh>1C*Sk@G&dUDOHuu_
zZN`ZO*&q5&@0C7t?VMFjn*EbfyL+?!mcPGTR{ipQNcX1gy4_;?rF%}V{W3QzGVl5~
zzpqJmZccNZeShV1q;U<0yESLpcV=#M*m?EX>kup5*aN%n?m4x^cuJ*qPfu}EQSoEv
zXNRZdaa}B`Fb~M<J!Cz#XtxtmKFfOg*>};tNfX~Dy}Qo$^x28_Bai)du&y~jqrXCD
z?!CtcLtGZzdG+YC?xeZ{zKZ9>?(t5EUi`st>78{*{iBAc%DG<u>*}_&aR%g>Zk&0#
zwqDEo41>3s(f;?ROFWlPE6Q%Wo*Dn{dE@mpR_-8o_=4RLgyarr{~lk5AF8AWG*7W!
z0W`J-5orKdaiU8uG;%@&7<hVie_@E;w{PE**RM~%+zuLxivSIUL8Z6d`ez3knuuKp
z8vKF^vK^cII%Idqfp8~&+b^>&gL*L#nFdqvOh6N8XdNN~8P}lZSO(NwBD@9(vcc+@
zhQ`9_atWueU!Pu6TWk4O%=XI#(7-f0VZF8;9A}^@ix;Sb?v><KI#p<b5bo9hesJ=@
zVq(+^JO&;Hmm=tHaOU4D_9_uPYXUJI*&T7*U%>&5#r^ABtH33;9Ht|$JK2I`kRMZ9
z_Ch&OibJ*oX23}F*78ftIX{2>nzVks{_^{aKrK`(A+sD`9QaIi#S+Y;k&2SxhIm>H
z!I<p0SGJoKQdTw`K<Q9J1Q{eG%1e2lf(nRRtHrGh7$L$3!fxL`zQdV+ul5y0vCaT4
zOK^-WL-a9#b2I*`23$<+9jxUsSvA#x12{(YAfb}5`tAGVI}6+IiM~SA!3ha>cKU7g
zX01{Ea>04MB~oP@F&fU0a0AyGaX4l-Ob*YtulEzOst2pR-iK>o)o<aHBBhdjw>eVT
zKq@cfp-uHkl%JiN`r;2b;m24<Jw8{uDpu=(HmGzx`w|pgb_ZK7P3Ju(3)1aieGz38
za(;r-%hStxu4aka^n>IXuJeE^E%*f5m(=D$c7}j+IcD0ulll4ig^m|~uwi02@DzEJ
zLAYmkQrK$IW3mhljEgV6NLf=;RW<2tnYQO70dq!%1J;mm0FMRP9o(VK_Lz_1K+o>o
z*2<6Hy?pud_kKnOhMGoj^8hkx0W#0v9RtIe3r9~aU#{*s$t5o@Po-<ogP*Jn4X2sF
z$qPEgE>V6o;SM9ijKrinwzjsNL0)c)13&y>VmOeB&A=}+j(`l@xpSxB(kXZD-eo;+
z%)k&MhUUIwON@8L=runVW>8R3+h}C^w&FemgM%z&A_}zLB32qStJH4$@{RPLx%UE=
zecW9mCNq1FZi>;1I{DRBv64PXmH%}v{hM(8MO@X~FE{4habN!_an5#^dt$<pCD!-n
zPV_5R5SFj}T{FGH=!8u4x@b|WprbSTlsM=5Gc-&%Qn;pf>hT=2*$;lQF*KZJg!}j9
zstET>;a*c-L8oJ^Zb+v7&8RKN`DAoYI`-v8?#^R>W8D{8PfVS3)$d8_p6inCn>xgW
zdaJBI=l)UZG|RW&AO3fvOLxR0SCz;A)&*ahtHW>d=F_%mE7rTLT*tHQ^W^Jqn0t07
zfx`aFlI-g@4;V2sFgy?j7mA>DLd#w!Dt|tB?oHP<_j-A)z$}H&zQ49l^|AH}NmnT>
zS~1z?es_>pRe!#H{cY*Y<8C*sUUdh_&eSojjP_l+cuI-e$B8GWpZL62Xld1_AJ3+3
z|6VKSR#>z^y5GwE`WyD1-AO)HizUh#3f{T|rsUqy73;<bfUF-i6Fs*pzxros&Xkv)
zrzyGr&Hrz9(-Yl0rS^+t>^%{o8Ti-Z-uCF5dBT-)nt`w4=Joe%$^E4B-K$gT>G{fn
ze?J4PZhlU$lzi`ge6RJBx4v@KULoabs~>}A+2m%{*d2f*PlxjvCY#LOb<9QazS@mb
zMVADZ?lOv=DN~=*xA&dffv-xD&--fc`v$-Dd3x2f{`j%EzW3~&8HIRV(a^Imv)CTd
z?$3WL)(|wAUlr4{`(lQO&3y)j0!yUCWO~vqZt>j=bJLg;$DWv<KKbrP$&uUNSL{+M
z&e8tp(HZ1Cvwp|Z!gQ@^J;yFT)s+nm-!biO)S@`o;EfEhxVkZ`3}nLtX{4A^iM7si
zPyZ2pt=0Od+~mA37bd=Z{V)IhZ(e<_<?HgErtXOke}7kT{>wBew`Wm~_x$><-R@@#
zNv`}Du??E3UKAR>t9Z^Jvng)<(}xciPT9SC_k&873}Zxgxqh;JkKOa~<XX$P#qVC2
zf2@0c{oI$Y&)=6ymdkJKv37TxlY7rbqWu3u`#<d3FI+^ElkT_%irCCA-4M0*$;+23
zMao)OHl**2=?e0C_wL=3hYub9ecQhO<mJng|NQ*y{_oFEVViorHP^G#LF-!{{AADI
zR<pj@eoon8He#HhX>E;8+3t<g@|8ADe17qsg!FzHx#0G~?UmCm-rFL*|Am#Z`ln|H
zcO-vlmiOt|?LGJ1(%oflQcO3DXP?#6n>S+yZ|Vm|h6n6D)(u%1z1TaE+dl0*=rXbM
z>rb_d3D-}&^n3Kjjn6Inj_4bU=tIw=!OOkZ`8?{seEjvNv`xoiFZOMg{P(;5|NF2D
z3Oa0$-~Dovx;3e9iq_(HpI^IK-@SK_O<(!P!)MQ)J$mFR`dF{8`~E?O>m0{q9ZXS*
z_H98{zjPu`ZP}jv;7j`INf#@sFTbyzev>KoFt5U-ry*5Y=1%$BF7<3NJ{i4hb<V>K
zhq9@;lTM~I6_%%7&-H%cCnmf1v*KK}>aOCL!>hUqkDrKbknecTaP@*z`MTh@L5%U7
zwqGt}`{|b??2?L0zw}z;<+-k9m*4oVdGliP6IZpnv5(UP_MS{%S*CP8b@8ix?vJPX
z9{j6VInyH?e1+-l=P$Dj&)uGFGp%=(xBFw;eU-ZDQY}Y&+!n7keOI#V>C(9Ex(lr%
zmrj_Z1zQWCw%Eyhw(o}`roSdPi+c};_UyiyBWClTA(!zn-vX&!NL_T$d9jxQ7g;HH
z_Va8j-Ew=uqjcRJ^JCM0w_f()_l!GsNz<at^mQksaPj7~yE;8%?QXu^d-g)7Sv4<6
zoTz!ceU7s^$K}k{*IW1H%z84b*ZS_(_*bR36E<no-_5R=Im2;{@-@D^{CvZA9m)(#
zXV`exbTDeLBZ}Ku9=v8t;iGK3cDtQ<uzk(t<nYUX3vDI+)QmJAeN;6*YBF*9-*xNu
z2C8&dC|+El?lt$u871SbWu|xkhJ9^2`h1qplaEgi8|J_MYw`dzF89~8yr<Vb+Nn%p
zvPx#IyV&D*zt-Jmo9q{MciBu&*;Lt$WeHhnt>>2OhW6~9J$p7d)#p|$XPASW@7z9Z
zn{aZ$Zu9+9R-AJ<_W62q>Aid3l|T4RioX2Ld0M~o%hI5`pjzkW*T+T2Vt4JkmwD-8
zgJ0$En#o5i3JT6n{_*#SNOZYVnZ#`yQx>ob+RREemCTmaIBJ!Yd*IletlKA&WxJ0a
zy1B#q_4E1m^(vkvyEih&n4!Cb0aT$MJF;W<l~`-TcVD(FoSd4}v!O4d!pCfx#r3|O
zC#|}tSKMXTmwDKl^}!rOu4Ve*>Ct><iL>;on0N2q^;pdbJwJKf$LUYy|Nm&Wv9)ED
z)?FIi|5~Pe|Ce6RyK6U3PPOXdo@{Dk_Uziu(ldtd82&UAvIp?Oi#s)j`7I_Ve5`7H
zpB_zViIx4CefsO|Cz?wZ-V*b9^)6}Sino83E#9G58uG$&;q9eA=U6|JC}*fUu!DI8
z+cBgCL$~tom~MR*9NoKHfVZ^A+E%S}`#HhMW^JA?Htj0&aesd;HvJXDW4;6YYR6<}
z^D<6pMryQ7o-p_K&75nq_+*dGt(<4jd`PMsv_(3(Ys%R);XQlSNzSe)T6;{kjU~o<
zp*<Vp9F$fOXXcR^Gg7DL+)?$sH0!ngDq)H8r!B8iR6UbSo3uk@n`CF7WqbUNX}$CT
zbBS_>tB{2>kacyO$L3bX)ksIE1t-6XQD4g;Y%KWr+?st?E}k^HJ4K0m@ytVs)%(xo
ziYH7Cyev`9P-XCrVHI-QXz~QNo|7f}m-SfR4)pPrEZ@F;`=<{d6!`i1d)ItV&oXIQ
zw|$|Z;XAd-o*RBUr>~d2(dS{kJ+>j%z9PV#k?$aS5IRX2s>$wJ)?<C0FMaCQ!#Tb)
z)J`!yKF1?`coCm4+v9h84(wRm$20>Y`V#KUe15e2-?^JRc7H3qZ1C;?OON#{jRsD&
zjY^<~A4>-EsJR_y>YbTV0;ivDx>$5z$Kf5u2UBL1%c`A8+IT?3QaPs=oN+3*J-pMi
z`)Zb|zrX*|magpOpT2zga^&2F@CMH{7Us$F3p^n`Imm+FOJ$GOt>la4c$~L0Ch5*x
zO|{ezclFb$;{H9m3wGRDe*tWo_1(W5sXYSu;PMJl4KmnqUX3&{U8{F<$L6<J%r90N
zpS`@bT*dd)i*Mh|Zu~vCBb!~KJk4b5Y`tT$TSP%M4WjyI{Gk$(esPO)cj5QLNgFfH
z*6#e)m!bg<se+yHo|9P4Z`WM6yKugd$|8+l_dIuZXzk8UzT+4T3i!5bIJ#{$O@-U1
zo=qzjI~FUP+F1B}`@WW4_7df94?L}#dwKKI!&|J)R7zgEUz030e5W7+N>LY3y9F&q
z?-prf^}c+tDOmkj>~E_{_5c1@dUpI0di5{i&eP7vJ3baC-MJ}Uu9&QMOt$5aO4uDx
zV_MxI`XWZ<!t}vY<MFwY+$Gzj%R`r~pSQX2dC}eD)>i+1eSMw46(gE_^od;C3jKxe
z{4alfCL_`7*8BdP<xC&FUv)c=oege_oU0}V3bo7qGZ%j5yby+5MZUcCqozOA>Wydm
z{fw7i+KhVdKi&M`#*<vd$&TNDM_he*DnaP<@AQe^+V{A9zw~;^@o!J;s;2Tk-UAtm
zzx^{WpmZ1W%qdUaHk^%V^E&xsX~g%R`}SPC)_-sBwEPvv9xRn85B+35`)t(ph32MG
zF`pK_o^j{iJ*(Ljxu)-OdKOvq@%Nm4ymfEb>Zyg#*S)MN=Ie1&{`q?SekuFqZ~xBn
zQ9F40l*siRm1j()%RMJusXALAH{)2>g`X&CIsB;Aq<uk)LgJ5Ibb3^wclqEsjo0q&
z+#%}vkM|}{m)kud<Ia84vR%TFYLRbU;*M3%EriuGnlF3eRW3ez`~3SV`)L`1-g`Py
z?%X$BvupBG&fcvqzaMw??w)#Pmsd!-!s3%IYVJ1sYASRe2lP5#cFPi;dn4f3+}!2+
zIGLCEIbVHNmHWOry4QL(-}ZGi^XAQ))1%O{`|zjSODu&u<4fPT#fYyf{5<1|!Rp&b
zvKAMn3;7$o)0=PAv-@k++-Rdm@9Y2n{(gMnGIs^$E1dAs^zzpY6Ms5%2Gw>F?kmi$
zIsWWEW?#W^df&9yCm%;2d~bI@#qN*f!tjhcs^^Q=PbpcpzIV#z{NTqTH{F)J%xm#2
zSz_?+&F7Hqh3VDzXPdmsS++Xq&enF5XEruACS`upe=nVK*W>Jj9mmdYdcHSL*t^``
zX^moAA^YuI+hcS6CRedeXF<68>W807lk?oK{4LJ=a;tiawCDHSn!V>!Zv-wnrq3Fs
zZxrSgVn6Bo+pul7UFNxaP1!a5x$<Ov)3aAJ>d!TQKHq*RQ1#gD(-Bin`DgyE=zX$p
zwad!BFTd{|{*zvLcV^S!o%bh}rv5N9^?P`!Gk14kd3m|||6l9>-}0z5G5jU)*w0_%
zah{1(Y-{0kKi+>|Utj-zV#5Caf8S3vm*l*dSZexi+Ue8}zZ0UDg?hM4wwb-FImQ`m
z@GfEZ+T%MeXSUwhz`j5aQK%(opZ0X0^6FGhYSEvKh2M8c&%NHAGS~WBt$FWO<Ei1-
z|A<PJ|F&5%&u6;)?}@cXkKH|9qv2JW^6QpQq}k2L%+-b4BXqRNZDwoqtDRb;d+hGn
zv%OQxCLf!7)~Z;dyll<&*SFp!hb>+iSibJqUCTShldDsuoqgv$-sNs-9^0pOz2{)j
z&lZDs=M>K|%s`A5lw1Wb`B{ATN`a#E<oi16yB}Y^SaE;xt1jt7$h{r8*+t$n@4A25
zb^T1Q#F-CPZ##mRXa1XaYQuED)o)KE*i66rk;9Q+#++@k%0$o+gIj&BX00xKzA1Ql
z|G7Bn-rcuv-@et;YIWMA@9{CKC(BZoOu2hPGq!fe-o3eRjh}Q|y??yXPdKe(bzwQ*
zcb{~NufP8`pAGYQr+sYh|LnHU2Ta0l)bK2dJ7|iiDof_dyxVe1^53-5hkhH6FOhak
zaoe!>z4;!EIbpk}PTwfB^q0_H>nFx{eVmPx*5BDtJ^lXQFIM$tPb&7@&);-W@^p9l
z=XX0cZ;H{||Gx|r?LUs&t9T0OKhIkI^1<O9#WPQ(Br}+XiY=?0c{Xip=I)XOzV8<H
zzf7Bb_Sh?_94j}q^X}2}72{|0q<sn9KKlmCqglPXA7@{P{e1Xv^Tk`sCCUprv4r;A
zniH>!>z3cRtah#a$nUxF{AN`vPVe~Lk$NXE$>{9XJ3FeUMs5$zxUlqccIoT)f1m&V
zGk>kcyERiv=hXlG6?*eW#_E>>r*>o~M_!pJe*1Oo`s>GT`AU{=yS&Qq-5Z0QcGvki
zU873-cNLqybIO^N(4GHyU0?dCr*&J_%B+qnjy+QNXRlnUpwIiQhqo7|2dzK%@-D*y
zW_SaebK9qlH{Oaw=OyJnsoY}z_LzSA@hgdUa_6OjIlug#u3Wk4>6(;lp^L6~JQ6;>
zv#jmX{nu_bA(=h9OOo>Q^ZA!WFa0s+RCi(e{N-vr*0YUrPwklPqZW4k!R;Nz59e5=
zm)d5h-YV_iwYtdP`98O-M0uS-XKb#?yON)I$@6aea6Deu8F-w*7ZJ%U(Le7cIQ2e#
z`s2RceHE!UQmS`7b>xr#&)ae=_F&&;)tY^f`z=nXnBC^Qc6NvN=dxQNfAs%9-5*hS
zC-S1{m%O~ZHEvF+A2Z#4+(~^O)3bZ`?%nU_n%4TppG(@jd)->eCz~eJO7~jd&OWf?
zbG&<vRQa~=C&VVNoS)jVPu|Ml9jIY@J6GcIJDEp34Vs8H#)hfy@5cA{?oQFXd~coM
zrTJ^U+#bL6-Tyu|jk|=me5&uX;Fp@JUSCtU8JP$9Ntbu3v@T2BbuK=>Zugq~;ZEB=
zrro-*d+**-qrRG1g4Z+dTrK^pSt?N;C?dH&w)9NW#t&8etEbKM{kg<PO*r{)w)s0B
zvt=ua<WGbAlVy0wf9~a$3*Q&N`h3Cd@i`Sf)7ZY}S$AGuTWm9Z$7L}m$@0>pb_U9S
zC8A9>FX=sBi_|+ubS<Sc!DVN;+UhU)C%b)i?QT1vP&N5{&|8;zr`@jB_8+s}+jpmI
z_tYn;O0i2pHv{L-54#?gb!V?1fB6C11kK6kE}B*=+>YF6xZ&NqcWb0;_F3h5-JEG<
zRU@Hhw!8h8M!%I*iP`JzGs{k`nzHt+safKko9pt^Z&&UudwkC1-w(5Qud3#iJij9N
ztM0`G$+gF&Z+!V(tN(T9sl7%Q%Vh)O()Z>kv&V_AKd1U`3+v?{`BCCN_rrHp?7Err
zB>w-`c<<h&R(48p!q5N7We6jp<@(`!D_-@e=-phgP=4?G|KB#h&auB_zH9RIjU`-t
zv1h9mg}AGE``!y`_W!CHbvr)#XUFcprs6N2t-r~C^H}5B!Vj;n>n|^EeYZz;@$PpP
zeOr&;cy_$3{L-#<_fth?`YvCi`S{!un^0?s%{SL<D_Rv5w(pa`qzT7jV;8?$b;taA
z@va(|6_4v=?f36{Retwa>}9tjmXhUW-#^4W@{2Z*othUVUUM|~ey;qFgG>I3TJ=9i
zs^?56O67QcO_kAA>3eP@TT-sS<zRl~^5g5iDPIloZ=2ld(^XM(a!vX46Q}Er-@K<W
z$#u_!j4Q%R{c_SK&WzeU>s{UIs>6?pebqkw2-<h=?#h*$j$MD#ne+I-QsGqNPiNhi
zukAawXkFs2sI`06KYyGxW2sBvlc%?0KPT>bojUd0ua6ybS3O^ul>ur`#kQ}koBH*F
zU!k6C#{J-<n`W$;pB{YQXJyg-nDdpz#g9ur&ogq8EDwDb9Q$?kxgs5{(*awq?zo*}
zc0ZV}KeLJ@b#Ce9WqLED%6FN`9E+`;v1Px+#SA_~jlOjvcxd+BSsm3?#uGmN`I>OK
z^9qNxXP)nF{zyB%rPn=6tBd6KJ~Q8ZLbCkjud3yirbd3-Ess90*14Sc{)y>trP~$-
zFI{e$+^Q+L6;vY`e*0~uRQWzD*U(Q77w6Q*E<Rbgs>EQD%F3;CYV74puT0&w^70Pj
zwa@qQuGjj$_LQY>?^mrBqj#&WJm2+dI`8bW&mPE3&$<)3^03*9d2eUWp8eqIv(<UG
zuCN9__FLXw7%neSUWd|A-uCh7rB1HYJ3md74c^`P^Z;aM^4(*xQ;Uq|Hog4(bH(e(
zmBRP4ZFb(-Z=rWD_s&$U?`vPZyIWem!tmXlh_zv#K79D__y6RRF0<9=%da}6A-!?h
zqayy-=Zd4|sr`&te_egO{uedgWvN-eVrE~_p1iBIP<-1vv#nnaszTOTKnCR}=cJ!l
zD%@K5{947@tUEuY0)w{~mKPU4UQ=IPJ^OOB-t<LNCbhS>=g*rruV>lDu$KuTH!E*k
z;rQ^g=E~PKS3ISAtnagVPW}BX*{fi#n#i%(twr9xNt25#_dQeb^qUo+w`{#0zuwoK
z=Zbs`P2c(4`|SH<yVu<<o%PGk&wf{V>7_}cR=k#4>Gvyt{cbO-|9$&D-z^u-efBO}
zW!GXXK;Q<?1cs>A-b}ZSTlcy=wyAJ=bac+vsLb+=&AEHROyAX%cD*utR};VZG@GDa
z>DL)r%MS09Dqnoj<K4S=T-Gf7{QUQ>_kG%HvD@4Bdu~zK&V0LNEZ4WbJXY3S_}t4%
zNb9e`!=yVePu<(r<74JswDSD+?c29XbEuvFR<-w9oy(`v`?1S!&z_cfyJvUtPlGFN
ztE9?zSp*#4wKmu7I`X{as-V;_6S9?yc7M(G`4O}I*pkDGvJ-Ba#XYuI7sF<^Zm*Z!
ztR2sfSB1KLXf=B0W4+dHe!o`f<u9{prDaO*xl1=&9Wni>b$`+8Kd;yC-xGJaY`3Y@
z)2cl$Y>(aT%h_pbYrFN(4&zF@Rck&+J}>dQTzaVF_>G(`rCir9e%N>V()7ac=btOy
z&bV?q_}T3D76tDzdabXoEL+*IzD2I;h3Rt8Y--5S<)A%!J?CG)o};<%)Zr&K`+BYA
zzaKd6F-z-b#-n-Z?)pnEr^JG~<MXb6|NJn@-1oC^mhFyRz1H)kLqc}u+nGQ7km{AQ
z{h9PundkdYWkkw<y_pg+GkfRmYn`)aOD~?d?D%yV*NNASKBd<E+?VeA>~8zc8S{=W
z<(oNeY3A(HUzEc`AHVzd?OQcl``gm?dGlnXCRbI0I-#<QUL(&*hJL)-xG7U&M%k>K
z5212u&odVnK3{zCcG+XS>fX@Txl{Whg_Zx-*vqdgy=-E?&;8<+O8HzL_W16`@ZL&0
z(0GA#e(-GH)1NH<@3WKGc`f~NO}m_ITG82k%k^hHS$*oon+wP0=B?z8|886BzH`m*
zXS;QLzjj@lRC+P+R9;rvB$cA->esa=TZ<2=s3qN*i8L-0AQ~S$Ek}yY?plfUvGB?n
zbJ!oBd;7<3{l>1!WmE3H2$+BU;qJwu*MDxFF~e_q)}5cb)~zx;zr1kyl{{x@`NbuM
z@9r2HPUt$(mvt-0%<X-_{nX&6|60x7y}DOgv-_@O;7e<-^fu9lyLEEk_3O*d{ypcK
zdi>iNyIzIQonaHa{MDp)-}jjrT8kq(1q`c-G>^?)pDCu+d&^9!+|G?{?&QMjA+cX;
zWf%7D-okhL!j&tVL}p*i)MHzd`{(D^*Wph!H|H9^oAPNh^OBcSzV7O=zJ4x4y2o06
z@!jy%Q!l0kmD;?wdpG~R(f8Clp|L0aSGX+7{bQiJ+Dy89*;hU3_p9ylS6^LKs(gCh
zym@?Om3qGul79Kjwer9Edt=;sZ}SCJ6%`h%W1B%+BcPkFS2Y!ucX%F7-y1jI=GZpl
zmy3m;EN+fmUKpNg_<2#WNoaWg#k<wA%SsP_|6CZ;o||!N$L3Ccz3&%OYhC1JPicK$
zvu<K*C~y7c8G+Lap9js)edj*+*xZ-rPVV~se0Pt}@;5(s)!UuE^JE`iyYu4LpDXio
zuTM46)t+2)%kT2{iR(p#4}W_2@Zs+ttBzfG`!;uVk9F+LboUFPrteC!V`m*<yf44h
z8PT0#37EPnm@hW&Rj%o~lHN6W+ke;QTxAOqlb?HI_H60Oii#Ci1lM2Q@wxE)X4zfK
zUafjtI-`Wk_uS*(KMU5*UiS6ToF41xRdp*toh#p^nwyuYoiAj+x4f`CtHtB$@4)4S
z&mZ4fUG{DDo#6QI=hJ8Y&Wa8()abH%ccbpi=b8SujXp+h+f{aO<Hwk#cQyx~e_fT9
zYZ%FW>DkU;uc_;pUnHN}^Uj&!*xW7mXE^ZNemNEV;s8s4=zQLH6OPU8kJZiHXBL*L
zkos|_qsLUg^C?D!cKXNe_OI*T^$_g3+iN4+4?P!=>an(eULIS2E<JME)7|G*PE#wr
zdu+$$he3Iv?(de(*k_%yEX%Ak|I~_2|1zX|c5kXq%9?Py$1i_(Vfm|{C)P2~c(h3_
zVdAvcdq4M{)v&mJ@wBE|ZvSI`>Emh-RC5cETHXPov)v-L-~Re3X#L?GpAC(arW8Ie
z{^B&XXvL)dRmWnt-=12xKffk7^z_NCjH`Y(<t5e4Dp^zu%F@NVO^v73n!PZ5_h-(2
z&c}Y@#;4pE%v1TM_WEr!d>1oM{qB_$TDv#NU9Z3Y-C|2&xazbYS<ySz&5cNLTRNjI
z=8NoqC#mw~*SK_yx5k|MdwqR8yVOn7r~m%^d>k{sYs1Z-*Pi_JnSWNT$9nEGJ$`d@
z^SINS{0zWL1i@p6tCDUn_;&HZu^rYdkMqK}nJq3~HEnYC^9w5dyNYs>l=<UJFK>za
zVe&4g?DmlztLx5bU49+=dYArVFZY{2eNP`d(qV6Re0}`>EnhFCsPtw2T_40(DD&K{
zDe=zR0?Yp^tJX?;&dB3Q*!*o_=fRBMYkun7-c((gb!26);j+uCiu6yPx}+92>)zq^
zcJ{@-X;ZZ7#Z40L{M0$U3#kpUqUmjkY;5}BFWE7(dv>2q`)vF4<&V{GSGuh@e~kCo
z-E}#oZNA@L*Iq3;wBvKMevMSQ*)hgrv6jo&GUggCUR4-2b=9$jCudE)S-hmwJ6!*D
zjPki<GK(}$-TklSt@dMqmrmi$ie)_0Kfm_bZk5#XzT)}snYx!w<#{Al{WJ2*4Ba_B
z^|?{+^wOg{-u&FGTpgQq>f?!o9_!{SWywsoUoL3-FJu;W5Y3SmQ<FVtbuQZ}HhWs?
zNh$YTnTO4?xf1WZeK-HSV87aqDHG4_`IdO+XVm{w*GsSe{3Dup`C>_=@XM$k>&vg#
z6y;jI-DGiNO5yarw91MK3yH{Q#UYWuY|_s<-2MEZI9NmYlpANSoAS<`J1uwk`_Ari
zH4(I~d45nOZ@$#pr?blMr#`y9!@7@gSJ@I@8>6$qQ*X?jloyxwYu#o^%RJ{OyFwZH
z8lCdWy#CWtkIyM=y^EBiSZ}w@IQg-3&h?gEZUIwGi)wmS8C~79@YJDu66IG<XKalM
zT_;^STWZ_&nCG9vzs@Y#IZv&3_t`Y%`hR~Wf(Lir-CVhK(W<!gxyNExSgosmS0iQP
z@9*ELyw~q)=d$&n1lg*VCAE6fSMJB>bote?8|PK^y*7H6;~p?=@BEn0(@nMg*D}tS
zboYfu?BaLw|9>3+ex@VmpU?8?yRI!?^xFJyM9B3ipO-IJk6eHK{?mx3J8k>^?lZfd
z#f<32Fof<<d3>(a@TIr$yHyezp`RAM{xdu0Re|QQx$71$iB?{&3px|R@SQ~LuEOV8
z9kb`1zW!^W-t%KSRv(M6{~Ma&HYIlV`ImF_?%cgwyIy(P+Vaew33r~p?&cGA_FDPq
zsf*d{-m;l}TB)hk_O;UGH-9AU;{K!=lzcwTW%gN~4x>%)ohHjRy{_s5)e*~5!YlI(
z-^m2s?&Sn6EwX9l^SOQu+!*(_`YrCU+<Z#rAHDgk$JO$=XY%a2e|(i+INRiid-mO1
z?4OwKnjWWayG{N3#nm+u&vjw@g-@@&EPG;!N<MoIXm0+PzUu#fKlMJQOxVfi9Lt;|
zousDB>T@pox=7Qm(+ARQCl;H$TV<xUdP?yx)w@q_O;X_ui!aHRSR1Cj+SjZrqq{I&
zTE5H8Wk-Uw(~@^P!k_Lmdb^^{<Xy~qUvtw9_usRxew=zfZK~CS*OuISe>Ml%%kyvg
z`tIRF#qZk#W=JTPPG9RQV;q^Tt7_`ITB>YU)ij}7J5JYq`C#b!=i9eyH#ACjPFMSQ
z%4Pk!=P!Qjx_r0G@Eso_FYnU2Hu1|;A;h#~nOmg2)ty$YO3C-V>%QD*b$R^n-O<Z)
zPZ*udQvYOh?{$xI<Pq*pH`_oj&veX1An#PK&(-nISfhGNK0N2n(*O6S9xSQ*G%L11
z^5&z*OXI?iA1yOCy1gewI$NTAxpc#}r+>bDNl7`8yZxWl-_j|8lT^f$@7#Qomr-21
zZ+`o($8l4ipZXGY?&6Nkl8V(ncVAnGT@-t~j`vu^uO7MowtdOZpWjp8U-x%X{h!D3
zpPrwWU;Vv`<MFv~&QI3I@82U)wyP@b*SSlv-_th#ym#b?YW>R`j``>J<o=v_=k%Au
z!Ggz+tvPAEZsqeopoIc|em?$kN6!E5u^q-9x#nu1?T4R4tPEoLrDyU_(YQK2qxQ@9
zg+fc&jP5U~k3P9&u}i6&kb1k-$<KQ=mM;1J<J;%$dry|<w5(mcPvh#ulR=ZWUk$PH
z@=O<zmn`YDxvw3#O1(dyb^mYhHr$rDiG|<yoj<JM$5-+=@cD~bcXyaPKKFEWmUNHx
z{M3ST$L41K&Dva;Uc5GShJ;dSeEHPU9k=rC?0hq;v+#MC|Lm@6wLACj)#Zm=JaTSj
z>iY&z+bH<)>|-UXk~tphmE8Ps?*7M8eKGExd-tvl*|ySeh0&+IlYi%!U7qHCS^C0`
z0-43WNx@eyb|Vc`m6+D-JF(=pVCnxk(tEcVZ#O!2{dY{8tZLSupaox*l9#%CRj$0B
zm%7{cN#zokmDQDYMnAWm+<Zq{HEW9f^MgO1JHK2pNw8QyInc|~zRLc`@8j7j-(yw1
zN|)S!FZb;KZ1c)Dnt^v`uIVccH-5RwnfVgy?6wH2w<ni0KKs1K?8?s1j|!Vz%~|#4
z?n`L$of-C4C;X)Q)J?~C80)V#lPKS1%DFn`zUCyAjdGR=)qK-G9o}(z@#~JcA5#~@
z)&jh~#`@(W&+bbtj-`FaVxtXBxofuRZt_mvvQ<vI)au_(9qqz9WuEh=YNc(@Gyi6G
zMP7RE?%lf|Tz}I1_(pz`S<;=YcMwHzbfllvqLA=3?a7b(dv{;I`(jU=%IiBD-|x;`
zHFxEnUC-8E*m3*0<JXj3e{S@@(KdKzSC)N$W#B}{E!QQ^>0WzyI{9*=NBoCfkA2Rq
z&W<VH9lPAkqs-hWI7jN&&C>E!vy3BiPKi7|H@`4_cf!_pdk#Om;C<I%=kaytPZZW_
zE%s7Bdv!;#sY%ZD!-sZQFUdGqBmZkx)q}^9dBzguU#F(Z9KXL<ee(~K6yL`YFE&|z
zl`F0cPg`$&WXd-ygP#+!R^M!UzC-Kyd(p}FV|uW6Wn-}{5i+^=eZ{Uv)2nQP7F`K=
zCZAV%XJ*&&Wp{$ozE9lq&a_yWE%;JkX>0b)wW_aHW-WVk?d*=vhOQyk9~S2dT)nw7
z)GPAuI=#n!=B*dE3BNnd@;UX+*WZ69A76VtJHK*UZo{lu%XY;omwvtS#3s{HCOLZk
zsTD?NmuEgc_sz~M^UlpTr(Xa5W47__`T6#sT&!)pJBw#eOW%9VQ)T^mhedXkq~E;o
zbHmB}taEFxzjnK(VbYnbXclStEacDXtUEt%ux{gh@owqq%@;sEpPqwq&d24_N$X^{
zFE;+8`})w_q<&BHsuw4|l>XoT{coFi>*cKNpNzs5g~Tr^Z?9Q4J2T_V)}Y7hQf9sF
z`<vllI&C^vYUbraFZa!+iFbDPecQQr?^eC$V&iu)efF-md#oq_x?1*l-K!NRc3tON
zz1vSlzarM%W>t~=Y?F6BUrR5qi*Y-;bB458q4)Kb*L_X*lz>(zuDrm(J9mA~T)w&N
z;$f>pmD?_<N|ft)%h}l2oVfr0U-{3^&(FKg2v+;PiTAr9%gbYmW*c87^`Q5oW7Xw9
z{hD)M^V`#k-d&6Dg9hTQFJGU(|9a}3+9O8qG%O7`y;oe`@q2px&*_tS*qC3p`3oP5
zz3Mt4*T6P>*RlC$O=mni_-$6rw8r(Ui%YMsHcr00Qb(fvYQ4P-pZ~wO?cT{(FY1)~
zYp<=6znyVs=9J3Vjk?`=u~xH-uH2noY}%Le?qz)a-={I^3uau+y6SP)@F&AXw!_b_
z6kj`X;z%*W<8?B(Z<OdAo4am*e_^{^Rrm^VD}#e!c4E8dCY?5)c;m$9jQm@@@qGO&
z5AV2ba~jO~lC6I=^Ul?aA2Ltv(01OwZTh(>8_s&4Dm?x-sK+{<_xGyHk1ka`KD<Mk
zuYFV0+AVC?mP(a}&JXOduD_o0`Ok~KjkeoQpLqIMP$G9-dak;xYo$%9S;@Y0bC-cv
zy}Ym99=D$R`jyRhJ(jQgwBuU(8IhjdMVE{W?t02SUib7EOVx{o;q#o>)oz^n&L-@t
zcJ29Wm*%^tmsxjymbR2wTNu9KaSrGF{E0kMKu1(`+V|82XZG%1B%5x0CT;WNFIBcb
zxBvfkKWguq*+%b9)xCcF$E?!R^4*Tt%NE@55jV+=*eUn^@vqVsZm)hAy_<G=>Bfyu
zcdv`-E(|Y~k~%i`=jK^SMoZVO{PbmM{o7-)zaBn#_Uu_T??L<ee=O&(@7x@<R%-5{
znJS*Ed*=q9kDTh;rpI~rSn71SZokA^?>sc4cW=%`%>N$@^KzfB>OJ#Ynf|PQIiW^U
z`T4(U-y20Q$lk%|vT2T&zh>Yn{moN<>a{OD77JPDWxxAW+Qq$V*5BP>ZMLlD?Ymhj
zCq3upZO^V<|7u5_?7lN9lXqPNC3H5Wg}u91EslI;wsY0J<I8%iFAMU#GzA6y{@1l8
zvRl^}`<F<^#uTSZ-pRb>61_I;-n1zzwCiub%?nAmrtt6cbAN3&mTiqC&dcrV|D6CW
z%6pq%|NCBRh0)BIQXQk*@+CX+?5>(1T9M(0U;9+as@{zZWY5h{N_C&Fs&Dl2U7S(#
z3tv0$t-_Uh(xKmNrPk+gz2iT5+GUqlXApDeJ-fB*)?V3hd*8|An=5venB03jd%MxK
zy=!Wv%6GNi@HgdI^=BK$<%_PzckS!37MH!;HiJ{5{8?&h@%mMF7GF3Pd-Yu0<zsW-
zax^UKv6gOL=zA=7*S(ahzn^ZdVF-#bi&=5#@L}f<*><g&w|P!o+^VfFdAp*g@Olxv
z=W+S#hAE!zov(US?2K+)tA6~N;6k(9`rN0-Vt?h!N*=u_So88LZ_2)p(dUlqe=6zn
z*tYonVV;$X9v0_XPTn)+Wt+*nUw{9dynkcO=jYkw`^==ucOBc2cm1^1_fuOo#vCcy
zY4bBW{_>>K!UgMgJ@~z6+xb6l-{vY`FIjhNZf0fJ+4no8%XeA4X?po<&hi&!yL;d4
zlH%f7<$S5)ozV4!<EGPNqv{Rb@dP8clU=elXkMLOxMhOHywfEc?ypGr5Pj|C#?>$X
z?U=`-E<97@<Bv%*lV%Y&rmy)pZ+Gnb<&5Pi26Nx9uPnC{4!$()%h8%w5<R>B*79fE
z`6=U>R`qw6UzT*Q_5ISNnvd6I?Q@m}tst8Es9$&6_lr+uat+>1I#R>g_V!xslO->=
zhOK<O?dfH=R|XS&+__(yoZFi-Tkm_ZT5tWr&l{uGMg+g-@x0Bvi@!}%qFfiLO(%Ww
zwv$@(yL&T&7g;e&o{#6hR_WclVe*q}TYgV?`Z%C!Zpe1^?-#S{{_dDlIDOsv@>!4O
zCh~ud&bgDD`unF^_s0hhW~qPt-T89=yCpwuOMCc@pUCv?e*Cf`^tz$9rTAmN@;UmC
z{mgl@jAlyodwh-!&v85S^3>*Y>1(|HMy$W?_I2T@uP-0<>rPL)(`ptI?9+RFRjI@F
zed*CN&!)M_3#_`bS?k%A9JAdSkNvi9{<F2Py83q4%ROrE^E2d^$@>Nyyo<{7S<o(5
z^%Qi7(Ff0MjA6&NN|n1-Uiy3N$)D><cV2$Ee9=YiX<`(6$?=<S{$xjgFPVEfc=2*4
z&@98B&`15cpamyZ8*`1``Mi%8mdaJBmaoZPUb?fZ@cWl9DO(M>8u+(G@8+$1U~_Os
z_D;h_xvCdamxGU>yU7+Ic|GmU(#6_cWgb^d3w+M?7nVna+4Wk-U!EEJD(-|;+|xVz
z+<Zbh?YC{Yx?}UrAFPkx)tp$T_$vB#d*SqJlP^4Fx$bOccWvW0<t^+zyQfJDgZ5Td
zf=+CznY3?)zpU`B9nm^s>h;;yU8}s}N_b@^e{MH>=OdnK=l<Bw{O#outIghb?ZY3R
zyRLT_<Q0kXf7iP|2llB+g_<RDwDw!AUVS>WXZMu|o>;#E+my$TRr7n8ex2QTiwQo1
zBi!JBN&NH5WGCtJeeQu*Gw;mQQIo&5!#H=%+{K0I#c{$0@6K%OwGF*?ZSz}?9djPv
z>amXHxp;Sd-TwEg|F%uE`aIw6_Ac3tzMsT*&3RCD;@ENTxaaHczdxO|)#`zaz1@#p
z*K^qrlhOy&Uv~ezVkl8wS2z2SQB%No*XoTC5%-H_cl9mF`!dV#{<D9-VzTwD-})Xm
zl_=lW!*TmY@X?A*wa;c-w4bcC*{A+I<<8Hp!xH7~M+$Rd%QvO)UIquEi0l2Y?}V=J
z>|W&Iwm2~H_A8m>2+?=%-f>Ou%aleGq6~JP@n@Fz9o+Hx^KGrCFN^2eUp_V~&pkAD
zui@Xd`H#;%f8o+&UF_pF`<Bi1T~-f;p1-m=UY2d1s^d9nwaL3{uea(<KfO6he0AUR
zr#tS%_FB)LyY@EQ?xXYckH1%${OwSR5$C-8V85dqv=%3ypSgRtb!Ao6re8m9svx_-
zFmp-5ou5B*r+(r|yfagRIrLm|aeeN(`1E-<rc6Csx%$rH3CHHXoYk)O_2@IpJuZ*W
z9lLTfZ~Lvj94o2S9FzMto&SBkL?(~>Zr=85HQ}c3a;9-+NU!NF+ov=A^c~~1vz=aL
zN4D*f<ZGXLi}kvL^!2@v{hE;VjGn)Q>`Hs`veL^=xkyTs+qam!D+!L;b$6YOtu1I}
zxQgeZ+&xq09)GrdU$6CiwdbZ1<-2~TcuhWb_wL=f!E-h*<b1sDoK<pn-mbq}rOJ<A
zf4ck5YN_&@&)?l~+mP5WN8j~h+;^Yf|84|`?}~8SyES^=QcVNISYFMfeJ%d7j~5?a
zCVjOy>qYJC9_zazoRg3FcsxG0O{cWiT>kmT+&eGDPHkJMFH!!?B=gSPRn_~>73UtC
zyRPqN-{I#*w^qG9HaGikHnW7n(K*eG*}F}e-hcO<n{el4=HprA$f4{Re`tB%$BT)V
zO_}`uhM9Z$Z1+55sCZqe`09Zj#{28$&O4j2w%G7pN!zEDn$vex=X9+s6nCBY=j-+O
zPp_}9_j+!;w|(8Qxo=n4O}<ey=YO`@yP7BUJ7Z2&?VWZpLuK*B71K&TzcPCl#C*i{
zdxh71OUd%PdEcv>r)A$>8hqUHj{EH!6@H~5;-}B0K1qn3@lN5MNz`LK+XK_quh;+i
z>sQe)-KrN0#l!T$XE%B(>uf1}{`k9D)bf2Q$#-6!w)GU+xqG*<U4Q=Lb1CiCmv<HE
z9gCfM|MjV?tx+elwq7b*=i6(2_ot8H-u6(pZ#R!jeS57g#qikN`&I$RJ!b6c-L19j
zxb=kj&6+_W>-L#P87^Hby=2Q@yI0p5tX*%f_tpISNq^z1>}Z2XIdvA~h2bm@CVz3Q
zc{L;3_?_QhvnhqkXaCFG6;L32Z0^Z(g{4yEcCWk7YwlY9E^v15?k^VdudQdzShZ}%
zy~Ap~*3o;lzMuUbayeOe#X5<Us<&Qmd73s|TylK2+l;JpX`A1d+W5Lv$sTvPKeuf5
z9{J)uCWkF&D7ikBI>jN`>$Y~zv|HbPzu44sVCR*K4+|=aTB=U`x+T_Srk2T!ZO@fw
z{1H$d{_VIuuzlU<-FIItHx(<rR@+;4(f8wr#5*%h&gfs<vAU>V@8AyO%rn2|B$Z^v
z`piy0?rvMSwmkIR?Du>HS4-#SnAP6Q`|6fp=KuPuRr)5;r`M1C*<}0g$1W$y^5br)
zlT>zIe3)zQdg@)g$K!KPoP#fKspZ|OrM&J|#68Vri;p>9z5cKu!{pcAyqN3eYoufA
z<w2#~x&UyTdj3+fE9E&h_x`2=$(>J5@5nyHVEoc1jn{8-_U5}HF4s4hn%2%Tdbes;
z(z<0`c`Pwyy0g{XX5YHtqJCO!-3}Z5>p6F3-kJW`Mpvx+y<m{5yk}0Y_1*Rvi(Z3f
zsw=i{;hcRVvZa4w(c+6MrY>H7EAP%tyVs?AnQM}N`F*r3veEUQ%|B0Z{^xD$^0(hj
z0&mI&pYiv>^Oq6ST^8z(&mCpBJoSBH`|T&Ua!#K)zQynMr&X7CTz-1}YRJZuoB1Cf
zd!E7Fv-`F2yKT2)msc9i6q$EE#btS}+$)oJo31}kHh+_C^sXl6b%x0#70;&Wu7NjO
zZ1%s~8=tyr$;quZ??lfJo}247>8DQq?Ff-imfK^67NV>Po|J1bC2^DY@;sKwo`;v7
zdS7d{W7U+SOC`(oD!1z1|5~+nZT!L>>)8|QcD>%QckkCI^;LJmr&m2ayyIeSRFd=U
z9_zV`0bA5&pUbei>iOwz<>j}FZi_u$w<_&h#pH>`zLMp3Nqh9-wsvYAyIWxKCGF14
zJ)378``)1!{m9~99Q&q@vuVj+V{RQ0Tw3<lGT8at^UoQ@vUaC$f04{+E(}lIl6n`>
zi(ve5WXZur#wtO6r8=w3X4FU;hJJ1;Tz-DF_s>~ZbZ6K6Sf#(sYF+8;s2=OspEnY$
zUM<#qeD0~_+D|d}@7$@-^}qY|m)Sd?d)oVYcQ49}+hrpYKYjJepp=Fb@q^z5AJ_I@
zc~!RizVbX@H@n*tYU_M&OWfS_VdC_XFWc8|`V?xmFL~+dpRb+FH<|oBkXTi}{^Abq
zoqh{^qjzT_O4fC~=f6iRJ3O!Cn|`lfzQ*Mrv3A^jzW2n8Bun=9ht6HcqqcERy;x@b
ziR=>ny?#|W{_hrt|1>xkt(4#0$+K(jd-15{))PEE?`@m^UdW$q=ANmtvrl}k{pr0~
zes8sI{AIT8liYu$daNgBnwG|N>pwnMmdtZ|&#r0xo_9B$Y+sj{o%Ji>&QIfaIo8ju
ze0mpoo4(6ge{_j*jJvFLtLMDjFV|j|p368Dv}MJ<yr>1Ik9Q`w9ZuA(+`iXcuk_gS
z&n2s3az8&kyu<tT8jy$I?fVq+^iOGF%=zDc>k{W0n=Y^E_1hA=`|S3>?BqMGbG+_e
z>($&A4c?sq-b;*qk#Df^<mn&piFo(NdYIfZ=h#K;8sEJ)c1?ad@fiI4MgO?tWxFRu
zhIhW=Nimsu;z`Hx>HO<cb8ZC~S1yciE);(iRnmJIG})fLzWT|m)q;sZ+jBlWJe_i2
z$LI7rGv6p>HNUi7Q*<x*^3j?rwLR9g^KwmdI~TpU?K0zRn%iZj*i-x7y*AkCZa2>`
z{@C5Zowxp!8O_{sZpY`T%db57S}C8KxoF+5Rj2ozI`vKRYwneK&4t&Wp?d%NVYg?@
zs$O4JqvZeAu5ek|c*gwY{V=1q8i8{s9yz(t?^BJwm*z{`eSiPt=6{l%o%VW#zE^3=
zrYlc!O{ew+U6MTN&K7GGwN4$hv9SLB>%K=%9^9z7V!5ktZO-KMo#9?qm#@2>y18Xx
z*w%-^TNhTmJvO)h^R7A4kI%i^b9^y-pJp`oC#fFm+vnQyTtHr3Jvn*zx0^eq%QxSA
z^CZ8&yzHA`_iUp*HP5ZDl+Kx47{1iUxBQ{WUc30zr^R>ouBm+UdETx&vjuKQl<zB(
z*mg3W<FVdc%?H)Z{J~vipYnteReJbg_=$#s1=h+wCx4{=-~N3kkG0p8A4?rxyB_oE
zeC7UW-`!JXvrl~X=nVS)sV3#q(q%KHP_`y^2i??MoB!!X@S<JDk+Sl;XL*Lp&g!~-
zeXgd(oZqsM;cc1DYrPJ;o4cNSqAhn!_SjrsJ15EVb>F|q^z2@Bd26oqf?Y-jcWgfW
zKEtGFmROWKkKe`89lp!j+YW4dGkX``<X!jPe@``$lAI~)dVWTKY()2~t#3D9H+!77
zG2%qlRxO#iw^MHZQ26qB>)lz>N7Oc+WQh(wHQjL9z5L0qeUsOC&Rvzfc-EU)b8=Z8
z!;iY&wrNg@%gS|U!qkq-OP8<TeX(+{$F-fw_sfH$tb;2{&)(ly_}y^&!k|TNuKIgw
z@3nn?zxAu#Gv~ln%9pRFow~GT;j>#0?&KZLees}5ch~*bRyMn2ujl3G`~TaQ6B2f{
zX7`lEZ$IwJ>`dLA0xr!G?#ztMpWSPHmqUMPnf1a~J`=r7-o?1t&RoNNZA;<v({plX
zttwrr=ksdU*>h9Oer{Vi*;TDGxAK?CyPAx-tN!nrc*E}WGOgU1d^figrvL8wbxT1>
z`myip883_9?atd$S-bnK7}#&1qXI66PR@B^daJiA_;72EPu=D@Z~FY*AJ_J;(*9Q@
z(mzGRbjr{6Xu0xbNogi=R;%>3PrDno?e<m|+tLJ)eSYPa)0gjGZuDlUbbLvQ!MxM2
zDq0q>Z|aqw{MbiYA+koIe3#p#v(p_Ww>{8YRhAHYKHl`cUS<9%1LKv^W<Lu|1!n8%
z$CsYkdT09SrG=KJxp!vDz5l((?B{B!=LYZeZtuvp`mgrda@)Zj+LyMjJbn7<rS8bd
z+oWqUrq&j0zN$Z~D9$wBY)fj@u9wS%_r06{cJr&(dxNHfR(0!bikpMjM*Y&t@=oSf
z#E5I_iJpY&`}q}t7HiA2^^-vvw+eKO-AuQ#BXN1Ja;E*|us5AH{qO((@0MTxxmoe}
z<G=s1bJKP7=bhc1^Z2=l+T}H`Oy1S>F1TdMw)^h7z{nXU>q=7VRw=&vTpn4n_-~&(
z_q^4G&$GqjZhyY@?$+zoemke_KKtI_o!|78>lTNY7zKncD=#niGu*mnj={S>52D;(
z9s6ElJ-a$9Sbg=oE4!oC?&+KKd12_%dFhs^3~HWAtFOLdm^|^M*_M+FE<QEQUH@}O
z{kH6qZFhHk-YT{<`)3OSI5t5$#$Q_foN)d5AHR*ueb?}Jez)E)m-8iHdf|7$(>oTc
zn4i6R3br14?f2KeUS7NZJO2Oc`pCpfFML*Jmv~G*7Aw8%?JFsdef8n4&et_9<X%?1
zJvR6C*W^2*^KU=du}z}9^lI&Ni?A@iZRa<iw~A`XQ!za@SN3_*ozS~0x91+4`>uKZ
z%6%u>4=2|g-)<&ZzAM%9(w=L!S9hK(+HUyn(#lo4CVqPPb;mPJ)0fv?Z(S3n9jPOB
zOEuvZ<WL9jru>|z$s2ELZo6~j7Pe8@zH1E|jNbWe1l0yX%ANi)&wnj4+v(S{TlRX&
zotx8kzdkovtv7nM(eWL|*80chT0hUY6WY1BRHA&}qpHh0u1(x!DgJn!*G#Rg(o>%$
zFPXWzQ2hAEgDbWNFMg8q#dmtaiK3IiN~KTBa*xe@TfA<z>f_Zq$ldgur`64!N{3&6
z_FZ)F-P6l+kKCVaSCfpfa$4^O=d~2@Xe?y)^!NY&?nf8iQMizJYr~1A!tlL3+oS(7
zUEg)C`Si}*(|5P#_(*Lx+qEuOVD-K1*vhH7O9Hm~y}Y(f%Q}DZvAMa=PhH{I;r964
z(^<DN?i?-rW7}%3x?4Iu+Iqse(j|F5^Jadr6+E>=yE@LdZ0A`!VY_+R;*awzWTNhi
z2iH!2*|BfAOWf+h^h<TC7T<|Ib^FSWVqNjun=-f&rTT`cmnLSN3|hALZufHg=&3!&
zZqKf}zx#~X3#oTnvvrnV3I=V+&k5ahI|wv9%d!8@x=pupl{^<_&RF;P`t<vHuisCd
zkjrsfrhb)U?U|*L<)P-M3N#PDz2<-X=C?b!hVQ_unP;tg8uPR&=5_eh>ep3qvwzQ4
z@my-O_VkX+bHyLOTh15Kxp-IlhP7(ZvNNtdHIphgD_!CF_?(*EkE(T-UmM?5+;aP^
zm9M19UNiB-N4DJYE#H<qxo~;3@wMfJ>9e<gt*ZUB=WgD0jrd%XcTV@q!;xBLZP#ah
zvGUrrc~RTrdmm2qg?PuMT)Mlrgze(&nrT_;pJL2by{k64_p<cKw%cn}^o3t)se19M
zRQ<Loe1q8d`*wY0)eh!&jNUU#yh^kZelIGkd>B8gFx*ssUGK7Nvv)D4&bU9`qWRcw
zduGQv=j$zn;ah!jtp&}#E;{x3)v2wL<#zLydmr4Qcl%A*JLdbx=DshUzbaX=$9nd~
z_Fc~(i>Uq5dwu)nl--#>x1HQ^dFt%$!tk_&u#@S#GCgFDfBN!8W%5avdGqFNIkq^v
za<){t-uaGf+Z?2|4TvS$57X~LHW3F0;o3yJf7*9&<3l9f{pr$5xf3<TC1+W8{mlN>
zoV)nw635z}bsr68pWX8Os_wDuU1mNRkNwL3)$Nb}b-UQ$U0z<EpIp3I)WL0qnL+Pk
z>VmhPiG3Y@bx+crpVsR&pQqhfdfDG!HrQ<Gt?QplG-q5}xy)U0-SzCpzf+Pw&Ac$B
zaJpZpX)Rk{dE(im-!?m?Hmdzvx9owcbh)dy15f+m_nBWa_iXC?`11Xx`qih`ta`m~
z_MOjX(;ok6RR2<2?wWmPDf^92U%&ppY3(d=z0rO@|K^YYdy$nY-AYrRENr!u<y@7>
z$GR?LrQNp!jqZMpJDIm%u$r{VgEjEv)AQRj)+A<nPLC{qAQpAHp0)FPYVz@UlKr-R
zpEiC`tUPz!_*;e9=gQ>s%WLZDqH3qxd^+)Y_VeAzRVqaXmt6^1_AzKuisI&rFKsmz
z$8S3Q{qDT9RVy2N7JDo*iVM3h=N>yZY>uo?Qly%9r#f@sswBhi&F<OTH$N`Fnh;aB
zMq|?St3Q9gD_ibf%`ACVY<ZQ8vEI{#WpiZ{e=*;E*1oU%X3;t^=@+|qthV~6+hINX
z+rrPbvtw>=GO>JK%KUu!^5tQts@6a9b2r;*w@z>R^JRHuuJT7>C;vNs^lyp&m(V+@
zkztyv&Ydn^{YWo=v0nPdnH~<avlmUy-<|c`w%hvp_vE<!CcgXk25($z^;@JoGVK4m
z+toY&S(ZMoJtABA#5Q5x`@WYKJ?>8v>OD01OwgjHi9X`9^Sk}tB=?q=i`>inuJ?NS
zMxG{{a)t9Bm+hG0>Uihr`|GQh85qBN>^tr9#qCutC-;4sc(1=!Y4gVgo6fB>_}jSd
zbMnJUyS^WPv1fv0;q{n1vV85Y%%Y8Mzn^w=Zue1}oO3&UBXiG3UoN{^Uikd+j$I{R
zXY4pzx;rfH$Xw}PI`2w8s=iw{ce2@$x$oXLZ997RVZns2Rl57@|4%!a5){$l{Cs6|
z_KP!{LcB7)WoA#!txeW?x9QFAtUceg-sye6Z0TPcdosE`sxbZcideY^S<3x3pLU)8
zeAke1$B{4WyUz00iW?t&=Xz)E{|KGMuh{qWv-0Fc-uXFW;f<%|F<Y`P7hhR2r(^f0
zZ(-YKrQP(AxjX%3{50{x=WIt}1?L{kUUlxIZin^l$inOA!vD!_TDG(F>AdsLZ#BIa
zJKEd3<Mbx`|2xaGANf6>mEP7ei4C?E;AY^fxOL}h`>)$C&)d_#L%Dws`xzt`{oVC_
z-peyJyTl8xKiOR?US9h1=kCs&TT^{^JKwpwJ^ONTh<W$MEQYA<4DO+GXV00xuiJX|
z`<qud3!nG73zUcc-I^;M`0CgF>dRBBYCEj&Uw<QY`f1R!&pUgLKR#8QcX|C?rfrY(
z_OstwwK=~q{qtVC?~$bn??4w~9eTDqnW>=jC4bOtd2YQr9_4p`I(F|mo_#KzW1A*x
z&aDahh3TI=@-9~|(Js9HWRBU+Wxg#B&(F7)-oD;Qpgb-2%e)=zh1c1ZecyW4GS~Ue
zOFOq$zyG}2bT@B*%DtcWGiKMl6*G9rfBM(kZLea!x42IJoO?U${m%1FcP6^aRkofj
zKhE+%=(7BhW%gpP?yX){{bm>A^YioV=RVn@`|jE2%BSV4?|o1I{pq(_srgU7N9X?S
z@O?kATD&|~E_}MXP`OpV<Et<GzcW2rCv*Att!Hz#DZVR_lg`V2dU0Rue0SmUpO2U1
zPVrtIdsEIje#c9x(C4ovef}@uefi4ouUl9P-Q_Buh??D(6>jkMVUN8ocXWqYK%r^y
zyFF`s+4}TO1%KcFIaI$qPf20cx^uVF3&YJ9pL%v{cf{En&vtZJ?=G%9_cXbx!+P`k
z8141B)`d6w?=yGoE_!v&ed?b}wfV`DR3@d~?cQCT@!0I|E!_()ceZ-Ye#F;>9O|C`
z9y^xTUv^BJ`{Y&BovVLu^grHVcKG_K4YlIsxpr(h#cu`6zvgaQ|LEPOJsrEBeLwyF
z{{HOrbANw)JX|@yy#LDCIoC3$fA4r%Tif^Y)H<vF?Mm;?tn-iDU&ejKw)es6x{lp>
zj!5A=>Cf@zcmI|(`-p#fvT4or3nvQ#=czT{*d_i&`Q4k0*HO1+#0%5Q^;Vy%=6<v;
zPjFuL`-iWC?%dpFdSq_o{Y97c-V0v-z3Zf9spjpHO{>x_-RA;%Y{BiaUF+ui?XKEl
zx5!tZ{K-W3xI}QeUXryTtnH=3=9kqs&v72Ukd;u=mtUA}oKY59Hn~+T=T+AZ>!i<e
zht=LL@|^wVQ=Qq)dFzhc&D)-RWu4EftZH7t^6l)8*3H@VIZ$<f$@$EGeCyU7y{pTm
zd--+o>aQ+$9H%LQlkX&O3YxUb@u}*%^cQQczrNNNdrTRWIh5b+vdo)Yc5#VsnPu~~
zb$!qEPw%Tqx%=(jbxDhxO*>ZS$A9MnrJL$w&*r?^<~h0Sr^X|{<@a|Stx|fYa2n#1
zli<wZd3V95NqX{Yv#Z`1)pYG%rfsbB?$pk2hl-EH*3Mp2z2|dLtL5$DTOogL{9|{R
z{pekg-mN(2*^;wLudnUdQ@=%1{n5EMa{J5v-?1)zzIf#h>-Vo?yR7H#KO3sO?>?7R
zeR}@Jd9|YD?S~zA$G1I0NgsC?d=d(-{Py|z`BQ((cgJQQ*E_s?N4C|EuZr({;?mxG
z--)%(@7VpTIHf8k{?WR%kIf!#I<xKihTd;MY>&>#F57%qt`!u3tv=zMrF$2&y!%^x
z`o*8QdyiJl>eyWq`e@yb<Dc(_L%a%!v?C=AiCX7l_;Pa6mc<mEew4Q}CaiA%8`)C5
zSL>>I^L_8UT%(Y4xz6{z^W~W{BE$acnID;3El~dJ`ulqhccw1B&6ay!^U*rVj@|EG
zU*G=ejxqT9!1Wt`zMH`ilVo+^gXX&!5A*qt^7h7=OQrmnB){wWhWtn8T5~pJ?qBx&
z;8c-~nyX)y=cKM!zb)HnLH4b8Ip_B0-px5R`}<k5?ms(Tn7`*d5^MSRW5jCSTk|e|
z{y)d*&dlZ=&UfyjTjX$Ormfwq_y76-f8gKR&wKqWgY%u4SEUQX<HIh$zjG`3QEcaK
zwasd~#mddr%M|Ri`eEC!LtEWb=;z<x<(h#aq5GtqpU;`M-T3;Wb$(XA?6&JU+);e@
zP7+jGP7J?MQ|`l{XZSZT%DiEBP0ZD&2aX+G+`lfZZ^jkx?}dAJB`d!>^Xjel9aYbu
zpL0*U&k`)(uK#Y<mG@#tV(*sks>`2}FHl~0E_3#ycY+RgzWU#px#zj$D&&kRbeXa3
zrNZT>2adHqs7L`_z;+<JIsfi1rFU=ox_3C=nR)H(vOT^>V()5g+ir0qpXt##TdR8Y
z^S5W7`)Bok=68=Pe~-Ujd+&6uSo!3WPhRO<ai6{Nju~21INX_e-8=lw+Uu{wUgz)D
zTAvsD-uF(a>Pk7sJ3pf$mimR6KMXu__hG??tmyAOdGp`xp0nLW`VpVuCt2Bptvi~d
z5yj`_#UD5Nr<lok6#QB&&2!Ai``f3$P5HmJP00|cd%L<Rz%5YecmJk0<u{L<H{$qI
z%l=6w|4HoboRxcYl_gsbUgvL8knt>8nsf7b+@y?>Ff;exW=BdI8h044pZ-o^{X6!h
z`i0@&-_8FM*sr$wpVGToTeELhpZ#LJEj735{#D&KLaq}(m!)2M_b&3z)vLKSa?)QP
ze`k1f?!2XK{h9!G4dr+Hns@9z`>RoI>m$AU2dA7r@Bj19pDn-iDxXYzZhpS}_?Lh;
zNs^!zf2x$es;8Kdw5;n*gMa_xI!a7!JJ;3RUwY*7!;k%?5+|)}&-<mC+CKG3hBorN
zJPl$!qoTLj-w!{$^2lkINvS%QAAW3ilvt~8R3^kfRYUYt#<mq}+HdYVYbcxWL!^B7
z-E~H<U%p&vcKC~IZRvC0<#F5f-j(c6pS}Kb?CdJ#cdOoS-PQQMz{2F;xvkY3R_@qr
z>%Lv#ozMR0>-^X5)-U^>d3Wn>HQ)D=N9N8iuKGE5*I&W%`;K?+ru}v3-}TWBbl<3)
z0mw%dGAV|j6?2d79(|sy>eZW4c*6enDV=~tO`R$)zt8#dHF8RjQAOqN&o@0k#dd9o
zwGmm$)OpP`_4YZH0Iw#`BE=U$m9=4ut~kWq`&YBi{;A)jFSqxdRN1kj{pLPB1F%>0
zKFvCzdb{WakH@jc8)f*~PbDk8JM*e{$Lf9NIsMti{7UccbXvz|mc0G9+FE^j{~Pzf
zD=%){Rqn91fBxl@b?I;Wq}ywp+zakLO5#*|wC-KG*d4vCkIsDy+--B<s+(NplhWy+
zrniJ$m{4ouis#o4@$6W9C&(yvuH9|@6d8@c%b}jvyq0-&N*&vD-st3}kT`X(DOJ<1
zbDx~Pbp59_Q&xC>oN>Qzzl3)|-JjyH;6SgF2KVOMRZpJYC?t9=wR-3KGQEXX)4SAu
z?>Y!hY5MKjhQa2yUmow5UwcKi@cO&L+57&V{dUjcj_Km{kIsE{lDDt_x8}}&!SoFZ
z?{?WQPc?3Mea`;TJ8P?^)8&%4S6$b=&i`eF^n2xZCzRhaey%C^nQ+pI%VlN2v*@{h
z^^e|tW?`K#aC+T__y2y($TFDRoBLDm=-uB=$GkdcO<8-RQtNg_Va@h=C-?Ok{55Re
zVXWV-U3h)VzYgoopYwj#UOw&_ySLns=kTdHCcbm8oL|QKOQ^gwb!~P1;&+C#Ph8*E
zy?fW^4;{u40_E>KFNbWqy*6iibmaQ$tyj%YhuN;T{@=0ty~4Y^&2<adK}qC<cFsQQ
zW$kLVC)DiDl?6XuDpRs=b6?-@=bJz7OS?Mt<VK%KokB~GZK~L={Wwr--q~ZP(@#y^
zH$PAPqr+dpR<++&hrS%|$uBgQ;nV*7O73%k>N}qzf%31<zs)-`_ho63>bn?ys}CHH
z&V}yI4%#0rUcRgLy6r;ccRs&LH!OZ9rSNXwWR;V#_s*C8FD!cfmDv_i`Pi!c-2J$Z
z<#GHb?O4rklWG>WJEYCNoc{ZAllap9t7)5NX$59!e7v`4&d(&N=S6Ejym(`|T(T}p
zOZ#%IY~ruvW8W97Us+L|0$ME+^7C%Car!U4ckA}b$QOp!{@X25UfO*~;oX<lZ96{m
zKUyb$C6@Wf-SV7!$`#x*_I$rw9=Q<3CGR&?>aG*ny{pFk?$Po|mrt!fnDhDh=WR#s
zRx4e0IBD)VBeh)p-K&4czXdJY@lUXI$7cKa+wNbD?YusH$8Ix=-J*rz-#`7|<bEV(
zOYZGoS8d~>%I40#S6-^U^537ImtR>aynA&z>(VrN)+4d@D|WMCi6FHTPiiY;G{5~)
z5@N5MJ7>w=lCQP%&5qoC7^<e8X&zf!-yd@Q(YZ2#Rng&>9T&fr4_v0LG^=huZ(;a%
z33r*}x4z~V+2!tEZG9oXD9`s^;9_f#qn<DJHCs8~w=(w1#VvoY?aemeaXvEFEz<Y=
zZ{>y^uh~nlGZcQ8J#shq8vhpuM6+>bjjlnU+D5y3Dspq#(gK5GPB^}nEmze(7x(b7
z?zD+Pi$XL4KgHc~f4;Z$r`9I5-*E@a1XfkQtL@&stY7rk1eJAitvOY8x%<0!82{gQ
za;Mv!t;+98UR`G|Ot+dXQ22blmFAja*#(xkY>$~+J8fO6nZ>_CxpUjY(;m-Va{s#4
zX4RduxE+?fo(Wp}*k*Kp+0)-owU16a_hI*@Rcp?{^3i$6J6GpNABp{Jw(_?}@wuwK
z>+bx&wVPS6{OIfZU*ybJMo$*aDP326yY|Q4giCe@&YL>isbw!LpN*O<d1mkAVN!j#
zC&!_DQpEGk=PylldH9k4vqs(I{?#{E?unZn`rTCe{VnAk^&a69Tf91hlsoU+X??4m
zJU!d^=_koD{d}?CyAFOi-qU$z#cWR_x&GeM-8(k_56t=<dt~m<?}rW6{K=d3Pw=mO
z-JcbAzTaA;==+}cc3I~R?YRHTy7OmTS^HYF%J=;5#dw^^m)*&vsx`x-NbyG5$HK-g
z`}a-1H@|wb;fvwr_e)l<WKsQ{_nbLUYeGhB@V1x_D;FNw{cG2o#|t$?PpDYVpE`Yd
zrAl}6-F<one+`q3UKH=taPE7VGtoOQ_RdWmo`TA?zV#QB-ksT>U!)hqYw}C!-Kl%V
zH^U3V)$f$7ufP0j<`v$;>-;{q*ta;}t)HOqZeQ^C`75_q*(;;8qS1#@+Hbv>{^nEd
z_RW{;m?hmOx}@$|b573CH?=gXu*{${b*7H$JRX;oT}O4!$*sM6uJ3+mbK%d8i#+1O
zp1<FHd#>DD-V~GQIj;)OXmq(vuAQCyEBV;=9oe&9dfmCYmZeHhKc;K9+SBcS9al&H
zTfThxslThz`V`;I;y2kPRBm?v_39njm)^-a-dUO%wKHF$?bh4R_Y5-SFYuLqmwoik
z&;g}$@g-wPzIUhFL(emsfd@U7b)Vh-ea~Be;}2SzdoI6=y{4Zm$x`{wVcuikkADkU
z3#adoUq9>6sSWb^o96WGyQ=K<?P>p)S#NF&T$VTP*sZMA{M@c%_pa$H`P&b#KJGJV
z$*0{vcVC$GC&BHGseHzl$U9eU`D*^XD2R<;T0Kvo{O_B??^!2*V|*J>em{2Kb>Vly
zv4zKNEAJ!s5jt1Oe6W47dNyNFxVSiz;^{p9JEl9ucHPe{ioGRJUfR!UYik=iZDpQd
zgGHZo{PJB!VVqZ&J$)N=$23#ga#?@pYn^?KJ65j~e{}BOEZa{zUvh>27i8bg`-pE7
z54eLoHD{l-8pHG%Jaaa$k#F9oCUl_H;e^qV*qi0E=iF9fTH1TOd3K!n-Pcb($r+yA
zWm=ei>s#rmn@jG_?T$Zk_i<qPS-GEgN?5_hvAZKmd&V6{QXb4n{n{Thk3UVY{Mqko
zjXR8`=UlD*u3!JN`_EJT`iXbf{rGpHTD*Ll_Clq1T~GI^7N#2six#HWpMCau=Xaxf
z)*aR-jE>04ptPJPH-3Iv{)%m8F7L0JHEXIkAFcawSMB+=={r`hs-OIN+3t!?|HAa!
z(*(+o7Tuq;!`M>p(Yb#zn+%+OD}a-00SnmEuu%cFbJOpCG<~u9_r`zQ>wj<mG=2Y{
zr6r=lpl}u_PraX8l=t5E&da*(c@Oy~M_PC6J}yvR8f4))=~nT|YMUc-|601-*~*XI
z?=?SV<D2*Gl7F4c-J<hZ{as0VQEbuqN9*1ghTnZ18~R`G$lTN08h3nFfA>mkujX%m
zmfN2nJB7WF<1b9VFDF?3cJuAGDZB5+xt4F#+>t9#J|R`=5!UuC%L5^BnAGt8dUfyY
zRAJYP+uvWEnr<VPJ^i3d+>KM)mK`@;S$%cuit6<b`{nI>ZngUE%_%N5e&={+=DHn!
zzI+MU`QB8qYlrr<-I;%VUbXFb&E8?%P}i`dS?6@t@!z0cMfCw2$RG+dxGu})#6R1u
zbG~Tjnlo1QM=m~nY_o0A@|Vgpt*-Cs+~aU(r{tg6bF^=N&Wd`r>!?6UtL39}vGt3h
z<BrVzYwCQ5v4r^%-zFdDJ2&mJrnB$3bwas+&$~}Gpf1-%*@$Vi$FDC~&;RJ0%4+^c
z>sBgU+WE})$<f7KyMNZi?Yv*KGw12OoT9xxsvB1S<|}-@&i<mVJ}6}?zGK+sn7-}j
z;_u=84tFc$L9xs~<2iWf>)nA(Z>;yR)xQ3E>y^9IqjPl=Ru-R~eWKf4w0vFsy1b%w
zIp<futZmt`+qQ7}erX<10u(4`xV!LjynRvqR}PfS2sW#<`N}r7+HL)=SI&y;s!@-d
zY^3n+%#+r&4xEQK1nyjYD{1y4y}sn<xrd)fU9sI~CBrv&OYQW(4B$|h-MC}3eS3#>
z!@CPF*ZYQLw%=w3xfM1}Rl+_k_5MofCEtAS{ERyIS@1~gT_&+mC6DDb+j3WU`b{og
zcH6G*-=CLja#JGJ5+$z1EnoJ1nSNn<m2Js8>m#wHY@p<>^p0Vd^YZ=A=IzNx&X6wU
z36<vxEOKJ`LK1)52_KnTd-wIZ(#zR*)eEODTlwd({h#JPSL6Rq{c3sHR=)J<Df!4N
zOSu)Bcl>V7vo0>Z8}n7YWA`(KcMQLp{p!!6ms0Nze3H5A7=L&73m-Y(y<vHi9aSHl
z+xM<?)3&^+cXu(?-Tj_hTv}ZB@6XS#b9cF~Dm^z-yD+^fUg6!Db4PW%cFWt>g}j^n
z|9EHj<DGF|f6Q~Z!}z6rS^egR-%xVDwBv<#$NOcw*NQgV*ZukN4Ky}U+N51yeoNK&
z^*UpZtG4oH&o7%@SMmNH^Ky>y+;4&3=k46}{k!Q-^VhcmukLOTD8GN(=WeM?|M7F{
zX8X<FH`VUXHAn1rO+FasH=nImt@*~TqV?Ca-#-2&RK87UNv7m4t#_~D%yK79tzWKP
zc>P#%N9>*1%bsqVdUpDk&^tSK^mXjMt?W5zJ*(fT8*j_*o#yzUVe)r2?{<E8>l|F%
zek=NA^1@j1$gik_!iCr8?a2O>w{O$yrP{@-T-Ki}T{YXVO8?QhQ2T}*#_vDZY!hZ^
zSa;#&`j_k9Nu!KWNWOXcCG$eMQHSfDo6{K!)6344tP7U@?k;mYYG%jo<6`BdZ&P;0
zSnVxiV8~r`IsS6|U2{;5Rt68*$n}Cp^c|Wm%il{dm=?KddjF)_%iEW_EdG!kFWO?%
zC3LfXO6va8YIV~bC%m_w@Vr9#{j{exI>#1W2?@LYt@6IdpPI=2P18G;fBIGPxBa-m
zJ!{+jYR!9Pj?BHeQLwyU{as1l-D7_j&c69%W8smz-_0I7-8uXG^Qj&c&o#gHEPF0g
z$j-36!LQ!8z7(m-tI{aj$TL-FX`4~+^hqk*Gkci=y-phZ`}c1~iK(sUMsSb)ve%46
zmDgWvtfyZ6GR3$T+MLi-Jy@c;vea^Y$L{s@{NM(J;IwPXr?(mLPhF9qGFfBNi>B#U
zcV8~fF}iVjXDGNQv2*=P>&}w?w@C};Ht#Ubc2<l0S-wlCy!82(m}@T{dEGIc>zfg*
z7G7$c`MFlGT&?tS?s2`o_8rU((GJV^FWbKhDTmqeu}AiR7E@G|fBYHI8KfL3^XdFH
zBkn0H5|liD*{avpiY=YO1L|{^O{$rGDMy^&b*00it#y|6_r#3OrN5opwR_K=MxXGP
zH=pmc;YrzMdE35rYWh-@8M#)L=hd3`&WRQ+*JImbR;kzDz2mpv-6kcFV}B{V^GR=*
zb*H$)`pDdK9|g)83b<c<x&9^mJ1;!JEo*<6tQsiMQB|jVrs4MS<1<SxUwygxujf49
zaMeidnOdq@5~uA>tDFw1oU0M|Dl$%AC0_6Bl_eEtl#aXSIxlr$b(U=N@;Z9=-}S<6
zcRz2M@pIpVjk`3yr>Qjt8O80G8(Gdf`CuI1BR_q8-{9xRUGL1CT5Thjo&NMbsJ(WU
z!S&9~t7o6ox!(zu=f@i5O+MEG6}(!F?!S6duldgG_|3}Zh_cq&??Rw>Q=7f(&ebnJ
zk`oLjfBpUL$6lkt@>}cw+%2*0WcLcOnEv+V=I=)%xHf-?I+C(s`ek)+&$YkMLWZj}
z*XY4kOMbonY;De0Di?oNZd#cge>66B=jnCM;g8OhR-f7AGf8FTnK|d5N2Q)#y1Coz
zMtb4)7(MCu#d@F_sTFtfEo7{0r*~L0>|l-gbGGd^8@#B#>^xa6MYzBJ{U&MsrwcyM
zEiJiYKmY1C)79(#{0%(m(ixN-x##-RbLYi2-!K<0PrrZr3{zm1%I0`uN&cqG{Cy5?
zms@l6(>bgTxCyxghWvc2QD3vM+cEz7YQtMHx1Sc~sybc<RVw|t!SmJLUR+XZV!16-
z`pR4VR~gQCZf@KCnMeHZoV+$}&x|6QBeD#4nDqXo9nNju0h$Qon*F}-rQy$gm$D50
zsqVfsHA(+u`k}dJ6K>BJ>(Z!QV>bC}NN139=XbTIs|Ct;N3dP*o9=yN{rk61uN$m?
zKA+VxZl3?<Q%x(^$egy8_Pns%asE1+)zTmOjz7NEx7PT_^`-0NK!YWF&TUIwu{wM1
zoX*EP0{7<BciisSy-U=t6yoB*=Qe(7!k(A61XdeNbzgVyY5R_1^>?q*q@I1(e#FO+
z$0%OE`QbK1(f(z|p3~2^?g+}+dZcRllPyJWwztad5-Yzsdk>G_%-!$*Z|nYi+~)K9
z+!Q&srA_a$@6Y-UIp(kTg5-+$qW(vI<p;8hbLJl0&uLcadpaOIe6D0==+A9TOJ7a&
zn_Dz}F7w^@J8JgN>;AUl_PN(`%hzV}?>jR0UGf37+<hx|Sj+I4YrZQf24|feKW6i8
z_g%Z=bh*LP&!2<s?Csa?^Omc8^7HKHyM~Tx?@vGW+IU^{nq!<gxSxK1d2!)%&u!MS
z!L3HKbX7p(i>-^U1hj?T|9vd%*+QYEYLi0Vq+2tXTK?~_-kiMK=KHov-_sYu3$Jgv
zlN!11$lQ|~W4E~9EsHZ>Y|ypn*zpZJ{bR12-E!7kwA@PjveG*ShFh-B-|Ielw{Iot
z@Y8iB;nYK~ANxMK__4o4LUnohg}DpA_U)b|ny$T4usl*t{<q7bi}TB`@y<)Wxu<?k
zpZLkB#}>zHS1*0^|KI)pw>!Ku7cxJ3=W+M(LeHX{WGkkFEVK74OLe&OH_>js_aqg+
z^xr#onV0R3O?`KMzWvkV{qj+7uYHSBe0OGjYW&gIxlh(+Ycnv!HtcA|oP>2$3wMp&
zHSOkuAM8~Y_v2>vmQSjSUwvlUlUHlBRtL|E^4t94Shw-P8D3FZyq~}S;e9&&V$Ojq
zy``;u+cn-@dtLgpu5@$HtU2tmjS0nPeLl^a##osC@A3Wi9hY}rE4{MTpl8SLxNp^B
z<?GhTGC0guc()*L4`RO67S^4A!~YgEg2?rJ(^-4(aG}=Y_U9J=@U>f)w)|67ZrI)H
zIeT7xKOwqOsQmR}jT*g^HPsUvt)dIdjDPQAdgtmV5_9Dy<Mc~T?a?CTxl^8o9f`f0
z#F8jsW_SL(!n;q~KAm{vmmb)&>)V$vUs6i@uQl#)zQf2crEv!{qIT{->>0u;?72?o
z$_Ldw=fdX79@~BEO^NB$1u6I6)+l(f3a#}$9i{s2UaDc(qAL+%?Vr!{FF${t_0h_6
zqTG>xR&JI)$G&mb7tcE{?M{6?@#x&qg#G=G{M?Nc-<^rjn||)L!lQLNcbpEdbiKpK
zAmVt35mDH?D~acL@uo`YpBF0)Smd@pW%~Qwwr4|vVg2xZwtc&-)>>H4II_uSnvg%+
zqL8CWVoUq4J<HJZ6YNXb=AjaK%t%%%P;0_Vt*xs!E1zP!Rr-Q2<n=wq?Q!d+r{7=h
zQlnBB9)8_`M|y6&bmJo@i)nvX)Tb0Kk2ard7V+J0?=JV^+*^frcmFGT`P%8u(ZV}F
zqF!C&1zo|yQpk?n{P>cqc~QgWq>ieV#L1G4KexR&^3Ozi?WCrP>giukN3c201GPDV
zW6m6E-ErFJXGQd>FWH4$ss}T)x^sV?erx}&^USg4Q&zhd<t&J8U$@~^(uM2gh1ZWQ
zk|@pnTl8P=NUUtX#=BQ7exklh$|k?Q(ze4mcm1~9Cwpvn2qjuQKkZumGV0D%+joB+
zALn2Goe7+l7~my5c+&WMWZRC@o|Bds72C~MerIz2y=~WSwdZS2?!B0@O#aciKQ*PA
z?_$0sTU}=@eB#UZ9kvz#)T}vo-}dg!y9KjRx(_cOSe_Orx3p@`Ju>&+&$Y7|Q=;>Z
z#9ALW&1_!wcI(N%X}k0vt^2i0;T^*Ru?s(UKi}PRK@SmN3^7Tco0sKHkaV4xBKc^Y
zZee;=T)yL-x!YZ1ZwZzA`}<G*{qo;>+ehbW?l1d3`{lll-LGCZfto4|$iWUV#b4jd
z{m#|-*Q-U#t!A1%I(N1If3!&XuAoa#WOiE3@31~1%iti{VU09S_&{j3yh(@k-_IA=
zLA9jz_x{H_K31-CPT$CS`AoG~`R=>te$C5Jdgt?-cdktMahE%a?-&?PIUuD>HHPUo
z{w#PodB^I>L7#udY|@zw>eR(gQaN^fpJ?Ipqz(5&?!1i22Ak&lu2XIG%~{{1tt{8|
zbz;e040;=XI$l;Ue7;$y{qRDg&&T`aJFJ^OXV1D>UKqapRY5d!k6z2dymNWmSA*;E
z{nvfJ)ut4Rw<V@tdsyIbhw*@K19El+o7cQUd*1$4F|juna6j_ff5+}<tgz;lC-YuR
z-cfw_U#$G~)*Y*(&$v9_m@fawZ@IkV9mWH?n1(!#p7wR6jumtD^hbx5>3!D%op+p@
zCgOT5wdCt#`NHS^cV5~#y?45^(_(ptH3LJnKzRea;^sV{YG$8Nb9$5A)TJ*E$Q3TH
z*UL5XJ=MEow|wF9+s_2c-(KfsSddFlOMc*;n_D`IU!~2CJ^ZA$c-M1|!sXZFO72ac
znVKhl6Xfu{0oTnh#ox6@OJ2ve>%0z*oW=KMw?KKReMYIAWi3nL^!e=J_Wx=-ckA`7
zuI>{k&r3Jl_2xLJzSMv5XYKb`w+wMaxd#qNNEkf+xZ~RoP~CD_vPAFIKaNLw_WA4T
z{wTi_C|7&ys?H875|*qxFW-Os-f51vLE7&=$@={K^9MAExBC4gce%<s&|C|H-bTrW
ztG3s^e)*yjd98QH?YCu9kN^1jIem5N%G0iQUdk`-^$9KvzrM{^PJQj^RawTq?>LXh
zK04=mzZI1D7p^;>|EpZ|mp|IDz*~kjuN~9kPdDwjEH2}_{;_KN;e(kw>;M0|yE7vz
zx#6OE;dB+xr*%JHty|aMy(9Zxzm2V}<!WhgF|i;F%jm^M*@l-qFY5mNiQL)WS5X)$
zb|iN5uJ3_&c3Ol_f4-LgkzU_px9`sLkIX$C8gScU-P<)MK9{{+H22qw<FoEvRx4#@
z$Phjvd!_fgVEL1Y-y15y!*VzH4wSH!#Pa^yCHG-oGsLBfeShzCElj_x79;ar@aWvP
zJ5Q~Q{&DoH*WM0mh6W|%Jo_c1=8f>oUUs25|9-GFZ#*+;Z_Si9v-jz$O0~xSUZpT4
zaLS2)i*<g-ntj~N(^PZ6(dM{x<#wItiH2fJmu=d$?fh@IN6$}J#mp@HwsE?O)ZDAd
zDi^0(nIA1<SZ2K7b=HOJUmL#59GSbDu}*qshjr~DjZ5d&M^90m?_2%;k>B%w@3ZaO
zb}%<oGa{Eha$T`H&P!cZF7$c4ROO^o+G2+(K}J30_rLjuU!MHp)c05~8(F#k8SN9-
zT>ktfB<ynVIg@Fro2FD42`rt$a(U{KYftwmz1#QCcEZJ+!d31OQT;l%J#9i3g;Z?I
zubdm3V9jt@@<OTUi_4aNcawK-1BW?t{E@l;O1GSJxwEx6=C0XO?>kq|ws=oka&f0s
zKL5H~-F|lk${843k@M8cLW>hgOI$!B>D}j#drgr#`DjA@wyBW|Tv&xYFTJ;X`FgX)
z(v%OMzCGVO`N?jP#N8DdpbGu#>7O6BO(?X>ULSJj=~Ld6U0&zy&Oc35*nD>W-|x$f
zd?vmBtv30=qH}p0z)5A7)R&(+-j@&Ni$6N&dRMT#%>Li*Ea6!B?e8C*b15**yxy@p
z?X3vI0albaHK<vm!o?hTetoNCf&0#-DZ8v{x7nZE{Bo5_wrcQF7vAKX=`&Lzwbl!(
zdfA?S-TLJ8rSQryF9N+eEB)`Y_wY<vQJ{DGbnW(H&a35&FPUyL&N$bwZnfk5^P3dj
z-QoS<`{~%@jh~CQE518qU}6`3`st>x)r&HtuZVh-8sGPMz3TQkf%3QaFF$`S&2T^+
z+0867*DQ9J!j-!3>dpT_cXInSe`eeGhU@pc{{EG0#y77#UAOGGJWKP;HTORskM=%t
zH*<gD9{rOyJ!|w{6-_kvTz5Tr&xShwc*$+d26Gu>!<+Y6Sx#D(nVsr*XQ%Xo*-u{n
z<M^)o?v;zT<hK6Y`N7}$b}h>d3|H7$xBW?h#hNp>-<BOao_lHCZn1K`cbn&^cuHNp
z`=x?`As3~!#_wA-!Pmxa-|4(PQ<~3}U%OcNzb5SV^)<VUET?%I1%g^=?@M=n-h5Q&
z+u0+r|Mu2|#lGDA#_#tl4_D?K_Jmk|qtzEAmuwFelYewBL~rMcYVk+sT#6Lm-I4z;
zb|h9B>;RGSb^n>2mdBS=+AuV1L#`Q@9aoup{keU8L-R-dn^V_`RD0S9zk6d_^!u`t
zAoAqsk{Z!RdE%!Z-1=D5Iir4k(5FzD#f-3Eu{#p`l|Mwh)cwxQzdzjXD8Bo3tKU?#
zd{_T!W`-@kckfqC4!!))471bq=G7<JQt|tqe%i;`HlLk;ez#cp&+6A)-8oOX6X(>P
zZ`|>F_WqyJ$~kN`pw^J%otF<ES%qD_=n5(;V}Jj6P-9nq%WVDD>)YOU8u{EaU#@*D
zX8p6C9ocpBpS~&EeXKP9mLDTS%!4XLl^sZvu&}<A_(Y2nub-&AUAFrD?-IRtMkmXb
zC$9={+uRB+9Rj9Eo%-;nn(xTmw+d&zNd1_STC3$9yf9Tcv!-MBviFCJ3T1PbG_KrH
z{P*$yX-DRsEG#`b<Mr=#`H$AUi*2eEEBAffw}ZK1Ux9^8%I>?T%63mx@!a=s-t!$l
zc60qj^yY<AK5aeVGV{o<ipdovG7&9Elb~Ti`d96~b-FBmVDf@9<%7)WXMZ1;?D4o3
zx$Jx2?oFcU=YPEa|98Li#b*q+zA9|)PtDZYlIMEIv~rCekF)yqk20~1X-e-NS-flA
zQC#SMr0`Bww9B2Hxy$$c+Nf3v>N7aRBQ>#R#)ziAj7n>MydVjs<0Pfekof!G&b4Qp
zzosv}Q4@Oe(#?jyQK4dm<x5^xFOqY-^OEmFZTIezDUV|AxCW-w?2EZ0Y-a2zSpM$i
z?j4&2Pe1?O-Mx*Af#HG(qMGJEoTk_8;Ax>R?K4m1+RrzeOH>0ZWCD5~ng84|YwoGn
zTO&*3H-B7b+f?1FRk+=*>(KK_XSRz=uK4Vp?En6-_UzE<=Z{ra7FW%?E#pwGsIh5H
zT;Gc`U7Kyq9-X_(@L%re+?5W}eC>YkI^D&~)sE*D{oj?fd{^n~Up3e6>g(OoVqkCx
zMhs5dBF%7qa+UqZvEF|5IX-WB<G+5pW_bl{dS7NI09wPcEOo6=`TI>0+JRX*-G_fZ
zZ@>KfKI<bpxvro_pGjYG?(eBv+}-nRi)BNZ?TI~YeL0z{bvmreng5s_nR{~anOcGJ
zbtxY5M`B}VZ;YHOQh5DOoL#!z{OIeTz6nDuBfRZ@S$QJ28F&CPz1vD7aB)0nLHIep
z-@GX@u0m5kZnCOAVlwq==Fyu6RbZ8qme^*E+AU`8#f4o3Dw|!EP8v;n8PFL78qPcV
zZ+CE5!L|uUH?FY?x+HR&QU1|84p1oV=PgVRdS}<M+oI2Ur~0gIuHui*x&2XiH|zds
z-`k#(U$ZkXTwp`A&*XX`{iRMzXn*P3yzPH8+2T}LKYl}A!2RQ&h4>@A(@!4fYF=J{
zRC5Z;;*~nvreAt@<oIlz<%{!6`zF;MeZ2qM4Za@&<?g@q-o>1)dNq4TwBGb{r|+^C
zrq8PH{aTe<Gq=q8?|%u0J3IH!D=l3;+cxX-jITvIx2%(X#K*w!iwWM{RAZPvg*T;i
zhiYMXc-U<BZ$-1Ztc4>dO<uP0+s;x||6gkFN?M<<?cDvf>g|(x8+OL6dtZNKZgk=D
z%jZjP)`PkT3-qsa?XF=54YfS|{Q2^$-A^XE&$|zqamrzP8~H4KLS^r=N9#NzbJ+Kp
z8NWTXE_&_^hdXzt?a02RH!DVe`uG23yVuS=oBBDz;L*CDwb#DZ@-i@7FhgGa4r*36
zf75Zk^YjK^O>FG;T{TDU=5|_#e|M2TGWT`y%IcWOzn#<Xt9^;R^YYBS(n=c!h6b}0
zqUGEAZ#`vPXZGoY^7`FS7qvRhKN5TQ%)Eyie#v(Do+`4C*~3#&dK6^PyECgay0#eK
z7Ah}YoulTNR5I7+o~d}-!p+r>0*~IU+G|!dCFXftR+Fdf>sxVm|0dpEe*@etW~g0=
zJcPlx<4D?td8spx6vkMtSS{VMOXiDd?fIC?n`X%6+s(J$omZN)i2spac-)LLe%ao4
zUY>iAwK#Xz9`&5GpqWp83zb{VTo)dj*VOsqt7-9$clKtxGS)LNF!&;sGY^DjJ62Eo
zS!?rkQnYZnUKrn6>$Z109q-iIi`yNY%f0aSlGs@(ujee^C7HBrvv}z(kNZdFdRBkD
zx_p++qB=hjSHIiZ3=9prh@{C7lVqH69yDugnUidgU+r_ZxOnxWcLf#}`rGphpF6#{
zwaxqT@sihRcl4%vKYt#yyjS7fncJOfcNE`^V`N~+K~zdC4<^+Jr2Voz68ll+)gtY=
zvt)w5-?_7DNA}`e(AgRN^7eB&B`!byEmFShdqbatGq{(@unV={?&`t!Xk7(gX<_Bv
zbsOW>Z#~ERXq~NKa#hWdxw9WDy*uM@hmqmHTEuWE=K<AaN-FGy;Wq8NcI?T!{^R50
z_9dBJJ9aCAdb)G(-G2OW$JS~G_XVK2_II0azwH5yCS-5^tMHD2f#DWAyx;&08n}A+
z%?B;4%rM!p&$V#5a_S?CeVT>SRXRTxzlgr`wruycO|K0EjS6L~_x>+cS>robF7i%m
z;)^d*x3&n+{w>7-?%pAmSsy7AxT{`R9>*`87kFpw_3X7(UmfqfTql=R#B=xalju7$
zxA4z@bgrcJx?T6~UDbzEOt08=?zYNtl>+6{JXu76&!D$a)<yZ<zl2X7i`H(?Q0`iE
z3vARW?jv*U3)6qy$eMq2?m4^It@1}?85kUXqYPZURrodU$lV&d{F0o@jq6uiz4q9-
z>$rbuy8KtqJG|}A>CadA3MSt&tL?JB{=Hu2_}V+{9oFVwt=ykS?X;0&U}(rjl=X}|
zmaJ|3t=qYK8S@3ZZtHNN#r}`hoi3jeTVx><l|6gi(Yfm;Y}_ecd-wl#wRb*gMxbf8
z<DgM4l&TVvO!hu4inLs@y1GWB@cJC9l^?!*Y1vV%^X^v8Y_p&ZT(OGDn^!PCI#*l0
zleO^quKR2Z3<ZdBGSFxQSLZV3s3WoFU)}EP6f94ah}s@0|5oYrm)4$_heWJyc36MT
z?%Ki3z_0-^NsCwwD`mk#W}oU|<juD5zUil4fBxEd89ZyY?b3q$M|l=9Wp)qF8VZ)H
zy-zpZSr=Mb9Qa-DNbIa-=Wh3D7hZp6T2$C$RD$HVTVEnTLkJZih~Tvq*&Wg5)fwbG
z^O(2iq}DTTjT%c+B<kgJmaTs2+4c0dp6a}LDSo(?yJp3n(|)8Ed(tFeQHaLkn~y^J
zKb-oAIe(_jJB!a~wjM`e=i5^qzHEEUj=!r~_E5LedhV|qa}KM$z4GnfhD>?A+pg1I
za!N)|yi-y(<Lu*|k<+f~Z3As~^Y`~Z_pba%?C!tf3=9q2NRB6I3hh%q`V?BMVEODw
z1us@3&r6%n2Yad=Kc7B(^WV#$4p7t0Ws^VWX!F+a8m({Ku{+Kj)KK1f-!5ibx6bL5
zy>Zv&E<ZE8sq^`J#PV**DW{)q+WfdQ(j1f(Y_t#som^Z0RF_1BS3kEJFz3n3r(g07
zUw;0ZdZk(H)ReU;tEQ|-)cLJ5S;zZn=^~ev>6LpY)a*0~p8UwLTSk5>?^GdCo>U1f
zP4V*TpQd|0<*#0;QTp-6Youwk=*)&4o2|FKZp@cxn|gfq`R9JG?melxz2&%;PkOd#
z=JIXd+kJl*+|(;s7diR(w*1IDGdrF{3ze%mUHTRUnk-n*kE<?C+0@4rs5RwhSo(kO
z!tIvl&PgBHr2S_1^okWOte`H~yd|@x&ZPX^XI=OHRL^ec6w!TqdmXn$QzkvXZg2eY
zo_Mn6nM2uvAUFPYmN|ZpZJ*V9q2j>uyWh{7P8H9MS+DjsWaYE>s#h{+ue)EnqPTw+
z#~N>e@^`oEE+^lN^Pik8={oUq8K@aL1!Xz&g(d7ak34?7`^_<L%NI52va;XLr$4Se
zyGpy>MQ5f4sHOLP*PWj?9|`^TDx991c6?^#;hi~r@{>|$?#Yi!Su$nCgWtcu_w`@x
zOZk?q_SmsN%7E2qmR?G=rSk<wGv+fo&UfZME<WZJ{^;GFwOcgxZ|#Wly|uDCd)Z~P
z+cQpvl=hq1#swFqTU+xKK3^8M?fRwC{k#ke51KG1Hf+`Ihez=q+n*A?E9i~tPoEu|
zC3AjXb`o0Je>HBtY`AYPXq5WK-${WVY6V1k;`CBt{zbgq$n&#FM*sYBS2M_*+HA(O
zX{noTzm?)O5-h)a<@dECv3D2mH@m*t)4H_q>@SUXv(9WY&i$;{-@l`{-cPWcfuZ0v
z@}SVN<4<DE)*qdkv|9DrZk6RzllSX>dEk8KZJliT^{Hzstbdh$JMqr#Sz>_Ji?Ze4
ze_h>M|Ni~|fA4!YNG3cpkxbbo$1uxg-K$+XwPNM=_5Vu3zUw_{?R(;M=VjsBk7?q^
zo$l<+{|zcr7_1T564qBko%brQS{|2JddKJ9<W3f^a@Lz`&p4}k`KqkEvA&xz?Q-%~
zLxvnBp}fdDS9R?kZh9BHWo@-cxz+U*Yp4I4E}Ommw&^+7J3I5uG3}~PiRje$4epAi
zv;-DavEP-9dcQ+EvT)lZuEO#t)on57o*L;*+Ip<8FLm{_uKMrg_316WF()&PPQ01C
zV{`5OX=gXaa?jEe=iFf1=2`nL@XpJa#p^(|*L&C9&UbdMj~0I}QpnE0P>Zw}ETt%P
z%F^taynW0)4{NGZ&F*>rs$FXoJ!$pkRcrhzH@(UJdNXm4{@-_nZTEkE5AyV0n)q+t
z{)K;xX7NV!_QssNSScSF&U`>kY2oSbwTkanT@)-|c7659pM@90O4kL-9QV6@bn7m8
zK6dq;ufOiPXt~vP9d}`R5uZSL-g{P1TNBYZ`(lvu%!p%3%jZo8PoPd<9XyJ<CUyNU
z+ag!3BX`U676u8qyq@&_t%{t+&sl}#v*w2XlXxGs=)t0Md>KX)@-`{BOqz1OVhd;*
zOT=~W%I!g3*IsWbi@Y1=Bhi2S-0ds2UAwonocL)Nb9US5O?mhKKKry|*>Sf!rI-B}
z85m|EMyFpET6C^TP&zraRqEfFB+wF6gLU=w!RTGIs^fP-gGp2NKGxGeKL2=zf2rQh
z?GfqbCXycJg5|!cH&wSQz58Wy`NEcWu_w5X%#A+wc%#Nr6&`2L%U2@T=@&kKw5u%i
ze6>iq+9G)dh6UP)glH?Y^Tw~uQm>uT7GHim^ZDwHdH%*%uQ(hFR0)*SU%mPJ-KCqb
z&TL&-t5tm}fLZdq*wodJv##G1^kuu$v0K?LeT|CerJD)+xhofLp1}O*+#k8px&1qe
z?|;j8ytDJ&c18w<7$o0c#Il3dfAd8x&5rHmk^6g61)l6=uIw{EdQ>N-W4F#^@Zy>e
zYvh<E&kNnGkGWkQ5SbosBI)5Cc;%<UXDQ!%J4;VLT6g+jo%kmw_aeo2UuOEKolC!M
znp=MO;f2V%Ieqs-Z9(~;;V!}r;Ev2qnfaUV=w%wcaJ@5g>r}I+uJT7?FMl`uC03rB
zQm(mW)vL7Pn#svaGH*rN&X!s22^xiEXoyB>rRK10w(PL}oUHtA*7lWm*Zs4d=6m{X
z>F<o!cN0JVyz?_>_p-O|rX7i${4F`yU;ZsPw`}J_?(^N?OWVv-m|mO%T7I2+``GV0
zcDIC-ay@o0d&^gN-7gx{U^}q533*~;Tk}nw(<wV+swOK=w^_C0^{0=!^q#OjdS{kV
zwBI%G$r2v3|Ahu}{npv`pMUPTybaXwYH(*oZd>Q1dQ3Bw-XqV)zWi%NNMU&$@9lNf
z;*;14%cV_r-jBJ<Z1!l~>Bs`JuU{@gOHPzV>{_0ao6?%guYYy8vo#)6?wxyeAa<Vo
z(lhs0reC(p^X*W0cWY&O`1eh3x8_voGcYi0L2WIbnxOM~`VQ;$-r>ym=G@J@zH>`K
zVE*M@<%;?xx2C-ODaqH~doJ+u>*gKV&*fft-8uWbShD~4+$)<st+&?BU+DS&>F&FX
z44_$J*fI^y1FF7kDQe97^w=7<r4}ms?wTg1_bNB)yPk@#^rO7(w@;Ssp8B>dTQy-;
z+<dcFPiEV7SkE>xiIqs+e%o`BN|e!#?856y;$rV|GcYjZqNEaE_7pp|nYB9I?>63=
z5t+Js*RssYT@y@7jnsG!yFJ(HT6FGq`#C11+&lcams~*oiu}}qt&85)*p=V=wwVW1
zIwm;dSOvkjW68^gGsi)rT^DV|9<7^YC3!hy&kdWno36hz9@k|E&woE9Cx|Wlk>7Gz
zPzRr37h3lguKi_H)STjf8ZXLrn@$Q=)1Up`>C%$SUu*TIo77s?)#V*BxT5vH!sgwQ
z+AW3lTR0!_ft+<gJnQJ(w~Nav8&>z)d^+)3?>uOW@uX$UMz_WPZ;uq0Pkk8`wL{DQ
z_VerCT7TwF<evVtXl3ZXpEd9Ho~d2Z30m#pcWS|Bj!&wEGS<27q2MkYHWxlKJo~WV
zhF5G!df-+=iL16@;g9^j@7fZ0e9p4>i?f^W@2@{ywDZb3|9$#3%k{OrX3O2adPw5+
zS1GU~g%M>I<BlWkJBq*VnAN>$hg8oiufy&_<+-uX)#lh|-Cq8>G}~s^j>{|e_kIE8
z7={@rozf0#^X9<2$@Y_W6svmPa&q7H?QP)weF@s{V$L6Wvw6qno!5Wsyt_3^6Exl-
zg51+{yrcNe=XRIg>#w(}f9DnT35Z_bC|bVm{oiWg@@?;V-a6g+TF9o$z~F$g%U0-!
z>?1$%%jFzqv5eQgTXrovQ7!qq>+B%`(7@R{`?<ev%becE?+ofZD<j<b^5Tyh>PFK1
zDi*wQO$Q^=PR7}Jee(sMHL$)mRN$0`SIYmuX@B)*|A=IB-1pvL-s9dq(bGO}kmwEy
zj*PwiyjJ<+=MQUg4!=JB`-Znr@40WXo+V4q`DR+Z=ze_T_XAt@!t}U#X6N(8zveiJ
zxK4fg{`ca2`(8HhFwUK<_ud}VKzFc5sy@-T`>`&XGAZ#-t(pI>S@T@N_q`8#^z!A#
z#Rii~tLDu;l~r|W<}v6hh$)j2c1^mnYfku)*j<w{7r3kpaNB%zrQE}*kKd}u#l4G;
zOBXkh{qpzU-`l?**dBlWX8*p<-By}cx9xcSxNFmO3mHDpp7@C>oicpv9D$9^u(bg1
zQ(qgK6>0V*FHZ&SF=b$2KqL+Diorf5y?e1Wc43RIc!;(C*}V1)c&o>xy7Qj#^IbJn
zo2PHLpFdaS{!)(HN1Z`?Jl4ja>)+nm^Et9Q{K(xju@2DC=V$S|%P0Bt%|CBe|LyMl
zQvv(lSI)g#;Qz=kJZx*=w4XKWO82Z2v%aubPi>}JP^06&zsbteW6meJfO@@F@2@?c
z$HvgG4^ddZO#BhyDZ;jBUOcz)gT5l~lO?6Ua_T3g6R|DNwXgqHn^z}Sn-S0Y&fR<e
zNX7l!el-L%$M=2t`Fl@N7r3+*-;8^=d#-ndqC)Hg=Q}&+m0n(=vyN?XZpWs5Q`rmI
zpWE!(vD*3@s5AMv$e)?PAs%UTh`>Y=v==ka{$7;b<2=*QMOOkI{r!HPzk8y_(kDN^
znsC3aRZL#$;ydZ}R|)+!_Ya4+@fTjdw)=3-DWm!4t!>M~zjHj|yLHS>Pt`N>ep>(e
z?|Sdbb{|r{X1T3DQW-SXa|Yp-FF5-x@(yaks$RXRALFK5+egPF#cRIXboPyfalXa$
zvk#p&=}i89w!3GFkm#Jf_4@Ne!++`Ro_mDZcV)(b#ogB7sg8FHPt=>_Jel;m+~(fx
zCQWbyxfm(YsIA;%_g~Thv6D{i&dus4-<G$kc*(EcYiGS~mQ>;N)K43Kt1f=<+d)HO
z?}=}J3hy3TygBXo2FAkn9hX@P*`I%Lyz_Ejv{2#oKRa^wK4M^CSfGj2%bi?)bB|bf
zS8VLQ#qS<jpUixEBVpUm&pY`GxBo7k6C1wm(c2f-=ew85cI^KD(f(h%AZYEWUWc{C
zaW}oUWqIMp%=SL7oxj=Ym(IIeuRyJ+S%|d7X;c|67v8mZU&j&TMRdrWiRVcd8+W{}
zx={Waw2|D}@>|*Nw^J=5)?eS6D%pSB4Vr{6Z;jD9{A3>g;S0YlS04_$GxOeQv*S<E
zQZlE}Pvyg2D%XzBKC<|-gRWN>w`IoO$Lms#-t^L1ax3jy?77-x?au+7K@-<(_IWQ`
zo~nIr-pBZVr|S(L%{vl1N#$5-;nx>&_m9l=tMo}fs`&1~oM_?l?FQUe!tR)^1rLSi
zA#EC;a56LyyqS&9sO|IHsW&UsUw+?uD#vr(M<xN$N9&5jV(kvU|FRb{fwM*{x_zAu
zXaIA8Wry{5a6N>aybPfI0HcjX@O^284TfF!pFGYg(^`K$?P~4WW4pg`yff80ayL^f
zR$!{_q{>;Y)6efXeecQBTWfaJnB6-)`|{^E&UbcJ*?bj}E`0uKZght=+t2>CmwT^$
zDLiK+P!3954N-;D-zS`U{v7>e9GPoEtX?4o6Q4M3c>Cz_A-?*wjejFc%OZZwcv*hw
zYDm+h+U=hkHAFqOnCWI;{r%j}Xx$Up@=D8d@{8{t2NhMGljgmheLY{LyZQF#J0Tjn
z)4d-%E_*#yb^p5gtvg=-x{-V3_BNXi>x?EpYmUPKkd3X+xr0+AAvOJkt9^*I5X;<^
z#G~uOl4DQgh{&-Eftvp5%m1<&^(l3ps)(Fxn>6dxt1XY-BnX{0iuAIP><AL=j+|l_
zH9L6wsyCX>yeT%(SJw3HwoYX=nx*Sk%C}|d5>4OMN#~CT$4)tVbz}MN*tZ+o4kxC6
z=X=C=YZ?EhGf(EtKmYvR`AFG75k*kO=UIs{8*q8?MDS7yb;IQ@tjaU>%<kX&yv_dX
zfz?YC?%hlMYc$Pq!gIbSmiI*N%RhIzlR6W;7Nb4=tHg<lX(#?IPWj(&9_i<P|CNmD
z@2=zZZyoRKw4c6D<(Q?F(njCH>(?G%xFDbBd*^Ob#iq)y44~0mxw**WCM*voxr>#r
zyT9{kbkdesIpM<V*G${~HS8$v*DqXN9P=)df#HQVB2P2K6!|~W^S$iHzWe$))kl4f
z|CAec6!U}3Js^YJcGw9TZI(YG`-tzB>vCDpl%*sjoiHG)s!S;qcMV*A-0jXm+raB=
zhYY41et02E(&yKF70*5MH(P<0R4||%cG1aSc-^(Oq`;Or-C|9g3Tq+zcb8b{2)*fR
zr#~#PxDz_t<qjhQMgyq)_&VX}ewBBZOupXRwlMbC<3jygR*>}3&x_n4QFwPpc6a`x
zb6<HJgbSbVj&=SWlg%G%qg2g@O|{LY9ntHr`}N;7FANWtyIlT9@twnR+meqRZ!E!U
z-xzFA&QmDLe{}A7^^H8=J2TH&xZH7!t$wkqH+|;59lKkPZ~v|Hu59<*@1L0&7y{Uk
zon*6VNAX{a`L8AOa;LKwvit7H;g7XfnqBOlyXpL+bKiF|GBE5w(Xc~e%1j=E!v;B9
z?d+Zg$sG4{jlBJw2}LJp&jdpPN>{8z_uZ|!DSqL4yzS1<kFS&dW7oAK`|%y8{}%cD
zc5)MSwcFR%9Tx@VbOxkqgmK4{dq-kLT<@JKeE(=&p4-E<o<bRJ_x9D;Dpg1JY3-`>
zxhoc3D1N+f@ngN|-k@gI9UYX^l>f-D{K4&G4*za#RG-}GqbBS*Y02g6*HJ33=0zX5
zn>>NrIKKZx+_c61m+pwkHePf4TXHY-)$cnD3=A=d(RASk?{~g;Ug}LN)Moyvrtofo
zZ;|5N_M$6WJ?|F<iqAe;2TDgDULbelJg+}m_tyOyUwd<yWnQYn{T3C^eNVh3ml-n%
zmKXSmxW>s(JbO{F{Px>x)t058nI5z>72CaAFKt(AVud;LPrJq)&BdU|GfJ5`Z^!HA
zge#1o=6ix4j;@cbl>Bd(w8xDs%MUsmNSxNWdD{KtzL&Ry76ty;x}M8P(zWxA{i#j&
zQ-$qME1dW)d!l&H#PZWca$?DWSz4=4*WW&Fv_`gKZoU50>(5{R=6k&N^5^RQNAKpP
zJ@~>o|2;p;j$<`;`=wuA2`@bEb&-MLLi(#?hz)p`oj0CddL4F9Szv)s#QpT@C97Y0
z-T)8k^Yt_LW43DD4J~3lvtrK)6@K40X}ZRw6)i7+m>BEKIQi|hb@a@3uMmSto+r!W
z!ruFx|7hD~J@=~r-tBLtUBd6!9{SC^(EiHS(;q9|?Csh0CG?JAw-^J%FQ2tLHrHO!
z<1g4c(Os_c?$e*|X2`WS>$tfKioe&hlh+Q+Qt5X7cQY)lQApHB#dH7jCF{>GnlkC&
z>D%+q`%QWu^zZGXg&LwBTdwIpKYrWk*v~bf{Tx%*o?%!0>K*?yQj;@nw%@tWwq3hb
zJO#>i8+J6?1zp$6_p|~R!e>wx!Sf$J?zPB3;On2L8I0Te`;A{NTYWkG_hg&d>%2CF
z8HIXXF_>06&2!q)Pga48u58{D=dmwl)=JNhGmx67XOG-1tDE!C{7>n}7f9pqz15(@
zJl?&oNR$v0OYL}kBmefkK!NfL?w?#E*6qFhY1*yD`i0wXzts}owD3F&LxUZnH^gZa
z>E5Uzda7pi=Ko7~+?Gjy&YN^o^xIu;n~+6KGjm=Qg<pQWAQQ5c#WuFEJmN%zW?=Kr
zo64Kq?};Y|YE8JgY<BU@tvepyE!xigh%c}AZeF=DcW}x~dr-nGIE}~&RT-C>a~^&C
z7+dxj^^6DArN7mY+Mj2V@)h2F`u>{LD0XRU{e9$(C<k;VTr5$%eOj`KuR!r#+hN5=
z?-(8KFmB;SuNC@FexDkKyf!I^EqdRn?3c+~XRcZ1HATv6kGbaj#vRr=DPMBg9(<n@
ze|XQlda)-Jm3EyQ6STCCe>&H?<8tIt(ZcfI3hx+hv4Z@9RES|6(~i8ecdyL-T=PoZ
zbK6dD>OFIKLCA%-e(%4ouKs`T|4;k>$2pG3zF4IFZpSf(GW5n1%gjCc^Rrd1!CRQe
zSMRXi8-G6I>&-c9VZ+qt(=N2{V3rjqXL#ELn&dM;8X-#w(mVh<5kZ#SIC09HdyeI8
z*R0=ph0R&(5`1TFSkGQH-q#k>)<$XB+1g58+`7a2@}`+>1>D&Drgq}VDh==JM$$6u
zMu&fXJC(C%@|WG8`Yhjurk0*6KB#ABr)C`+n!0q-G_S*dZ0ntWrkY4^n6>Wc-2dB{
zw_!7IS$m@KbjJlMbEbPXO!b)xI`L$7{j_x|T>Z^60{^JVhi?w9+-tV_UA9@=*Xk!-
zFFJOYNA^q&Sr-v)shqDHSP+=buJF!5{D`c>ZuDULVll@h)L`P1Q%<~xE9!r}IlpT2
z;fnCtbJr~sn(}7%Tz(hOeznZV(j#}H7J1*SSbHu@<Kwz@=kgrxH0tdFP4`#mYadt(
z2~0#8k629u-p+UEaYE`B@3No!ZeR8>HJwl>;u&)6^s6_u<tx|tX`ka$+o&^n>5<8g
zlh=fcLzdJy-`T65vS!MP=dW(o+$t?&dBj(8QM7#DX--gXU|?W4gVg)aSOVG1p9b5^
z@2dW7`OS=}B1dlTUK4-Jh~v|pMw{caA0>&cI}&>~Yuj^hql|rOX_@QvM|n1K)%pGj
z{Ezq+)aD$yTebIFTpj}hLp&nSF%@`Df0So5vtqsejpiN98S>JF$E#Ht86HeT^b1)Y
z2py4q(FBqO)tU{G$hGDpr)@5QEjy|iK&h@7oazt(CEVa0b3!b3Ve^jNxh3n2-y5=I
zuz_<T4|2=vWe{j&@%`7<vh~JAVhbd}6}xfP(b#>>n)Bz+|Mc@`=GWLyCzQ|U&wJm;
zc|bL`Yxn*A_0{Y3w^Yv+EN3|D0B&Xln%{H3GtvDX^E2?-T}?Zfr(c&WWWT@zaWm#&
zJxm3hkN8R=^`>`NH%xQHVMgq>+q#eV7Nmk|ZH6?oaO*qxG<UJ`y9t{a&T<?U02cua
z$jv2as{HMvCJc52BXYns?O=`tg_-biLvWCwG)7+r-C3IXYVSTs)Rl-eg5CEAv7k%1
z!F!iT`M%d&Am4B4KUdoZ3i=<+=+?_F+z_L;ce?O{X_hj4;DBXDbi5gN9BB=SUVnWn
z^XZ2LFZQmxz$07O?!b`22Xc^uJaQZrD!waeIhSJeF)kbwg$ty8!lymm$IQ^+j#zYv
zw2)u{=?e+|Y_HWhe5>*L(eHNOCb=x$T-BqpE9m($g?9&@mbxi0n52U?tS~Szm>?47
zmw-1#FHNUp?wO(zc_K$dMt(2)x@&eb%w4s8Nd>z=!(ytB-qot=2dV^eUM{Q<DmK1Z
zSDUW>F`zSOVNY83DXZNJv_TiU{Qt(XHa?w&$)UL9zVxd_|JfKAc9bH5kir44)JN~M
zqG$4VeZ4*Zl!51^&9%XvY6o5C-n}q&NAlK-x7iEXFYsp00xk1=Tc-W^qXa081t7-o
zQMSQapVC#mOlTMEw0);G2Q5-Nnk;5%mnE&GswHvCz(lzG_Rqq$`ya0Vd-K`6Qc@%E
z;h!9~d!27%4skQSWI7_dW6!zv!w0J^8Q*cv{eJhSo-zYNgFhk+9MxWH2rPA)nP2*C
zzexG)$8YvH>g+zW@Au>6RR?{{N_Vb)S$M%@#>ro{^?O2t@5qW7g?U|h;B;Z{e7pH7
z*IygPMeJ{1-?Q$>-J+de?&U3zw7Pz?T$1q}FDT16m?E-_+^jDOvny(9rr)j5WS{$f
z&Em)Ze&+01A6c4Oq%%2Xk;}@BI`>`|Jx}kBe8YPr_Fvszhh?k3{NDd`^DD3WsoN)4
zEYK9?ec^TIBgfOX%{!Q1$YGd2IV5iWf1aQw#ENCT2{)g8iG;TcmVZC@*7sDp!aF{0
z$=cbB6~{8g?i<`Qw{BzXur8>aTRUCw!98$c6oP0zy)>+xem1*s>5Z#TtzYTwn>;71
zk2h_${rqaN@_hZ{<+pv~E<f6@{BFT<g?9|QK>J4+0(^0_)nSv?$P0`sM9Y_de;s=p
zw5YlN|3`bNi&J-ezMHndGA6y@9k|d42}Uj$6()Nze*38Q@rA_<&c#c1OlU^50&>&t
z-``%|dCvOXsjxY=i}M<;A3MOm@Uz5~*ykrx9_{U6_zo_+7tF$3M*!a-X)!_a9OTTS
z_?y<xe8Q$))jZF-`^S$NZ%Rs2=huYZ4BEJS`>Hql|K8p&`7r6h_S<hIBJ3F24?EWV
z|M%Bb=D5*JpM4#VZ&XV%zU%#2<M*G7fg!*Vd7Dd>gjum9i`Svbo4YUi3B9iQ7P)JZ
zh7Dhm+sD~8F=zdre!aD3*ZP|k*X0iGZR^`nJ^g5e=hv>S`Jak%!(#2E-#<P3vNA9G
zK{<H!blt<fwu}sS6!zEucLNpwA&B{=mxU4DA{v1QT_$lK+}7PLj_Y`$+^8_w!tK*u
z1es0S(BHl&L}BuinvY$3>Xaj8?#xSPt7BmJ3vL<)AbR$oai1LUZbtCoeXYk2o`M`K
zw7mQ{{Cwv0{u#@VCw}|-H^#-DS@h-NEg9az>Go{DW6Wpgm!IMS9|<6n;q4hL@q>}!
zi#SG_CVqu&_@i}crnmEJ_M9xT`W5zE<7T+czifVHdxnO8;P%f7L_sgy;EmlnhL}SK
z_!$=L2RFk|4~WDX7HSOB4L&e4ywC^LObuCxB872BOQSr4Lp>w~BXSex0aczq3=F@#
z=kA#8qjv8!2Lr<cVdQ!Wq~XhSP*;nAfk70xzUF+y$FN|3&h}_<7_lPC6^0m)|FF4%
zrI4NBLOi(Yzlv!T7Eglq7-DlXXde?a6qkkFd1^i5)6buvrcKy=)qa~#f50u4RV$<(
zFfxF^jR)0pihEH;#sXU3+rI$GF%;DQkb54p7~6KO%unq<=Kuc*nq&F=^G>yGUg!U>
z`~OV`O%(jRSsj_zS^xKXz39>@Er~Do>TEw&|I7cs=aisNpzYJ2<EBMFTL1sodRI-=
z|DW{#KiaFa{Yd@a_5VYs1by=V|Hc2_=_2nxkL~|0)>!&v|KIKZpMezo|1<x8@RT5<
zxqf@6Kb`ht|Nrm*yMnyh4ln$^>5kO@hxUKi1HDe}|Nnb`wZ3=wm)JX3QMZCAyxYZI
zn9ly_oZOMQvK`je0_9~2@7_4vx!Jg5Gkf86d*tN6Qh41KtmGS92{TwP-;uet9lQTE
zBG1cr?0)A6H3eimAF}a|cfRtYCYVzGN9Vw%pt^v$FrEL=x_Z=jUsnxrB*b{Q3uHU2
zs|CvcqBML3%I`Ms*bFuWWIT!on|HjHM@@jQAz=VD9ufu+<K>RT{zvo&KyC5Z?~pKn
z7|#xNJ;eBL3h#a)&P-Hem`*|vgHsm+wEcP$bb1j)1X3t^ncbHah6pe~f&_eyF;oQN
zmlV(`%1{wVI}~ipvn8Ll^`wZf#jkc^edw_$MPL4wr2Hm-B}vv-Qv^?B?3$1pwJHCX
z)_Jd5+1J+2o!{?&|9?YWsQ26{vo4jJ^<N(Bkv(lD&98Few3)=|GcWecyn6mcOwAkB
zPPh2f;KrAxxf8$l>MXl|+AKEb$=<1-r=5EJdF!`jDH8Ah*H@>XSgR$_8Yp$qZHZ*A
z+oE0%<69ly<ppxhFZGx$zL>T}GS^M{bX{D6n<HCljn;{~YqlQ#TxkDM`1u)`v}b=b
z?|Z!wmbC2i5i5NzlOo!G^z#1f>yry(zSo&Oubb7pW|HU9+9=t1SED_jNWGIiT4l9j
z@BKL^7Zv?W6g_>TSpWL7-pBuUZ0q~EE&f!_oA~#U$3_32d%pSOqTT!Erc8G;(u%vS
zv8gAzI`Z7HN4u|AAOCt>Xg%N6;_JbZSB_oj)X6*dzT9W)=Y9HyUpMa)41R6tCAH(&
z{keO^WBXR#XYaKBa>03h(U!Xgj5i9W9CazZ@~892=a5U4I>PqvHFyp!mB}^P<M60b
z>vM(DzQ-Mp{Za~N?+I?^DVOk&Xfr>P5-3xV`#2`uV2XyPs;`o1#~0Om+uqFGXLfwL
zr_FQ|UzH$c2K#%rGEIKggvI5kev>Vn)5x><$<FL*@#C#NcOGp$tID^hW`kj*$&ULu
zdm~PlOemkweCn^*shmI=j_-HOAKL~^-?97Oy1$+}pLf4cFMhXtXWZ=s3C~H(jQW{B
zzPhE(ZCm`vk3Y*+Qu^KYf_<8E>tlRAInK$d|Ns7$)wA16d#`-Y(egA2@m#i0#hgDg
zXU~gu`7?8p_sayYeSGcf_LY16CwsIt|Jj-twC{c2{^UX#_dOdQ)^R`IWLT?i+q*LC
z-gnhyb+^ouvUHD|1bA8oKRS1;TkrUl_bo?cL3dPJ-pZT7uqML&kyYOg$0*5;*9V{H
ze0E3{UC9`tbNkWjUB;GPDe)Dy@+mun*2=}+*L(kDN8^&CjW-OZ9w<E`Ijz+Gbljwc
zD}#4WPg%mY^mlljowa`1M*Y6WUK8ZJ?`Qr~*>Q5~-u~1VU5|GdMap=uU%%+j*Mgsq
zemkB0P_p>y;q2Gj^I83*J>9NHsx3P**RSUepT@RRiy!^IIp=rbw8VSI?(&s|?0(wj
z&Aqo-M|pi+n&-5WsR7nra_4(4Fdv__?ee=@yPn;4e71O2<NvBz>NlJ2uin-x9{VkK
z{)r1B{8!&xQ!9LJAb*wT*>$6@GKF&->bP^`?G6{KoIHH9&9)yFINN(>M78fL&k`y(
ziz~5OR;S4?T>gtC`rPx)bIw0s{!h&I%Z2Rl^>5oa546P^32o0ib~dRfy`U;plGE;e
z3IhXQt*47)$TNR|<*#4;e=57+)2Hiywz4(%ob|CeKJj2l?9cr*3oa?F{GsQ^&B?yb
z;_>}clh4nsDvI6z=R@cD^ruJN(&j0jOVE0K`+LY{*}XTPeN3<6j{YghcjPP2^=lvM
zHt*99S(G?MV%m(UFLvg49oCxm(Lp!z3%lv}SAliR?lS2yUIHnRWwEd7Ja^rg^Sg4J
zy|d(wc?)Z!PPp)fmGhSP?GAA=<v#WOZ`FDJp9$MfF8KCCy5q5h(LdXJf9BT}2!+`G
zmAXGoXlLp3l}kJm3$h=(POr7rb&}k%EPHj`GplKBJ65hdHr;vNf<om;+g<zS9S_ld
z|63^7{%!O$!QkE%l0|t62XB0_-u`jXZNsn8l_vMpL07cb2Y>?XL8{5CJvI_OOSUtw
zdDh(HJn6g@$E9D{)prX2*!&ERDOUP?^L+Z#RxcR~$E=EY(-(P0(k~9bnVfhw;m`kf
z-GBbD8QWC9i+)*bG0)}n;nd2I(uC>nA3m!vH#XShv(7m5Oa6^#clZ{j&y-->6Ix>Z
z{FKJc6EEX#->3*!EuU0zOtq`3?AYU(Cu6_8ojCvcj>N}D!+%ZFRV~S8dnXn$+3?l(
z>kD#URr_rH_)q`HmGU2DU;Ac6smxcLetucB4^M59w*EeoWo2{PJ9no~zm?e-F8g9(
z`@QF1Kp7^^_1??sFI%=nK6+<$AXIizqKf^+6&qf@3s5_`%S7Oc|K8r;?{bnqN}bF4
zDRF%7nnyKki;ZX5#}uV}{<&t)1^@is-^X)Qzgb;-X)T*NyY1(tod+Mk-n3W$ljFaD
zMe{!$yFK-hrtNp#bj{0$*#2!bHq!I|>f7AobLqg&bF;QuZqGfx$!F6WmE*Zu3#XqK
z$(#1zrl*l+PE@^m;d1t^2X!W%{7|*Oa<RvyOPe;lezW1qmwBt+zVTCfDtSLkL+9-6
z$m)-|`%;VUtXB#1zU=<_Z+(X7G}l)*E2`Sk4YYGN%@<eK*dKmBc~$TCy?rb5zv!Os
zSQ)xMv?<v3jDgy_oIO8w&G;p2BlUjr4rl(o_A9QJ9cK9;^yOa(uT^NJ`k_5*+{457
z@D!BWX9=e+-@y6F=U5hJRH6OSJ)e`Woh^Iyi$_$--hbzzS=PTMzJ2-e{>>UYZT)xW
zrsV94c`ZC;RX(3nq*=thwDR~jPmW)|f421TyPFZYM`G`s*!O(j%oV<OY=6{F-N!t;
z`1ZGTA+^N{4>$en=@Ke`H?`(<L(Kn84=Y!28;N{hSXJO}yESI@<9(?!W4@OZrA&Fz
z($Fg&|0H^4(=P4B^WWBoUfPpW6Mx6NOfv3PQ?}s54?!mu?QjnR`}%Ls%J<)UXGDFq
zsXtL0do9c7&drLCzJ_1B6+r3wMQGnPX|;y`&nB$$iat9{`sLp?t=Tig&0g&-2@4CB
z+_7v`#C5Hz#;AE8Y@2(U*VH}#$x!<!-m0!&OM23d(<z%*gw6U>8F2H$yL}NSOCCsR
z`^K$$@p5lc)w|i9_S1LV)>$QLRX=Y<PDJ(kH>q}IM?)q&3}U@Hd!^R=_$dulQ}b_n
zn*Ay_Hxl7`5&h`hhDrCmmVSG#<uuQ1SJ8_VTRQ*N*_q`f)vujVd3W{N_l8%G{jNK9
z<@;|ppS=$^nI0+)Q|jEE=ky44E8c3ETyr0W|409YtKMEUb=#|*)7D<!{NmY1mG$qQ
z|2E37>bSJo>dL2v_mU}7EYBQ&dM=w+<=v?{B}-3wCq4dOySsnYzm?PPe7$2XT(4Ic
z{$z=EiQPuU|C47=f9-X*GU$D`P=Nl&w;HckO5M00w*F1_qjg6dpFRF`c;zyg>%mjE
z7>B&r`@MXBrOu_(pMS{(=kEE>ZTMAo-`(fyk6wBGZ_?4HCsf|;;zX*~ZBAzjKmW~V
z$;=si`)?!Prmo{lZC@WMQCHs@-t+%*iojH_1#G3e*W8pdS=LqXcCl44zts}6`R7k{
zt5vW3^PKJFdq+{d$_t9MPiq6Cp4~0J@AK!rTzOXJgtI%>R)@Of2jtIvQfXwlrFU=B
z{j=Y)Hs4g(yL+Fk3h&jREr~j_PkpkL*57yC+}8TInq`^C;nO?|DvCE%+h3J?_5C%t
z^vFMQ<@)b$9s5Os!&m+KeEzJZ|NFw_dw)EdaVymWd~xj5#c$g<A4v9{)_DKGdY{kr
z_0k`n`2WeDc1N!N+4B9nHb44*LT@)8U++;vs~E=hFDIwW29=8I;?mw^ly9FDJ<YUw
zQcium%+riF4_>h}ysG$q$6R=8r?u^a-6H%NLBXNhF7A|leDh{x`Tut+#}`{3T=YGV
zYx>XqUk{xBvbS`*)vC4m(Vkb-zUO_2-W|BFS3Lgp?5AtC<u2ml+0ppt-Rtw#vi;BY
ze*U8Ktw1yK+W#3@kN@89Sh@bYZu^X?wHN+zJl#80JYFW)ng=OHZWP7*IWGKHXL78O
z&~?cZCAGin-GB0)ntQC~K<MSjxVA@P^NaG+wi+{hxm@&GHE(^Asp$E&v*#|bO6;Gf
zavPNC&5Tx8Pg*<w*EzGdKeo+3UGX4p)%vOb<N1x`Y&^GpeDp4dF_iP&qu}$k#sTwp
zT;3ns{4CY1VV~ISV*9gk&mK4KFunKUe7>#qYQ4gx?CHlCr?2Cv+AFr#KI7}(^_x%K
zni=|0>;AS+#%I_!G#l)-cGwPTYo>0RRb~3|L)CqgnOC>{mF&8=SZD28xyt&q3wDyz
zYF}0QZ2bgkV_x1T7%W;HxqRgkwq=L+*xULBdtTmJ6_NPZb$arv@5uQlEJmy2=G(c!
zPNh%oWQ11z-NAFTSmtAwtk={ztKSta=?)fQSNL@@N#W(ig0qL0lzlt)J5ct@?d;R*
zq)qJS^(KA(`DV|B&3;W=EH+$izLl6+{Q3N%$>MEie}^7DlJ#)X|Bt@4{%zllYyJOz
zTkBQ(=v|c0!?Mf2zg`hOUZ}tMSkC#sCRUY!clX4Lo;S?d^lyUoQO!^9SMG9O@v-_6
zD@)#O=dH&ltxof*U7i2)`~461wtQT4c;8Ej=WLn2jLX=JlfTME^V(dyADmmbVv^hW
z<W*C@*LJR)|E+h%FOJ7Sk>2{dWP<mL3YEWD*dF&ZV|OCchQzgL2Q2S-95OI5iWZr6
zZUy7(x0^U)=Ny`U#7IBv*(#M6t6Fv5g=yVcl`8cvV3Et*=*yXZOr~p1?9-oIp_e(!
z!{o|ui@#Isw_h|r4NBhc3U(Xy2$klpt5o=x`Q>>5+pAmeLJnL$U6Pk>5LuD<)%NSr
z?WcPhe|t7nckX_af0a9F=JMjs=3Op5XLrtj7PYa;phv}X{n28XbcICCgV)Y%-|g+X
zcHi=(tv4M+zi~>b=k9tuTW*cmyQPP1=GVU1@reD|4WYKrm!7>hiz~Tqep({Dlb3yF
z|EJ<u`xU*XKcCJq*!_OxeZ#MF|8~DS#-@G0$MEX8?e>zvuYW1Ay%H)fiz~5QR;R84
zzKQ+R#j?XJ7v|hudbqy-(t|B}j8kP(ETu)ef-8)=F3np0UH#_Li9I&oKgqo-P&#>P
z&-Qbf#?w!3sL0cJd9Kd$y|qQ&Ga)|qRl>9R8Pra$+NHAQn)z-}LoieM^T`b*xrw`s
z-?x6r{N_Eg_wS*tPrsjjS9bZA_1skL`(-O#l;3~+entF#+@u|+k9^rJciePe<lNtx
z-!{$ZJ$n86vmK9ml@9;?)N~|vnrB&rXV9+pSNoRFIb0N$!5{na*v2(k)7{H1nma%8
z+g@3|k}oe8)R}O<dB$0iPwL1Hubhl+<zYX~t0#mS1$r+3eLr~GSKDP#75T4S+moG>
z?`I{iTAE+4yKJ9IVft%uUT{RJOWr@5(4%!aiShouV_HJn7fVN!&z|b?&SR3FiqSsK
zn(Dr0mBoExtuHK&u+{w5I1*CxyLrM6XMWo+TJE=bg%3nq=Bj*?<;*cJ{{Q;H?a4AK
zb9cPWP566M=2GX5duz6c2!41QJI8F}4_&d=A5k5=KfVQato-rKToI{C-oB~ph`hRa
z^$do6dpm2DlI<s{o@DU;HmRq!a~e<9$G667l;V$ho~{n7RR+011>}asNN#|3*C8T2
zAXiZ&V&ZY<rErer{PRV2^XLDH2K7;6_imF`gBp55uJ60&orUf9<gaA!PGo|JHn3r7
zYeJ=LK`GDnFev3gL>Rznaa06nXz&W5_u@e5?E)IHd%Zh26{87*xK=BU2St8C*8q~a
m@Opt9xHjas#gM13)IIyqb+0}JE%Fivg@dQ7pUXO@geCybXc?9O

literal 0
HcmV?d00001

diff --git a/log/cl-step-control-log.md b/log/cl-step-control-log.md
index ca800e5..fefc9aa 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. 
+
+![heavy-filt](2021-02-15_heavy-alpha-0-01.png)
+
+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
-- 
GitLab