Przeglądaj źródła

OSC feedback from steppers
top and feeders v1

eLandon 6 lat temu
rodzic
commit
49095afd27

+ 19 - 6
HTequi-firmware/lib/Atm_lien/Atm_Teenstep.cpp

@@ -14,7 +14,7 @@ Atm_Teenstep& Atm_Teenstep::begin(Stepper & motorRef, StepControl & stepControlR
     /*       STOPPING */       ENT_STOPPING,         -1,              -1,             -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,       -1,           -1,  RUNNING,          -1,    ENABLED,   -1,
     /*    HOMING_HIGH */    ENT_HOMING_HIGH,         -1, EXT_HOMING_HIGH,             -1,              -1,               -1,        ENABLED,             -1,    EMERGENCY_STOP, STOPPING,           -1,       -1,          -1,         -1,   -1,
-    /*     HOMING_LOW */     ENT_HOMING_LOW,         -1,  EXT_HOMING_LOW,             -1,              -1,               -1,             -1,        ENABLED,    EMERGENCY_STOP, STOPPING,           -1,       -1,          -1,         -1,   -1,
+    /*     HOMING_LOW */     ENT_HOMING_LOW,         -1,  EXT_HOMING_LOW,             -1,              -1,               -1,            -1,        ENABLED,    EMERGENCY_STOP, STOPPING,           -1,       -1,          -1,         -1,   -1,
   };
   // clang-format on
   Machine::begin( state_table, ELSE );
