Browse Source

Feeder : working prototype, need sequence
TOP : stepper with endstop (digital/analog). Most needed methods
implemented

eLandon 6 years ago
parent
commit
94d4f86373

+ 94 - 11
HTequi-firmware/src/Atm_lien/Atm_TeensyStep.cpp

@@ -8,7 +8,7 @@ Atm_TeensyStep& Atm_TeensyStep::begin(Stepper & motorRef, StepControl & stepCont
   // clang-format off
   // clang-format off
   const static state_t state_table[] PROGMEM = {
   const static state_t state_table[] PROGMEM = {
     /*                 ON_ENTER     ON_LOOP       ON_EXIT  EVT_IDLE_TIMER  EVT_ON_TARGET  EVT_GOTO  ELSE */
     /*                 ON_ENTER     ON_LOOP       ON_EXIT  EVT_IDLE_TIMER  EVT_ON_TARGET  EVT_GOTO  ELSE */
-    /*     IDLE */     ENT_IDLE,         -1,           -1,             -1,            -1,  RUNNING,   -1,
+    /*     IDLE */     ENT_IDLE,         -1,     EXT_IDLE,             -1,            -1,  RUNNING,   -1,
     /*    READY */    ENT_READY,         -1,           -1,           IDLE,            -1,  RUNNING,   -1,
     /*    READY */    ENT_READY,         -1,           -1,           IDLE,            -1,  RUNNING,   -1,
     /*  RUNNING */  ENT_RUNNING, LP_RUNNING,           -1,             -1,      STOPPING,  RUNNING,   -1,
     /*  RUNNING */  ENT_RUNNING, LP_RUNNING,           -1,             -1,      STOPPING,  RUNNING,   -1,
     /* STOPPING */ ENT_STOPPING,         -1, EXT_STOPPING,             -1,         READY,       -1,   -1,
     /* STOPPING */ ENT_STOPPING,         -1, EXT_STOPPING,             -1,         READY,       -1,   -1,
@@ -54,25 +54,30 @@ int Atm_TeensyStep::event( int id ) {
 void Atm_TeensyStep::action( int id ) {
 void Atm_TeensyStep::action( int id ) {
   switch ( id ) {
   switch ( id ) {
     case ENT_IDLE:
     case ENT_IDLE:
-      digitalWrite(0, LOW);
+      enable(0);
+      return;
+    case EXT_IDLE:
+      enable(1);
       return;
       return;
     case ENT_READY:
     case ENT_READY:
-    digitalWrite(0, HIGH);
+
       return;
       return;
     case ENT_RUNNING:
     case ENT_RUNNING:
-      digitalWrite(0, HIGH);
 
 
       // _controller.moveAsync(*_motor);
       // _controller.moveAsync(*_motor);
       return;
       return;
     case LP_RUNNING:
     case LP_RUNNING:
       // _motor.run();
       // _motor.run();
       _currentStep = motor->getPosition();
       _currentStep = motor->getPosition();
-
+      updateLimitSwitch();
+      if(limitState[0] || limitState[1]) {emergencyStop();}
      // Serial.println(_motor.currentPosition());
      // Serial.println(_motor.currentPosition());
       return;
       return;
     case ENT_STOPPING:
     case ENT_STOPPING:
       return;
       return;
     case EXT_STOPPING:
     case EXT_STOPPING:
+      if(_isHoming && limitState[0]){motor->setPosition(0);_isHoming=0;}
+      if(_isHoming && limitState[1]){maxStep = motor->getPosition();_isHoming=0;}
       return;
       return;
   }
   }
 }
 }
@@ -94,6 +99,29 @@ int Atm_TeensyStep::state( void ) {
   return Machine::state();
   return Machine::state();
 }
 }
 
 
+void Atm_TeensyStep::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;
+  }
+
+}
+
 /* Nothing customizable below this line
 /* Nothing customizable below this line
  ************************************************************************************************
  ************************************************************************************************
 */
 */
@@ -101,6 +129,62 @@ int Atm_TeensyStep::state( void ) {
 /* Public event methods
 /* Public event methods
  *
  *
  */
  */
+ Atm_TeensyStep& Atm_TeensyStep::setLimitPins( int limitPinLow){
+   _limitPin[0] = limitPinLow;
+   pinMode(_limitPin[0], INPUT);
+   return *this;
+ }
+
+Atm_TeensyStep& Atm_TeensyStep::setLimitPins( int limitPinLow, int limitPinHigh){
+  _limitPin[0] = limitPinLow;
+  _limitPin[1] = limitPinHigh;
+  pinMode(_limitPin[0], INPUT);
+  pinMode(_limitPin[1], INPUT);
+  return *this;
+}
+
+Atm_TeensyStep& Atm_TeensyStep::setLimitType( int limitType){
+  _limitType = limitType;
+  return *this;
+}
+
+Atm_TeensyStep& Atm_TeensyStep::limitReversed( bool reversed){
+  _limitReversed = reversed;
+  return *this;
+}
+
+Atm_TeensyStep& Atm_TeensyStep::limitThresholds( int limitThreshold0,
+        int limitThreshold1,  int limitThreshold2, int limitThreshold3){
+  _limitThresholds[0] = limitThreshold0;
+  _limitThresholds[1] = limitThreshold1;
+  _limitThresholds[2] = limitThreshold2;
+  _limitThresholds[3] = limitThreshold3;
+  return *this;
+}
+
+Atm_TeensyStep& Atm_TeensyStep::enable( bool enable ){
+  enabled = enable ;
+  enabled = _enableReversed ? !enabled : enabled ;
+  digitalWrite(_enablePin, enabled);
+  return *this;
+}
+
+Atm_TeensyStep& Atm_TeensyStep::setEnablePin( int enablePin ){
+  _enablePin = enablePin ;
+  pinMode(_enablePin, OUTPUT);
+  return *this;
+}
+
+Atm_TeensyStep& Atm_TeensyStep::enableReversed( bool reverse ){
+  _enableReversed = reverse ;
+  return *this;
+}
+
+Atm_TeensyStep& Atm_TeensyStep::home( bool limit ){
+  _isHoming = 1 ;
+  limit ? move(-2147483647) : move(2147483647) ; // move to very far away until hit
+  return *this;
+}
 
 
 Atm_TeensyStep& Atm_TeensyStep::move(long int stepRel ) {
 Atm_TeensyStep& Atm_TeensyStep::move(long int stepRel ) {
   _targetStep   += stepRel;
   _targetStep   += stepRel;
@@ -120,17 +204,16 @@ Atm_TeensyStep& Atm_TeensyStep::moveTo(long int stepAbs ) {
   _targetStep   = stepAbs;
   _targetStep   = stepAbs;
   motor->setTargetAbs(_targetStep);
   motor->setTargetAbs(_targetStep);
   controller->moveAsync(*motor);
   controller->moveAsync(*motor);
-
-  // _motor.move(targetStep);
-  // _motor.run();
-  // Serial.println(_motor.distanceToGo());
-  // _motor.setMaxSpeed(5000);
-  // _motor.setAcceleration(6000);
   trigger( EVT_GOTO );
   trigger( EVT_GOTO );
   return *this;
   return *this;
 }
 }
 
 
 Atm_TeensyStep& Atm_TeensyStep::stop(){
 Atm_TeensyStep& Atm_TeensyStep::stop(){
+  controller->stopAsync();
+  //trigger( EVT_STOPPING );
+}
+
+Atm_TeensyStep& Atm_TeensyStep::emergencyStop(){
   controller->emergencyStop();
   controller->emergencyStop();
   //trigger( EVT_STOPPING );
   //trigger( EVT_STOPPING );
 }
 }

+ 31 - 1
HTequi-firmware/src/Atm_lien/Atm_TeensyStep.h

@@ -16,18 +16,36 @@ class Atm_TeensyStep: public Machine {
   int state( void );
   int state( void );
   Atm_TeensyStep& onOnchange( Machine& machine, int event = 0 );
   Atm_TeensyStep& onOnchange( Machine& machine, int event = 0 );
   Atm_TeensyStep& onOnchange( atm_cb_push_t callback, int idx = 0 );
   Atm_TeensyStep& onOnchange( atm_cb_push_t callback, int idx = 0 );
+  int enable_timeout; //in idle mode, how long before sleep (stepper disabled
+  Atm_TeensyStep& setLimitType( int limitType = 0);
+  Atm_TeensyStep& setLimitPins( int limitPinLow);
+  Atm_TeensyStep& setLimitPins( int limitPinLow, int limitPinHigh);
+  Atm_TeensyStep& limitReversed( bool reversed );
+  Atm_TeensyStep& limitThresholds( int limitThreshold0, int limitThreshold1,
+                                  int limitThreshold2, int limitThreshold3);
+  Atm_TeensyStep& setEnablePin( int enablePin );
+  Atm_TeensyStep& enableReversed( bool reverse );
+  bool enabled ;
+  Atm_TeensyStep& enable( bool enable );
+  Atm_TeensyStep& home( bool limit ); // 0(default) for home, 1 for max value
   Atm_TeensyStep& move( long int stepRel );
   Atm_TeensyStep& move( long int stepRel );
   Atm_TeensyStep& moveTo( long int stepAbs );
   Atm_TeensyStep& moveTo( long int stepAbs );
   Atm_TeensyStep& stop();
   Atm_TeensyStep& stop();
+  Atm_TeensyStep& emergencyStop();
   Stepper * motor;
   Stepper * motor;
   StepControl * controller;
   StepControl * controller;
 
 
+  bool limitState[2] ; // up to two limits, at least one for homing
+  bool homed; //stepper has been homed
+  long int maxStep ;
+
  private:
  private:
   // AccelStepper _motor;
   // AccelStepper _motor;
   // Stepper *_motor;       // STEP pin: 2, DIR pin: 3
   // Stepper *_motor;       // STEP pin: 2, DIR pin: 3
   // StepControl _controller;
   // StepControl _controller;
 
 
-  enum { ENT_IDLE, ENT_READY, ENT_RUNNING, LP_RUNNING, ENT_STOPPING, EXT_STOPPING }; // ACTIONS
+  enum { ENT_IDLE, EXT_IDLE, ENT_READY, ENT_RUNNING, LP_RUNNING,
+          ENT_STOPPING, EXT_STOPPING }; // ACTIONS
   enum { ON_ONCHANGE, CONN_MAX }; // CONNECTORS
   enum { ON_ONCHANGE, CONN_MAX }; // CONNECTORS
   atm_connector connectors[CONN_MAX];
   atm_connector connectors[CONN_MAX];
   int event( int id );
   int event( int id );
@@ -36,6 +54,18 @@ class Atm_TeensyStep: public Machine {
   long int _currentStep ;
   long int _currentStep ;
   long int _targetStep ;
   long int _targetStep ;
 
 
+  int _enablePin;
+  bool _enableReversed ;
+
+
+
+  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();
+  bool _isHoming;
 };
 };
 
 
 /*
 /*

+ 5 - 4
HTequi-firmware/src/blobcnc_feeder/main.cpp

@@ -27,8 +27,8 @@ EthernetUDP Udp;
 
 
 
 
 /////////////////// STEPPER machines  ////////////////////////
 /////////////////// STEPPER machines  ////////////////////////
-const int HIGH_SPEED = 8000 ;
-const int HIGH_ACC = 8000 ;
+const int HIGH_SPEED = 800 ;
+const int HIGH_ACC = 800 ;
 const int LOW_SPEED = 100 ;
 const int LOW_SPEED = 100 ;
 const int LOW_ACC = 1000 ;
 const int LOW_ACC = 1000 ;
 const int BARREL_DISTANCE = 10 ; //in full steps
 const int BARREL_DISTANCE = 10 ; //in full steps
@@ -36,9 +36,9 @@ const int BARREL_DISTANCE = 10 ; //in full steps
 const int REDUCTION_RATIO = 26.85;
 const int REDUCTION_RATIO = 26.85;
 
 
 const int PILL_MICROSTEP = 32;
 const int PILL_MICROSTEP = 32;
-const int BARREL_MICROSTEP = 32;
+const int BARREL_MICROSTEP = 1;
 
 
-const int BARREL_THRESHOLD = 0 ;
+const int BARREL_THRESHOLD = 950 ;
 
 
 Atm_TeensyStep barrel_step;
 Atm_TeensyStep barrel_step;
 Stepper barrel_stepper(3, 2);
 Stepper barrel_stepper(3, 2);
@@ -171,6 +171,7 @@ void setup() {
   barrel_step.begin(barrel_stepper, barrel_controller);
   barrel_step.begin(barrel_stepper, barrel_controller);
   barrel_stepper.setMaxSpeed(LOW_SPEED);
   barrel_stepper.setMaxSpeed(LOW_SPEED);
   barrel_stepper.setAcceleration(HIGH_ACC);
   barrel_stepper.setAcceleration(HIGH_ACC);
+  barrel_stepper.setInverseRotation(true);
   barrel_sensor.begin(A1);
   barrel_sensor.begin(A1);
 
 
   pill_step.trace( Serial );
   pill_step.trace( Serial );

+ 90 - 0
HTequi-firmware/src/blobcnc_top/main.cpp

@@ -0,0 +1,90 @@
+// stepper Y 22, 21, 23
+// stepper X 20, 19, 18
+//           St, Di, En
+
+
+#include <Arduino.h>
+
+#include <Automaton.h>
+#include "Atm_lien/Atm_stepper.h"
+#include "Atm_lien/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;
+
+
+/////////////////// STEPPER machines  ////////////////////////
+const int HIGH_SPEED = 800 ;
+const int HIGH_ACC = 800 ;
+const int LOW_SPEED = 100 ;
+const int LOW_ACC = 1000 ;
+
+Atm_TeensyStep X_top_step;
+Stepper X_top_stepper(20 , 19);
+StepControl X_top_controller ;
+
+
+//////////////  Setup  /////////////////////
+
+void setup() {
+  //Configure and start ethernet module (not needed for feeder)
+  //SPI.setSCK(27); //only bottom
+  Ethernet.init(15);//(10)
+  teensyMAC(mac);
+  Ethernet.begin(mac, ip);              // start the Ethernet and UDP:
+ //  Udp.beginMulti(ipMulti, portMulti);   // for modified Arduino library
+  Udp.beginMulticast(ipMulti, portMulti); // for modified Teensy Ethernet library
+
+  //Start serial
+  Serial.begin(115200); // higher Baud rate for faster refresh, CHANGE IN SERIAL MONITOR
+  delay(2000);
+  Serial.println("Started");
+  pinMode(13, OUTPUT);
+
+  // pinMode(18, OUTPUT);
+  // digitalWrite(18, LOW);
+  X_top_step.trace( Serial );
+  X_top_step.begin(X_top_stepper, X_top_controller)
+            .setEnablePin(18).enable(1)
+            .setLimitType(1).setLimitPins(A3).limitReversed(true).limitThresholds(600, 800, 900, 1200);
+  X_top_stepper.setMaxSpeed(HIGH_SPEED);
+  X_top_stepper.setAcceleration(HIGH_ACC);
+  X_top_stepper.setInverseRotation(true);
+
+  //stepper.onOnchange(Machine &machine, optional int event = 0)
+  //stepper.cycle(1000);
+  X_top_step.move(100000);
+  //controller.moveAsync(*stepper.motor);
+  //pinMode(17, INPUT);
+}
+
+
+
+void loop() {
+  automaton.run();
+  Serial.print(analogRead(A3));
+  Serial.print("   ");
+  Serial.print(X_top_step.limitState[0]);
+  Serial.print("   ");
+  Serial.println(X_top_step.limitState[1]);
+  delay(10);
+
+}