Просмотр исходного кода

new stepper class
with OSC extension base

eLandon 6 лет назад
Родитель
Сommit
2cdc9aff08

+ 350 - 0
HTequi-firmware/lib/Atm_lien/Atm_Teenstep.cpp

@@ -0,0 +1,350 @@
+#include "Atm_Teenstep.h"
+
+/* Add optional parameters for the state machine to begin()
+ * Add extra initialization code
+ */
+
+Atm_Teenstep& Atm_Teenstep::begin(Stepper & motorRef, StepControl & stepControlRef) {
+  // clang-format off
+  const static state_t state_table[] PROGMEM = {
+    /*                             ON_ENTER     ON_LOOP          ON_EXIT  EVT_MOVE_TIMEOUT  EVT_LIMIT_HIGH   EVT_LIMIT_LOW  EVT_EMERGENCYSTOP  EVT_STOP  EVT_ONTARGET  EVT_MOVE  EVT_DISABLE  EVT_ENABLE  ELSE */
+    /*       DISABLED */       ENT_DISABLED,         -1,              -1,               -1,             -1,             -1,                -1,       -1,           -1,       -1,          -1,    ENABLED,   -1,
+    /*        ENABLED */        ENT_ENABLED,         -1,              -1,               -1,             -1,             -1,                -1,       -1,           -1,  RUNNING,    DISABLED,         -1,   -1,
+    /*        RUNNING */        ENT_RUNNING, LP_RUNNING,              -1,               -1, EMERGENCY_STOP, EMERGENCY_STOP,    EMERGENCY_STOP, STOPPING,      ENABLED,  RUNNING,          -1,         -1,   -1,
+    /*       STOPPING */       ENT_STOPPING,         -1,              -1,               -1, EMERGENCY_STOP, EMERGENCY_STOP,    EMERGENCY_STOP,       -1,           -1,  RUNNING,          -1,         -1,   -1,
+    /* EMERGENCY_STOP */ ENT_EMERGENCY_STOP,         -1,              -1,               -1,             -1,             -1,                -1,       -1,           -1,  RUNNING,          -1,    ENABLED,   -1,
+    /*    HOMING_HIGH */    ENT_HOMING_HIGH,         -1, EXT_HOMING_HIGH,               -1,        ENABLED, EMERGENCY_STOP,    EMERGENCY_STOP, STOPPING,           -1,       -1,          -1,         -1,   -1,
+    /*     HOMING_LOW */     ENT_HOMING_LOW,         -1,  EXT_HOMING_LOW,               -1, EMERGENCY_STOP,        ENABLED,    EMERGENCY_STOP, STOPPING,           -1,       -1,          -1,         -1,   -1,
+  };
+  // clang-format on
+  Machine::begin( state_table, ELSE );
+  this-> motor =   &motorRef;
+  this-> controller = &stepControlRef;
+  return *this;
+}
+
+/* Add C++ code for each internally handled event (input)
+ * The code must return 1 to trigger the event
+ */
+
+int Atm_Teenstep::event( int id ) {
+  switch ( id ) {
+    case EVT_MOVE_TIMEOUT:
+      return 0;
+    case EVT_LIMIT_HIGH:
+      return 0;
+    case EVT_LIMIT_LOW:
+      return limitState[0];
+    case EVT_EMERGENCYSTOP:
+      return limitState[1];
+    case EVT_STOP:
+      return 0;
+    case EVT_ONTARGET:
+      return _currentStep == _targetStep;
+    case EVT_MOVE:
+      return 0;
+    case EVT_DISABLE:
+      return 0;
+    case EVT_ENABLE:
+      return 0;
+  }
+  return 0;
+}
+
+/* Add C++ code for each action
+ * This generates the 'output' for the state machine
+ *
+ * Available connectors:
+ *   push( connectors, ON_CHANGE, 0, <v>, <up> );
+ *   push( connectors, ON_CHANGEPOSITION, 0, <v>, <up> );
+ *   push( connectors, ON_LIMITHIGH, 0, <v>, <up> );
+ *   push( connectors, ON_LIMITLOW, 0, <v>, <up> );
+ */
+
+void Atm_Teenstep::action( int id ) {
+  switch ( id ) {
+    long int tempStep ;
+    case ENT_DISABLED:
+      enabled = _enableReversed ? HIGH : LOW;
+      digitalWrite(_enablePin, enabled);
+      sendOSC();
+      return;
+    case ENT_ENABLED:
+      enabled = _enableReversed ? LOW : HIGH ;
+      digitalWrite(_enablePin, enabled);
+      sendOSC();
+      return;
+    case ENT_RUNNING:
+      return;
+    case LP_RUNNING:
+      tempStep = motor->getPosition();
+      //connectors[ON_ONCHANGEPOSITION].push(_currentStep);
+      // if (tempStep != _currentStep){push( connectors, ON_ONCHANGEPOSITION, 0, _currentStep, 0 );} ;
+      _currentStep =  tempStep;
+      updateLimitSwitch();
+      sendOSC();
+      return;
+    case ENT_STOPPING:
+      sendOSC();
+      return;
+    case ENT_EMERGENCY_STOP:
+      controller->emergencyStop();
+      sendOSC();
+      return;
+    case ENT_HOMING_HIGH:
+      _limitType ? move(2147483647) : trigger(EVT_ENABLE) ;
+      sendOSC();
+      return;
+    case EXT_HOMING_HIGH:
+      _maxStep = motor->getPosition();
+      return;
+    case ENT_HOMING_LOW:
+      _limitType ? move(-2147483647) : trigger(EVT_STOP) ;
+      sendOSC();
+      return;
+    case EXT_HOMING_LOW:
+      motor->setPosition(0);
+      return;
+  }
+}
+
+/* Optionally override the default trigger() method
+ * Control how your machine processes triggers
+ */
+
+Atm_Teenstep& Atm_Teenstep::trigger( int event ) {
+  Machine::trigger( event );
+  return *this;
+}
+
+/* Optionally override the default state() method
+ * Control what the machine returns when another process requests its state
+ */
+
+int Atm_Teenstep::state( void ) {
+  return Machine::state();
+}
+
+/* CUSTOM METHODS
+********************************************************************************************************
+*/
+
+// Atm_TeensyStep& Atm_TeensyStep::enable( bool enable ){
+//
+//   return *this;
+// }
+
+/////////   ENABLE/DISABLE    ////////
+
+Atm_Teenstep& Atm_Teenstep::setEnablePin( int enablePin ){
+  _enablePin = enablePin ;
+  pinMode(_enablePin, OUTPUT);
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::enableReversed( bool reverse ){
+  _enableReversed = reverse ;
+  return *this;
+}
+
+/////////   LIMITS    ////////
+
+Atm_Teenstep& Atm_Teenstep::setLimitPins( int limitPinLow){
+  _limitPin[0] = limitPinLow;
+  pinMode(_limitPin[0], INPUT);
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::setLimitPins( int limitPinLow, int limitPinHigh){
+ _limitPin[0] = limitPinLow;
+ _limitPin[1] = limitPinHigh;
+ pinMode(_limitPin[0], INPUT);
+ pinMode(_limitPin[1], INPUT);
+ return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::setLimitType( int limitType){
+ _limitType = limitType;
+ return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::limitReversed( bool reversed){
+ _limitReversed = reversed;
+ return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::limitThresholds( int limitThreshold0,
+       int limitThreshold1,  int limitThreshold2, int limitThreshold3){
+ _limitThresholds[0] = limitThreshold0;
+ _limitThresholds[1] = limitThreshold1;
+ _limitThresholds[2] = limitThreshold2;
+ _limitThresholds[3] = limitThreshold3;
+ return *this;
+}
+
+void Atm_Teenstep::updateLimitSwitch(){
+  switch (_limitType) { // limitType!=0 means there is limit to check
+    case NONE:
+      return ;
+    case DIGITAL_1:
+      limitState[0] = digitalRead(_limitPin[0]);
+      limitState[0] = _limitReversed ? !limitState[0] : limitState[0];
+      return;
+    case DIGITAL_2:
+    limitState[0] = digitalRead(_limitPin[0]);
+    limitState[1] = digitalRead(_limitPin[1]);
+    limitState[0] = _limitReversed ? !limitState[0] : limitState[0];
+    limitState[1] = _limitReversed ? !limitState[1] : limitState[1];
+      return;
+    case ANALOG_1:
+    int read = analogRead(_limitPin[0]) ;
+    limitState[0] = _limitThresholds[0] < read && read < _limitThresholds[1] ;
+    limitState[1] = _limitThresholds[2] < read && read < _limitThresholds[3] ;
+      return;
+  }
+
+}
+
+
+Atm_Teenstep& Atm_Teenstep::onOSC( void ){
+//  _enableReversed = reverse ;
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::sendOSC( void ){
+//  _enableReversed = reverse ;
+  return *this;
+}
+
+/* Nothing customizable below this line
+ ************************************************************************************************
+*/
+
+/* Public event methods
+ *
+ */
+
+Atm_Teenstep& Atm_Teenstep::move_timeout() {
+  trigger( EVT_MOVE_TIMEOUT );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::limit_high() {
+  trigger( EVT_LIMIT_HIGH );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::limit_low() {
+  trigger( EVT_LIMIT_LOW );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::emergencystop() {
+  trigger( EVT_EMERGENCYSTOP );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::stop() {
+  trigger( EVT_STOP );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::ontarget() {
+  trigger( EVT_ONTARGET );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::move(long int stepRel) {
+  _targetStep   = _currentStep + stepRel;
+  Serial.println(_targetStep);
+  motor->setTargetAbs(_targetStep);
+  controller->moveAsync(*motor);
+  enable();
+  trigger( EVT_MOVE );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::moveTo(long int stepAbs) {
+  _targetStep   = stepAbs;
+  motor->setTargetAbs(_targetStep);
+  controller->moveAsync(*motor);
+  enable();
+  trigger( EVT_MOVE );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::disable() {
+  trigger( EVT_DISABLE );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::enable() {
+  trigger( EVT_ENABLE );
+  return *this;
+}
+
+/*
+ * onChange() push connector variants ( slots 1, autostore 0, broadcast 0 )
+ */
+
+Atm_Teenstep& Atm_Teenstep::onChange( Machine& machine, int event ) {
+  onPush( connectors, ON_CHANGE, 0, 1, 1, machine, event );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::onChange( atm_cb_push_t callback, int idx ) {
+  onPush( connectors, ON_CHANGE, 0, 1, 1, callback, idx );
+  return *this;
+}
+
+/*
+ * onChangeposition() push connector variants ( slots 1, autostore 0, broadcast 0 )
+ */
+
+Atm_Teenstep& Atm_Teenstep::onChangeposition( Machine& machine, int event ) {
+  onPush( connectors, ON_CHANGEPOSITION, 0, 1, 1, machine, event );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::onChangeposition( atm_cb_push_t callback, int idx ) {
+  onPush( connectors, ON_CHANGEPOSITION, 0, 1, 1, callback, idx );
+  return *this;
+}
+
+/*
+ * onLimithigh() push connector variants ( slots 1, autostore 0, broadcast 0 )
+ */
+
+Atm_Teenstep& Atm_Teenstep::onLimithigh( Machine& machine, int event ) {
+  onPush( connectors, ON_LIMITHIGH, 0, 1, 1, machine, event );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::onLimithigh( atm_cb_push_t callback, int idx ) {
+  onPush( connectors, ON_LIMITHIGH, 0, 1, 1, callback, idx );
+  return *this;
+}
+
+/*
+ * onLimitlow() push connector variants ( slots 1, autostore 0, broadcast 0 )
+ */
+
+Atm_Teenstep& Atm_Teenstep::onLimitlow( Machine& machine, int event ) {
+  onPush( connectors, ON_LIMITLOW, 0, 1, 1, machine, event );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::onLimitlow( atm_cb_push_t callback, int idx ) {
+  onPush( connectors, ON_LIMITLOW, 0, 1, 1, callback, idx );
+  return *this;
+}
+
+/* State trace method
+ * Sets the symbol table and the default logging method for serial monitoring
+ */
+
+Atm_Teenstep& Atm_Teenstep::trace( Stream & stream ) {
+  Machine::setTrace( &stream, atm_serial_debug::trace,
+    "TEENSTEP\0EVT_MOVE_TIMEOUT\0EVT_LIMIT_HIGH\0EVT_LIMIT_LOW\0EVT_EMERGENCYSTOP\0EVT_STOP\0EVT_ONTARGET\0EVT_MOVE\0EVT_DISABLE\0EVT_ENABLE\0ELSE\0DISABLED\0ENABLED\0RUNNING\0STOPPING\0EMERGENCY_STOP\0HOMING_HIGH\0HOMING_LOW" );
+  return *this;
+}

+ 155 - 0
HTequi-firmware/lib/Atm_lien/Atm_Teenstep.h

@@ -0,0 +1,155 @@
+#pragma once
+
+#include <Automaton.h>
+#include <TeensyStep.h>
+
+class Atm_Teenstep: public Machine {
+
+ public:
+  enum { DISABLED, ENABLED, RUNNING, STOPPING, EMERGENCY_STOP, HOMING_HIGH, HOMING_LOW }; // STATES
+  enum { EVT_MOVE_TIMEOUT, EVT_LIMIT_HIGH, EVT_LIMIT_LOW, EVT_EMERGENCYSTOP, EVT_STOP, EVT_ONTARGET, EVT_MOVE, EVT_DISABLE, EVT_ENABLE, ELSE }; // EVENTS
+  Atm_Teenstep( void ) : Machine() {};
+  Atm_Teenstep& begin( Stepper & motorRef, StepControl & stepControlRef );
+  Atm_Teenstep& trace( Stream & stream );
+  Atm_Teenstep& trigger( int event );
+  int state( void );
+  Atm_Teenstep& onChange( Machine& machine, int event = 0 );
+  Atm_Teenstep& onChange( atm_cb_push_t callback, int idx = 0 );
+  Atm_Teenstep& onChangeposition( Machine& machine, int event = 0 );
+  Atm_Teenstep& onChangeposition( atm_cb_push_t callback, int idx = 0 );
+  Atm_Teenstep& onLimithigh( Machine& machine, int event = 0 );
+  Atm_Teenstep& onLimithigh( atm_cb_push_t callback, int idx = 0 );
+  Atm_Teenstep& onLimitlow( Machine& machine, int event = 0 );
+  Atm_Teenstep& onLimitlow( atm_cb_push_t callback, int idx = 0 );
+  Atm_Teenstep& move_timeout( void );
+  Atm_Teenstep& limit_high( void );
+  Atm_Teenstep& limit_low( void );
+  Atm_Teenstep& emergencystop( void );
+  Atm_Teenstep& stop( void );
+  Atm_Teenstep& ontarget( void );
+  Atm_Teenstep& move( void );
+  Atm_Teenstep& disable( void );
+  Atm_Teenstep& enable( void );
+
+
+  Atm_Teenstep& move( long int stepRel );
+  Atm_Teenstep& moveTo( long int stepAbs );
+  Atm_Teenstep& homing( int direction );
+
+  Atm_Teenstep& setLimitType( int limitType = 0);
+  Atm_Teenstep& setLimitPins( int limitPinLow);
+  Atm_Teenstep& setLimitPins( int limitPinLow, int limitPinHigh);
+  Atm_Teenstep& limitReversed( bool reversed );
+  Atm_Teenstep& limitThresholds( int limitThreshold0, int limitThreshold1,
+                                  int limitThreshold2, int limitThreshold3);
+  bool limitState[2] ; // up to two limits, at least one for homing
+
+  virtual Atm_Teenstep& onOSC( void );
+  virtual Atm_Teenstep& sendOSC( void );
+
+  Stepper * motor;
+  StepControl * controller;
+
+  Atm_Teenstep& setEnablePin( int enablePin );
+  Atm_Teenstep& enableReversed( bool reverse );
+  bool enabled ;
+
+
+
+ private:
+  enum { ENT_DISABLED, ENT_ENABLED, ENT_RUNNING, LP_RUNNING, ENT_STOPPING, ENT_EMERGENCY_STOP, ENT_HOMING_HIGH, EXT_HOMING_HIGH, ENT_HOMING_LOW, EXT_HOMING_LOW }; // ACTIONS
+  enum { ON_CHANGE, ON_CHANGEPOSITION, ON_LIMITHIGH, ON_LIMITLOW, CONN_MAX }; // CONNECTORS
+  atm_connector connectors[CONN_MAX];
+  int event( int id );
+  void action( int id );
+
+  atm_timer_millis idle_timer ;
+  int IDLE_TIMEOUT_DURATION = 500000 ;
+  atm_timer_millis moving_timer ;
+  int MOVING_TIMEOUT_DURATION = 12000000 ;
+  atm_counter homing_counterout ;
+
+  long int _currentStep = 0;
+  long int _targetStep = 0;
+  long int _maxStep ;
+
+  int _enablePin = -1;
+  bool _enableReversed = 0 ;
+
+  int _limitPin[2];
+  enum { NONE, DIGITAL_1, DIGITAL_2, ANALOG_1 };
+  int _limitType; //type of limit switch, from list over
+  bool _limitReversed ; //invert logic of limit switches
+  int _limitThresholds[4] ; //analog value  range for two analog limits
+  void updateLimitSwitch();
+};
+
+/*
+Automaton::ATML::begin - Automaton Markup Language
+
+<?xml version="1.0" encoding="UTF-8"?>
+<machines>
+  <machine name="Atm_Teenstep">
+    <states>
+      <DISABLED index="0" on_enter="ENT_DISABLED">
+        <EVT_ENABLE>ENABLED</EVT_ENABLE>
+      </DISABLED>
+      <ENABLED index="1" on_enter="ENT_ENABLED">
+        <EVT_MOVE>RUNNING</EVT_MOVE>
+        <EVT_DISABLE>DISABLED</EVT_DISABLE>
+      </ENABLED>
+      <RUNNING index="2" on_enter="ENT_RUNNING" on_loop="LP_RUNNING">
+        <EVT_LIMIT_HIGH>EMERGENCY_STOP</EVT_LIMIT_HIGH>
+        <EVT_LIMIT_LOW>EMERGENCY_STOP</EVT_LIMIT_LOW>
+        <EVT_EMERGENCYSTOP>EMERGENCY_STOP</EVT_EMERGENCYSTOP>
+        <EVT_STOP>STOPPING</EVT_STOP>
+        <EVT_ONTARGET>ENABLED</EVT_ONTARGET>
+        <EVT_MOVE>RUNNING</EVT_MOVE>
+      </RUNNING>
+      <STOPPING index="3" on_enter="ENT_STOPPING">
+        <EVT_LIMIT_HIGH>EMERGENCY_STOP</EVT_LIMIT_HIGH>
+        <EVT_LIMIT_LOW>EMERGENCY_STOP</EVT_LIMIT_LOW>
+        <EVT_EMERGENCYSTOP>EMERGENCY_STOP</EVT_EMERGENCYSTOP>
+        <EVT_MOVE>RUNNING</EVT_MOVE>
+      </STOPPING>
+      <EMERGENCY_STOP index="4" on_enter="ENT_EMERGENCY_STOP">
+        <EVT_MOVE>RUNNING</EVT_MOVE>
+        <EVT_ENABLE>ENABLED</EVT_ENABLE>
+      </EMERGENCY_STOP>
+      <HOMING_HIGH index="5" on_enter="ENT_HOMING_HIGH" on_exit="EXT_HOMING_HIGH">
+        <EVT_LIMIT_HIGH>ENABLED</EVT_LIMIT_HIGH>
+        <EVT_LIMIT_LOW>EMERGENCY_STOP</EVT_LIMIT_LOW>
+        <EVT_EMERGENCYSTOP>EMERGENCY_STOP</EVT_EMERGENCYSTOP>
+        <EVT_STOP>STOPPING</EVT_STOP>
+      </HOMING_HIGH>
+      <HOMING_LOW index="6" on_enter="ENT_HOMING_LOW" on_exit="EXT_HOMING_LOW">
+        <EVT_LIMIT_HIGH>EMERGENCY_STOP</EVT_LIMIT_HIGH>
+        <EVT_LIMIT_LOW>ENABLED</EVT_LIMIT_LOW>
+        <EVT_EMERGENCYSTOP>EMERGENCY_STOP</EVT_EMERGENCYSTOP>
+        <EVT_STOP>STOPPING</EVT_STOP>
+      </HOMING_LOW>
+    </states>
+    <events>
+      <EVT_MOVE_TIMEOUT index="0" access="MIXED"/>
+      <EVT_LIMIT_HIGH index="1" access="MIXED"/>
+      <EVT_LIMIT_LOW index="2" access="MIXED"/>
+      <EVT_EMERGENCYSTOP index="3" access="MIXED"/>
+      <EVT_STOP index="4" access="MIXED"/>
+      <EVT_ONTARGET index="5" access="MIXED"/>
+      <EVT_MOVE index="6" access="MIXED"/>
+      <EVT_DISABLE index="7" access="MIXED"/>
+      <EVT_ENABLE index="8" access="MIXED"/>
+    </events>
+    <connectors>
+      <CHANGE autostore="0" broadcast="0" dir="PUSH" slots="1"/>
+      <CHANGEPOSITION autostore="0" broadcast="0" dir="PUSH" slots="1"/>
+      <LIMITHIGH autostore="0" broadcast="0" dir="PUSH" slots="1"/>
+      <LIMITLOW autostore="0" broadcast="0" dir="PUSH" slots="1"/>
+    </connectors>
+    <methods>
+    </methods>
+  </machine>
+</machines>
+
+Automaton::ATML::end
+*/

+ 30 - 0
HTequi-firmware/lib/Atm_lien/Atm_Teenstep_OSC.cpp

@@ -0,0 +1,30 @@
+#include "Atm_Teenstep_OSC.h"
+
+Atm_Teenstep_OSC& Atm_Teenstep_OSC::begin(Atm_Teenstep& stepperMachineRef, EthernetUDP& udpRef, OSCBundle& bndl, const char* address) {
+  this-> stepperMachine = &stepperMachineRef;
+  _adress = address;
+  this->_udpRef =   &udpRef;
+  this->_bndl = &bndl ;
+  return *this;
+}
+
+
+
+Atm_Teenstep_OSC& Atm_Teenstep_OSC::onOSC(OSCMessage& msg ){
+  Serial.println("OSC");
+  int patternOffset = msg.match(_adress) ;
+  if(patternOffset){
+    if(msg.fullMatch("/speedAcc", patternOffset)){
+      stepperMachine->motor->setMaxSpeed(msg.getInt(0));
+      stepperMachine->motor->setAcceleration(msg.getInt(1));
+    }
+    if(msg.fullMatch("/enable", patternOffset)){msg.getInt(0) ? stepperMachine->trigger(stepperMachine->EVT_ENABLE) : stepperMachine->trigger(stepperMachine->EVT_DISABLE);}
+    //if(msg.fullMatch("/home", patternOffset)){home(msg.getInt(0));}
+    if(msg.fullMatch("/move", patternOffset)){stepperMachine->move(msg.getInt(0));Serial.println(msg.getInt(0));}
+    if(msg.fullMatch("/moveTo", patternOffset)){stepperMachine->moveTo(msg.getInt(0));}
+    if(msg.fullMatch("/stop", patternOffset)){stepperMachine->stop();}
+    if(msg.fullMatch("/emergencyStop", patternOffset)){stepperMachine->emergencystop();}
+
+    return *this;
+  }
+}

+ 26 - 0
HTequi-firmware/lib/Atm_lien/Atm_Teenstep_OSC.h

@@ -0,0 +1,26 @@
+#pragma once
+
+#include "Atm_Teenstep.h"
+
+#include <EthernetUdp.h>
+#include <OSCMessage.h>
+#include <OSCBundle.h>
+
+class Atm_Teenstep_OSC {
+
+  public:
+    Atm_Teenstep_OSC( void ){};
+    Atm_Teenstep_OSC& begin(Atm_Teenstep & stepperMachineRef, EthernetUDP& udpRef, OSCBundle& bndl, const char* address);
+    Atm_Teenstep* stepperMachine ;
+    const char* _adress = "/OSC";
+    EthernetUDP* _udpRef ;
+    Atm_Teenstep_OSC& onOSC(OSCMessage& msg );
+    Atm_Teenstep_OSC& sendOSC( void );
+
+  private:
+   // AccelStepper _motor;
+   // Stepper *_motor;       // STEP pin: 2, DIR pin: 3
+   // StepControl _controller;
+   OSCBundle* _bndl;
+
+};

+ 2 - 2
HTequi-firmware/lib/Atm_lien/Atm_Tstepper.cpp

@@ -35,9 +35,9 @@ int Atm_Tstepper::event( int id ) {
     case EVT_HOMING_COUNTER:
       return 0;
     case EVT_IDLE_TIMEOUT:
-      return idle_timer.expired(this);
+      return 0; //idle_timer.expired(this);
     case EVT_MOVE_TIMEOUT:
-      return moving_timer.expired(this);
+      return 0; //moving_timer.expired(this);
     case EVT_LIMIT_LOW:
       return limitState[0];//limitState[0];
     case EVT_LIMIT_HIGH:

+ 53 - 50
HTequi-firmware/src/blobcnc_feeder/main.cpp

@@ -3,30 +3,30 @@
 #include <Automaton.h>
 //#include "Atm_lien/Atm_stepper.h"
 #include "Atm_Tstepper.h"
-
+#include "Atm_TeensyStep.h"
 #include <SPI.h>
 #include <Ethernet.h>
 #include <EthernetUdp.h>
 #include <TeensyMAC.h>
 #include <OSCMessage.h>
 
-// ////////////////    Ethernet  /////////////////////////////
-// // Enter a MAC address and IP address for your controller below.
-// // The IP address will be dependent on your local network:
-// byte mac[] = {0x00, 0xAA, 0xBB, 0xCC, 0xDE, 0x02};
-// IPAddress ip(192, 168, 1, 204);    //local IP of Arduino/Teensy
-// //unsigned int localPort = 8888;      // local port to listen on (not needed for multicast)
-// IPAddress ipMulti(239, 200, 200, 200); // ipMidi Multicast address
-// unsigned int portMulti = 9977;   // ipMidi Mutlicast port 1
-// // buffers for receiving and sending data
-// byte packetBuffer[UDP_TX_PACKET_MAX_SIZE];       // buffer to hold incoming packet
-// byte sendBuffer1[] = {0x90, 0x14, 0x22};        // MIDI Note On to Multicast address
-// byte sendBuffer2[] = {0x80, 0x14, 0x00};        // MIDI Note Off to Multicast address
-// // An EthernetUDP instance to let us send and receive packets over UDP
-// EthernetUDP Udp;
-//
-// ///////////////////       OSC         ////////////////////////
-// OSCBundle bndl;
+////////////////    Ethernet  /////////////////////////////
+// Enter a MAC address and IP address for your controller below.
+// The IP address will be dependent on your local network:
+byte mac[] = {0x00, 0xAA, 0xBB, 0xCC, 0xDE, 0x02};
+IPAddress ip(192, 168, 1, 204);    //local IP of Arduino/Teensy
+//unsigned int localPort = 8888;      // local port to listen on (not needed for multicast)
+IPAddress ipMulti(239, 200, 200, 200); // ipMidi Multicast address
+unsigned int portMulti = 9977;   // ipMidi Mutlicast port 1
+// buffers for receiving and sending data
+byte packetBuffer[UDP_TX_PACKET_MAX_SIZE];       // buffer to hold incoming packet
+byte sendBuffer1[] = {0x90, 0x14, 0x22};        // MIDI Note On to Multicast address
+byte sendBuffer2[] = {0x80, 0x14, 0x00};        // MIDI Note Off to Multicast address
+// An EthernetUDP instance to let us send and receive packets over UDP
+EthernetUDP Udp;
+
+///////////////////       OSC         ////////////////////////
+OSCBundle bndl;
 
 /////////////////// STEPPER machines  ////////////////////////
 /*move are always meant in full steps on the motor output (after reduction)
@@ -37,52 +37,46 @@ const int BARREL_DISTANCE = 10 ; //in full steps
 const int BARREL_REDUCTION_RATIO = 26.85;
 const int BARREL_MICROSTEP = 32;
 
-const int BARREL_THRESHOLD = 1000 ; //for sensor to trig
+static uint16_t BARREL_THRESHOLD[] = {5} ; //for sensor to trig
+const int BARREL_INIBSENSOR = 5000;
 
-const int PILL_SPEED = 100 ;
+const int PILL_SPEED = 10 ;
 const int PILL_ACC = 1000 ;
 const int PILL_DISTANCE = 200 ; //in full steps
 const int PILL_MICROSTEP = 32;
 
 
 
-Atm_Tstepper barrel_step;
+Atm_TeensyStep barrel_step;
 Stepper barrel_stepper(3, 2);
 StepControl barrel_controller ;
 
-Atm_analog barrel_sensor;
+Atm_comparator barrel_sensor;
 
-Atm_Tstepper pill_step;
+Atm_TeensyStep pill_step;
 Stepper pill_stepper(6, 5);
 StepControl pill_controller ;
 
-Atm_analog pill_sensor ;
+Atm_comparator pill_sensor ;
 
 
 void barrel_homing(){
   barrel_step.move(BARREL_DISTANCE*BARREL_MICROSTEP*BARREL_REDUCTION_RATIO);
-  Serial.println(barrel_sensor.state());
-  // while(barrel_sensor.state()>900 && (barrel_step.state() == barrel_step.RUNNING)){ // &&
-  //
-  //   //barrel_step.cycle();
-  //   //Serial.println(barrel_sensor.state());
-  // }
-  // barrel_step.stop();
-  // barrel_stepper.setPosition(0);
+  automaton.delay(BARREL_INIBSENSOR); //let the current position go
   bool foundHome = false ;
   while(barrel_step.state() != barrel_step.STOPPING){
     // automaton.run();
     barrel_step.cycle();
-    if(barrel_sensor.state()<BARREL_THRESHOLD){
-      barrel_step.stop();
+    if(barrel_sensor.state()<BARREL_THRESHOLD[0]){
+      barrel_step.emergencyStop();
       barrel_stepper.setPosition(0);
       foundHome = true ;
       break ;
     }
   }
   digitalWrite( 13, LOW );
-  if (!foundHome){Serial.println("HOMING FAILED - CHECK SENSOR");}
-  else{Serial.println("homing done");}
+  if (!foundHome){Serial.println("homing 0");}
+  else{Serial.println("homing 1");}
 
 }
 
@@ -98,11 +92,16 @@ void pill_move(int stepRel){
 }
 
 void pill_next(){
+  pill_move(200 * PILL_MICROSTEP);
 
   //make one turn, if nothing was seen by sensor try again up to 5 times
-
-  // for (int retries = 0 ; retries < 5; retries
-  // pill_step.move(200*PILL_MICROSTEP);
+  bool foundPill = false ;
+  while(pill_step.state() != barrel_step.STOPPING){
+    automaton.run();
+    if(pill_sensor.state()<BARREL_THRESHOLD[0]){foundPill = true ;}
+  }
+  if (!foundPill){Serial.println("pill 0");}
+  else{Serial.println("pill 1");}
 
 }
 
@@ -129,12 +128,12 @@ void cmd_callback( int idx, int v, int up ) {
       barrel_move(atoi( cmd.arg( 1 ) ));
       return;
     case CMD_BARREL_HOME:
-    barrel_step.homing(0);
-      // barrel_homing();
+    // barrel_step.homing(0);
+      barrel_homing();
       return;
     case CMD_BARREL_NEXT:
       barrel_move(BARREL_DISTANCE);
-      if((!barrel_sensor.state())<BARREL_THRESHOLD){barrel_homing();}
+      if((!barrel_sensor.state())<BARREL_THRESHOLD[0]){barrel_homing();}
       return;
     case CMD_PILL:
       pill_next();
@@ -159,7 +158,7 @@ void setup() {
 
   //Start serial
   Serial.begin(115200); // higher Baud rate for faster refresh, CHANGE IN SERIAL MONITOR
-  Serial1.begin(115200);
+  Serial1.begin(9600);
   delay(2000);
   Serial.println("Started");
   cmd.begin( Serial, cmd_buffer, sizeof( cmd_buffer ) )
@@ -176,20 +175,23 @@ void setup() {
   // pinMode(4, OUTPUT);
   // pinMode(4, LOW);
   barrel_step.trace( Serial );
-  barrel_step.begin(barrel_stepper, barrel_controller)
-        .setEnablePin(4).enableReversed(1).enable()
-        .setLimitType(3).setLimitPins(A3).limitThresholds(800, 1000, 0, 100).homing(1);
+  barrel_step.begin(barrel_stepper, barrel_controller, Udp, bndl, "/Y_top")
+        .setEnablePin(4).enableReversed(1);
+        //.setLimitType(3).setLimitPins(A3).limitThresholds(800, 1000, 0, 100).homing(1);
   barrel_stepper.setMaxSpeed(BARREL_SPEED);
   barrel_stepper.setAcceleration(BARREL_ACC);
   barrel_stepper.setInverseRotation(true);
-  barrel_sensor.begin(A3);
+  barrel_sensor.begin(A3, 50).threshold(BARREL_THRESHOLD, 1)
+              .onChange( []( int idx, int v, int up ){Serial.println(up);} )
+              .onChange( true, []( int idx, int v, int up ){Serial.println(up);} )
+              .onChange( false, []( int idx, int v, int up ){Serial.println(up);} );
 
   pill_step.trace( Serial );
-  pill_step.begin(pill_stepper, pill_controller)
-        .setEnablePin(7).enableReversed(1).enable();
+  pill_step.begin(pill_stepper, pill_controller,  Udp, bndl, "/Y_top")
+        .setEnablePin(7).enableReversed(1);
   pill_stepper.setMaxSpeed(PILL_SPEED);
   pill_stepper.setAcceleration(PILL_ACC);
-  pill_sensor.begin(A1);
+  pill_sensor.begin(A1, 50);
   //stepper.onOnchange(Machine &machine, optional int event = 0)
   //stepper.cycle(1000);
   //barrel_step.move(10000);
@@ -202,5 +204,6 @@ void setup() {
 
 void loop() {
   automaton.run();
+  //Serial.println(barrel_sensor.state());
 
 }

+ 6 - 3
HTequi-firmware/src/blobcnc_top/main.cpp

@@ -5,8 +5,11 @@
 #include <Automaton.h>
 // #include "Atm_lien/Atm_stepper.h"
 #include "Atm_TeensyStep.h"
-#include "Atm_out.h"
 #include "Atm_Tstepper_OSC.h"
+#include "Atm_Teenstep.h"
+#include "Atm_Teenstep_OSC.h"
+#include "Atm_out.h"
+
 //osc
 
 
@@ -41,8 +44,8 @@ const int HIGH_ACC = 800 ;
 const int LOW_SPEED = 100 ;
 const int LOW_ACC = 1000 ;
 
-Atm_Tstepper_OSC X_top_OSC;
-Atm_Tstepper X_top_step;
+Atm_Teenstep_OSC X_top_OSC;
+Atm_Teenstep X_top_step;
 // Atm_TeensyStep X_top_step;
 Stepper X_top_stepper(20 , 19);
 StepControl X_top_controller ;

+ 4 - 4
blob-CN/main.pd

@@ -1,4 +1,4 @@
-#N canvas 57 325 1743 541 12;
+#N canvas 150 402 1743 541 12;
 #X msg 73 21 disconnect;
 #X obj 72 426 tgl 15 0 empty empty connected 20 7 0 8 -24198 -241291
 -1 1 1;
@@ -34,7 +34,7 @@
 #X text 1069 60 total bytes received:;
 #X obj 1007 427 spigot;
 #X obj 1046 407 tgl 15 0 empty empty enable_print: -77 8 0 10 -4034
--1 -1 1 1;
+-1 -1 0 1;
 #X obj 1007 452 print received;
 #X obj 1235 33 route received total from multicast;
 #X msg 953 52 port 9998;
@@ -55,9 +55,9 @@
 #X msg 733 282 /Y_top/emergencyStop;
 #X obj 1159 335 list prepend set;
 #X obj 1159 360 list trim;
-#X msg 1159 385 /X_top/move -10000;
+#X msg 1159 385 /X_top/move 1000;
 #X msg 563 279 /X_top/home 0;
-#X msg 530 194 /X_top/move -10000;
+#X msg 530 194 sendtyped /X_top/move i 1000;
 #X connect 0 0 35 0;
 #X connect 2 0 35 0;
 #X connect 3 0 35 0;