@@ -70,34 +70,43 @@ void Atm_Teenstep::action( int id ) {
   switch ( id ) {
     long int tempStep ;
     case ENT_DISABLED:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
       enabled = _enableReversed ? HIGH : LOW;
       digitalWrite(_enablePin, enabled);
       sendOSC();
       return;
     case ENT_ENABLED:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
       enabled = _enableReversed ? LOW : HIGH ;
       digitalWrite(_enablePin, enabled);
       sendOSC();
       return;
     case ENT_RUNNING:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
+      push(connectors, ON_CHANGE, 0,  2, 0);
       return;
     case LP_RUNNING:
       tempStep = motor->getPosition();
-      //connectors[ON_ONCHANGEPOSITION].push(_currentStep);
-      // if (tempStep != _currentStep){push( connectors, ON_ONCHANGEPOSITION, 0, _currentStep, 0 );} ;
-      _currentStep =  tempStep;
+      if (tempStep != _currentStep){
+        _currentStep =  tempStep;
+        push(connectors, ON_CHANGEPOSITION, 0,  _currentStep, 0);
+      }
+
       //updateLimitSwitch();
       sendOSC();
       return;
     case ENT_STOPPING:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
       sendOSC();
       return;
     case ENT_EMERGENCY_STOP:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
       controller->emergencyStop();
       trigger(EVT_ENABLE);
       sendOSC();
       return;
     case ENT_HOMING_HIGH:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
       if(_limitType) {
         motor->setTargetRel(2147483647);
         controller->moveAsync(*motor);
@@ -107,18 +116,21 @@ void Atm_Teenstep::action( int id ) {
     case EXT_HOMING_HIGH:
       controller->emergencyStop();
       if(last_trigger == EVT_LIMIT_HIGH){
+        push(connectors, ON_LIMITHIGH, 0,  1, 0);
         _maxStep = motor->getPosition();
         Serial.print("Stepper maxPos ");
         Serial.println(motor->getPosition());
         trigger(EVT_ENABLE);
       }
       else{
+        push(connectors, ON_LIMITLOW, 0,  1, 0);
         Serial.println("homing failed ");
         trigger(EVT_EMERGENCYSTOP);
       }
 
       return;
     case ENT_HOMING_LOW:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
       if(_limitType) {
         motor->setTargetRel(-2147483647);
         controller->moveAsync(*motor);
@@ -128,12 +140,14 @@ void Atm_Teenstep::action( int id ) {
     case EXT_HOMING_LOW:
       controller->emergencyStop();
       if(last_trigger == EVT_LIMIT_LOW){
+        push(connectors, ON_LIMITLOW, 0,  1, 0);
         motor->setPosition(0);
         Serial.print("Stepper homed ");
         Serial.println(motor->getPosition());
         trigger(EVT_ENABLE);
       }
       else{
+        push(connectors, ON_LIMITHIGH, 0,  1, 0);
         Serial.println("homing failed ");
         trigger(EVT_EMERGENCYSTOP);
       }
@@ -300,7 +314,7 @@ Atm_Teenstep& Atm_Teenstep::ontarget() {
 
 Atm_Teenstep& Atm_Teenstep::move(long int stepRel) {
   _targetStep   = _currentStep + stepRel;
-  Serial.println(_targetStep);
+  //Serial.println(_targetStep);
   motor->setTargetAbs(_targetStep);
   controller->moveAsync(*motor);
   enable();
@@ -324,7 +338,6 @@ Atm_Teenstep& Atm_Teenstep::disable() {
 
 Atm_Teenstep& Atm_Teenstep::enable() {
   trigger( EVT_ENABLE );
-  return *this;
 }
 
 Atm_Teenstep& Atm_Teenstep::homing(bool direction) {

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

@@ -5,6 +5,7 @@ Atm_Teenstep_OSC& Atm_Teenstep_OSC::begin(Atm_Teenstep& stepperMachineRef, Ether
   _adress = address;
   this->_udpRef =   &udpRef;
   this->_bndl = &bndl ;
+  //stepperMachine->onChangeposition( sendPosition, 0);
   return *this;
 }
 
@@ -29,3 +30,7 @@ Atm_Teenstep_OSC& Atm_Teenstep_OSC::onOSC(OSCMessage& msg ){
     return *this;
   }
 }
+
+void Atm_Teenstep_OSC::sendPosition(int idx, int v, int up) {
+  _bndl->add(_adress).add(v);
+}

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

@@ -20,6 +20,8 @@ class Atm_Teenstep_OSC {
     Atm_Teenstep_OSC& onOSC(OSCMessage& msg );
     Atm_Teenstep_OSC& sendOSC( void );
 
+    void sendPosition(int idx, int v, int up);
+
   private:
    // AccelStepper _motor;
    // Stepper *_motor;       // STEP pin: 2, DIR pin: 3

+ 1 - 2
HTequi-firmware/src/blobcnc_feeder/main.cpp

@@ -3,7 +3,7 @@
 #include <Automaton.h>
 //#include "Atm_lien/Atm_stepper.h"
 #include "Atm_Teenstep.h"
-#include "Atm_TeensyStep.h"
+//#include "Atm_TeensyStep.h"
 #include <SPI.h>
 #include <Ethernet.h>
 #include <EthernetUdp.h>
@@ -204,7 +204,6 @@ void setup() {
   pill_stepper.setMaxSpeed(PILL_SPEED*PILL_MICROSTEP);
   pill_stepper.setAcceleration(PILL_ACC*PILL_MICROSTEP);
   pill_sensor.begin(A1, 50).average( avgbuffer, sizeof( avgbuffer ) );
-
   barrel_homing();
   //stepper.onOnchange(Machine &machine, optional int event = 0)
   //stepper.cycle(1000);

+ 14 - 2
HTequi-firmware/src/blobcnc_top/main.cpp

@@ -4,8 +4,8 @@
 //Automaton and custom machines
 #include <Automaton.h>
 // #include "Atm_lien/Atm_stepper.h"
-#include "Atm_TeensyStep.h"
-#include "Atm_Tstepper_OSC.h"
+// #include "Atm_TeensyStep.h"
+// #include "Atm_Tstepper_OSC.h"
 #include "Atm_Teenstep.h"
 #include "Atm_Teenstep_OSC.h"
 #include "Atm_out.h"
@@ -173,6 +173,10 @@ void setup() {
   X_top_stepper.setAcceleration(HIGH_ACC);
   X_top_stepper.setInverseRotation(true);
   X_top_OSC.begin(X_top_step, Udp, bndl, "/X_top");
+  X_top_step.onChangeposition([](int idx, int v, int up){bndl.add("/X_top_OSC/step").add(v);});
+  X_top_step.onChange([](int idx, int v, int up){bndl.add("/X_top_OSC/state").add(v);});
+  X_top_step.onLimitlow([](int idx, int v, int up){bndl.add("/X_top_OSC/limitLow").add(v);});
+  X_top_step.onLimithigh([](int idx, int v, int up){bndl.add("/X_top_OSC/limitHigh").add(v);});
   // X_top_step.onOnchangeposition();
 
   Y_top_step.trace( Serial );
@@ -184,6 +188,14 @@ void setup() {
   Y_top_stepper.setAcceleration(2500);
   Y_top_stepper.setInverseRotation(false);
   Y_top_OSC.begin(Y_top_step, Udp, bndl, "/Y_top");
+  //OSC feedback
+  Y_top_step.onChangeposition([](int idx, int v, int up){bndl.add("/Y_top_OSC/step").add(v);});
+  Y_top_step.onChange([](int idx, int v, int up){bndl.add("/Y_top_OSC/state").add(v);});
+  Y_top_step.onLimitlow([](int idx, int v, int up){bndl.add("/Y_top_OSC/limitLow").add(v);});
+  Y_top_step.onLimithigh([](int idx, int v, int up){bndl.add("/Y_top_OSC/limitHigh").add(v);});
+  // Y_top_step.onChangeposition([] ( int idx, int v, int up ) {
+  //      bndl.
+  //    });
 
 
   // FEEDERS

+ 11 - 9
blob-CN/main.pd

@@ -1,4 +1,4 @@
-#N canvas 279 475 1743 541 12;
+#N canvas 343 356 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;
@@ -54,14 +54,13 @@
 #X msg 733 282 /Y_top/emergencyStop;
 #X obj 1159 335 list prepend set;
 #X obj 1159 360 list trim;
-#X msg 1159 385 /peristaltic 186;
+#X msg 1159 385 /Y_top_OSC/state 1;
 #X msg 542 157 /X_top/enable 1;
 #X msg 756 101 /feeder2/barrel_home;
 #X msg 746 131 /feeder1/barrel_home;
 #X msg 563 279 /X_top/home 1;
 #X floatatom 770 196 5 0 0 0 - - -;
 #X msg 530 194 sendtyped /X_top/move i \$1;
-#X msg 710 227 /Y_top/move 1000;
 #X msg 531 108 /X_top/SpeedAcc 5000 500;
 #X msg 804 185 /Y_top/SpeedAcc 10000 500;
 #X msg 837 46 /feeder2/pill;
@@ -75,9 +74,11 @@
 #X floatatom 369 226 5 0 0 0 - - -;
 #X floatatom 429 200 5 0 0 0 - - -;
 #X obj 690 321 hsl 128 15 0 255 0 0 empty empty empty -2 -8 0 10 -262144
--1 -1 9300 1;
+-1 -1 12700 1;
 #X obj 698 355 i;
 #X msg 674 395 /peristaltic \$1;
+#X msg 710 227 /Y_top/move \$1;
+#X floatatom 835 241 5 0 0 0 - - -;
 #X connect 0 0 35 0;
 #X connect 2 0 35 0;
 #X connect 3 0 35 0;
@@ -131,11 +132,12 @@
 #X connect 60 0 42 0;
 #X connect 61 0 42 0;
 #X connect 62 0 42 0;
-#X connect 63 0 42 0;
+#X connect 63 0 64 0;
+#X connect 64 0 62 0;
 #X connect 64 0 65 0;
-#X connect 65 0 63 0;
-#X connect 65 0 66 0;
-#X connect 67 0 65 0;
+#X connect 66 0 64 0;
+#X connect 67 0 68 0;
 #X connect 68 0 69 0;
-#X connect 69 0 70 0;
+#X connect 69 0 42 0;
 #X connect 70 0 42 0;
+#X connect 71 0 70 0;