فهرست منبع

seems we have a homing system

and working hard limits, falling back to enable
needs a connector to push the result of homing
titi 5 سال پیش
والد
کامیت
5e8e27324b
2فایلهای تغییر یافته به همراه115 افزوده شده و 42 حذف شده
  1. 95 38
      Atm_AccelStepper.cpp
  2. 20 4
      Atm_AccelStepper.h

+ 95 - 38
Atm_AccelStepper.cpp

@@ -7,21 +7,21 @@
 Atm_AccelStepper& Atm_AccelStepper::begin(int step_pin, int dir_pin) {
   // clang-format off
   const static state_t state_table[] PROGMEM = {
-    /*                       ON_ENTER     ON_LOOP          ON_EXIT  EVT_DISABLE  EVT_ENABLE  EVT_ENABLED_TIMEOUT  EVT_MOVE  EVT_STOP  EVT_EMERGENCY_STOP  EVT_ON_LIMIT_LOW  EVT_ON_LIMIT_HIGH  EVT_ON_TARGET  ELSE */
-    /*    DISABLED */    ENT_DISABLED,         -1,              -1,          -1,    ENABLED,                 -1,   RUNNING,        -1,                -1,               -1,                -1,            -1,   -1,
-    /*     ENABLED */     ENT_ENABLED,         -1,              -1,    DISABLE,         -1,             DISABLE,   RUNNING,      STOP,              STOP,               -1,                -1,            -1,   -1,
-    /*     RUNNING */     ENT_RUNNING, LP_RUNNING,              -1,    DISABLE,         -1,                  -1,   RUNNING,      STOP,              STOP,        LIMIT_LOW,        LIMIT_HIGH,       ENABLED,   -1,
-    /*        STOP */        ENT_STOP,    LP_STOP,              -1,    DISABLE,         -1,                  -1,   RUNNING,        -1,                -1,               -1,                -1,       ENABLED,   -1,
-    /*  HOMING_LOW */  ENT_HOMING_LOW,         -1,  EXT_HOMING_LOW,    DISABLE,         -1,                  -1,        -1,      STOP,              STOP,             STOP,                -1,            -1,   -1,
-    /* HOMING_HIGH */ ENT_HOMING_HIGH,         -1, EXT_HOMING_HIGH,    DISABLE,         -1,                  -1,        -1,      STOP,              STOP,               -1,              STOP,            -1,   -1,
-    /*   LIMIT_LOW */   ENT_LIMIT_LOW,         -1,              -1,          -1,         -1,                  -1,  RUNNING,      STOP,              STOP,        LIMIT_LOW,                -1,            -1,   -1,
-    /*  LIMIT_HIGH */  ENT_LIMIT_HIGH,         -1,              -1,          -1,         -1,                  -1,  RUNNING,      STOP,              STOP,               -1,        LIMIT_HIGH,            -1,   -1,
+    /*                       ON_ENTER           ON_LOOP          ON_EXIT  EVT_DISABLE  EVT_ENABLE  EVT_ENABLED_TIMEOUT  EVT_MOVE  EVT_STOP  EVT_EMERGENCY_STOP  EVT_ON_LIMIT_LOW  EVT_ON_LIMIT_HIGH  EVT_ON_TARGET  EVT_HOMING_LOW  EVT_HOMING_HIGH  ELSE */
+    /*    DISABLE */     ENT_DISABLED,              -1,              -1,         -1,    ENABLED,                  -1,   RUNNING,        -1,                -1,               -1,                -1,            -1,    HOMING_LOW,     HOMING_HIGH,   -1,
+    /*     ENABLED */     ENT_ENABLED,              -1,              -1,    DISABLE,         -1,             DISABLE,   RUNNING,      STOP,              STOP,               -1,                -1,            -1,    HOMING_LOW,     HOMING_HIGH,   -1,
+    /*     RUNNING */     ENT_RUNNING,      LP_RUNNING,              -1,    DISABLE,         -1,                  -1,   RUNNING,      STOP,              STOP,        LIMIT_LOW,        LIMIT_HIGH,       ENABLED,            -1,              -1,   -1,
+    /*        STOP */        ENT_STOP,         LP_STOP,              -1,    DISABLE,         -1,                  -1,   RUNNING,        -1,                -1,               -1,                -1,       ENABLED,            -1,              -1,   -1,
+    /*  HOMING_LOW */  ENT_HOMING_LOW,   LP_HOMING_LOW,  EXT_HOMING_LOW,    DISABLE,         -1,                  -1,        -1,      STOP,              STOP,        LIMIT_LOW,        LIMIT_HIGH,            -1,            -1,              -1,   -1,
+    /* HOMING_HIGH */ ENT_HOMING_HIGH,  LP_HOMING_HIGH, EXT_HOMING_HIGH,    DISABLE,         -1,                  -1,        -1,      STOP,              STOP,        LIMIT_LOW,        LIMIT_HIGH,            -1,            -1,              -1,   -1,
+    /*   LIMIT_LOW */   ENT_LIMIT_LOW,              -1,              -1,         -1,         -1,                  -1,   RUNNING,      STOP,              STOP,        LIMIT_LOW,                -1,            -1,            -1,              -1,   -1,
+    /*  LIMIT_HIGH */  ENT_LIMIT_HIGH,              -1,              -1,         -1,         -1,                  -1,   RUNNING,      STOP,              STOP,               -1,        LIMIT_HIGH,            -1,            -1,              -1,   -1
   };
   // clang-format on
   Machine::begin( state_table, ELSE );
   stepper = new AccelStepper(1, step_pin, dir_pin);
-  stepper->setMaxSpeed(1000);
-  stepper->setAcceleration(100);
+  stepper->setMaxSpeed(max_speed);
+  stepper->setAcceleration(acceleration);
   idle_timer.set(ATM_TIMER_OFF);
   return *this;
 }
@@ -61,10 +61,6 @@ int Atm_AccelStepper::event( int id ) {
           int analogTemp = analogRead(_limitLow_Pin);
           limitLow_State = (_limitLow_Thresholds[0] < analogTemp) && (analogTemp < _limitLow_Thresholds[1]);
           limitLow_State = _limitLow_Reversed ? !limitLow_State : limitLow_State;
-          Serial.print("analog ");
-          Serial.print(analogTemp);
-          Serial.print("  state ");
-          Serial.println(limitLow_State);
           return limitLow_State;
       }
     case EVT_ON_LIMIT_HIGH:
@@ -83,7 +79,11 @@ int Atm_AccelStepper::event( int id ) {
           return limitHigh_State;
       }
     case EVT_ON_TARGET:
-      return _currentStep == _targetStep;;
+      return _currentStep == _targetStep;
+    case EVT_HOMING_LOW:
+      return 0;
+    case EVT_HOMING_HIGH:
+      return 0;
   }
   return 0;
 }
@@ -102,7 +102,6 @@ int Atm_AccelStepper::event( int id ) {
 
 void Atm_AccelStepper::action( int id ) {
   switch ( id ) {
-    long int tempStep ;
     case ENT_DISABLED:
       push(connectors, ON_CHANGESTATE, 0,  state(), 0);
       enabled = _enableReversed ? HIGH : LOW;
@@ -115,25 +114,9 @@ void Atm_AccelStepper::action( int id ) {
       return;
     case ENT_RUNNING:
       push(connectors, ON_CHANGESTATE, 0,  state(), 0);
-
       return;
     case LP_RUNNING:
-
-      switch (runMode) {
-        case 0:
-          stepper->run();
-          break;
-        case 1:
-          stepper->runSpeed();
-          break;
-      }
-
-      tempStep = stepper->currentPosition();
-      if (tempStep != _currentStep){
-        _currentStep =  tempStep;
-        push(connectors, ON_CHANGEPOSITION, 0,  _currentStep, 0);
-      }
-
+      stepper_update();
       return;
     case ENT_STOP:
     push(connectors, ON_CHANGESTATE, 0,  state(), 0);
@@ -151,25 +134,50 @@ void Atm_AccelStepper::action( int id ) {
       }
       return;
     case LP_STOP:
-      stepper->run();
+      stepper_update();
       _currentStep = stepper->currentPosition();
       return;
     case ENT_HOMING_LOW:
+      runMode = 1;
+      stepper->setSpeed(-1*homing_speed);
+      return;
+    case LP_HOMING_LOW:
+      stepper_update();
       return;
     case EXT_HOMING_LOW:
+      if(last_trigger == EVT_ON_LIMIT_LOW) {
+        stepper->setCurrentPosition(0);
+        _currentStep = 0;
+        Serial.println("homing low done");
+      }
+      else{Serial.println("homing low failed");}
+
       return;
     case ENT_HOMING_HIGH:
+      runMode = 1;
+      stepper->setSpeed(homing_speed);
+      return;
+    case LP_HOMING_HIGH:
+      stepper_update();
       return;
     case EXT_HOMING_HIGH:
+      if(last_trigger == EVT_ON_LIMIT_HIGH) {
+        _maxStep = stepper->currentPosition();
+        _currentStep = _maxStep;
+        Serial.println("homing high done");
+      }
+      else{Serial.println("homing high failed");}
       return;
     case ENT_LIMIT_LOW:
       push( connectors, ON_ONLIMITLOW, 0, 0, 0 );
       //stop motor if going down, allow going up
-      stepper->speed() < 0 ? trigger(EVT_EMERGENCY_STOP) :  trigger(EVT_MOVE);
+      if(_limitLow_Hard && (stepper->speed() < 0)) {trigger(EVT_EMERGENCY_STOP);}
+      else{stepper_update(); trigger(EVT_MOVE);}
       return;
     case ENT_LIMIT_HIGH:
       push( connectors, ON_ONLIMITHIGH, 0, 1, 0 );
-      stepper->speed() > 0 ? trigger(EVT_EMERGENCY_STOP) : trigger(EVT_MOVE);
+      if(_limitHigh_Hard && (stepper->speed() > 0)) {trigger(EVT_EMERGENCY_STOP);}
+      else{stepper_update() ; trigger(EVT_MOVE);}
       return;
   }
 }
@@ -198,8 +206,25 @@ int Atm_AccelStepper::state( void ) {
 /* Still I'll customize a little just here
 */
 
+void Atm_AccelStepper::stepper_update(void) {
+  switch (runMode) {
+    case 0: //positional modae
+      stepper->run();
+      break;
+    case 1: // speed mode
+      stepper->runSpeed();
+      break;
+  }
+  long int tempStep = stepper->currentPosition();
+  if (tempStep != _currentStep){
+    _currentStep =  tempStep;
+    push(connectors, ON_CHANGEPOSITION, 0,  _currentStep, stepper->speed());
+  }
+}
+
 Atm_AccelStepper& Atm_AccelStepper::move( long int stepRel) {
   _targetStep   = _currentStep + stepRel;
+  runMode = 0;
   //Serial.println(_targetStep);
   stepper->move(_targetStep);
   enable();
@@ -209,6 +234,7 @@ Atm_AccelStepper& Atm_AccelStepper::move( long int stepRel) {
 
 Atm_AccelStepper& Atm_AccelStepper::moveTo( long int stepAbs) {
   _targetStep   = stepAbs;
+  runMode = 0;
   stepper->moveTo(_targetStep);
   enable();
   trigger( EVT_MOVE );
@@ -216,6 +242,9 @@ Atm_AccelStepper& Atm_AccelStepper::moveTo( long int stepAbs) {
 }
 
 Atm_AccelStepper& Atm_AccelStepper::rotate( long int speed) {
+  runMode = 1;
+  stepper->setSpeed(speed);
+  enable();
   trigger( EVT_MOVE );
   return *this;
 }
@@ -240,6 +269,10 @@ Atm_AccelStepper& Atm_AccelStepper::limitLow_set(int mode,  int pin,  int revers
   return *this;
 }
 
+Atm_AccelStepper& Atm_AccelStepper::limitLow_isHard(bool hardlimit){
+  _limitLow_Hard = hardlimit;
+}
+
 Atm_AccelStepper& Atm_AccelStepper::limitLow_setThresholds (int threshold_low, int threshold_high){
   _limitLow_Thresholds[0] = threshold_low ;
   _limitLow_Thresholds[1] = threshold_high ;
@@ -255,6 +288,10 @@ Atm_AccelStepper& Atm_AccelStepper::limitHigh_set(int mode,  int pin,  int rever
   return *this;
 }
 
+Atm_AccelStepper& Atm_AccelStepper::limitHigh_isHard(bool hardlimit){
+  _limitHigh_Hard = hardlimit;
+}
+
 Atm_AccelStepper& Atm_AccelStepper::limitHigh_setThresholds (int threshold_low, int threshold_high){
   _limitHigh_Thresholds[0] = threshold_low ;
   _limitHigh_Thresholds[1] = threshold_high ;
@@ -391,12 +428,32 @@ Atm_AccelStepper& Atm_AccelStepper::onStop( atm_cb_push_t callback, int idx ) {
   return *this;
 }
 
+Atm_AccelStepper& Atm_AccelStepper::onOnhominglow( Machine& machine, int event ) {
+  onPush( connectors, ON_ONTARGET, 0, 1, 1, machine, event );
+  return *this;
+}
+
+Atm_AccelStepper& Atm_AccelStepper::onOnhominglow( atm_cb_push_t callback, int idx ) {
+  onPush( connectors, ON_ONTARGET, 0, 1, 1, callback, idx );
+  return *this;
+}
+
+Atm_AccelStepper& Atm_AccelStepper::onOnhominghigh( Machine& machine, int event ) {
+  onPush( connectors, ON_ONTARGET, 0, 1, 1, machine, event );
+  return *this;
+}
+
+Atm_AccelStepper& Atm_AccelStepper::onOnhominghigh( atm_cb_push_t callback, int idx ) {
+  onPush( connectors, ON_ONTARGET, 0, 1, 1, callback, idx );
+  return *this;
+}
+
 /* State trace method
  * Sets the symbol table and the default logging method for serial monitoring
  */
 
 Atm_AccelStepper& Atm_AccelStepper::trace( Stream & stream ) {
   Machine::setTrace( &stream, atm_serial_debug::trace,
-    "ACCELSTEPPER\0EVT_DISABLE\0EVT_ENABLE\0EVT_ENABLED_TIMEOUT\0EVT_MOVE\0EVT_STOP\0EVT_EMERGENCY_STOP\0EVT_ON_LIMIT_LOW\0EVT_ON_LIMIT_HIGH\0EVT_ON_TARGET\0ELSE\0DISABLED\0ENABLED\0RUNNING\0STOP\0HOMING_LOW\0HOMING_HIGH\0LIMIT_LOW\0LIMIT_HIGH" );
+    "ACCELSTEPPER\0EVT_DISABLE\0EVT_ENABLE\0EVT_ENABLED_TIMEOUT\0EVT_MOVE\0EVT_STOP\0EVT_EMERGENCY_STOP\0EVT_ON_LIMIT_LOW\0EVT_ON_LIMIT_HIGH\0EVT_ON_TARGET\0EVT_HOMING_LOW\0EVT_HOMING_HIGH\0ELSE\0DISABLED\0ENABLED\0RUNNING\0STOP\0HOMING_LOW\0HOMING_HIGH\0LIMIT_LOW\0LIMIT_HIGH" );
   return *this;
 }

+ 20 - 4
Atm_AccelStepper.h

@@ -7,7 +7,9 @@ class Atm_AccelStepper: public Machine {
 
  public:
   enum { DISABLE, ENABLED, RUNNING, STOP, HOMING_LOW, HOMING_HIGH, LIMIT_LOW, LIMIT_HIGH }; // STATES
-  enum { EVT_DISABLE, EVT_ENABLE, EVT_ENABLED_TIMEOUT, EVT_MOVE, EVT_STOP, EVT_EMERGENCY_STOP, EVT_ON_LIMIT_LOW, EVT_ON_LIMIT_HIGH, EVT_ON_TARGET, ELSE }; // EVENTS
+  enum { EVT_DISABLE, EVT_ENABLE, EVT_ENABLED_TIMEOUT, EVT_MOVE, EVT_STOP,
+          EVT_EMERGENCY_STOP, EVT_ON_LIMIT_LOW, EVT_ON_LIMIT_HIGH, EVT_ON_TARGET,
+          EVT_HOMING_LOW, EVT_HOMING_HIGH, ELSE }; // EVENTS
   Atm_AccelStepper( void ) : Machine() {};
   Atm_AccelStepper& begin( int step_pin, int dir_pin );
   Atm_AccelStepper& trace( Stream & stream );
@@ -25,6 +27,10 @@ class Atm_AccelStepper: public Machine {
   Atm_AccelStepper& onOntarget( atm_cb_push_t callback, int idx = 0 );
   Atm_AccelStepper& onStop( Machine& machine, int event = 0 );
   Atm_AccelStepper& onStop( atm_cb_push_t callback, int idx = 0 );
+  Atm_AccelStepper& onOnhominglow( Machine& machine, int event = 0 );
+  Atm_AccelStepper& onOnhominglow( atm_cb_push_t callback, int idx = 0 );
+  Atm_AccelStepper& onOnhominghigh( Machine& machine, int event = 0 );
+  Atm_AccelStepper& onOnhominghigh( atm_cb_push_t callback, int idx = 0 );
   Atm_AccelStepper& disable( void );
   Atm_AccelStepper& enable( void );
   //Atm_AccelStepper& move( void );
@@ -36,32 +42,40 @@ class Atm_AccelStepper: public Machine {
 
   AccelStepper *stepper;
 
+  long int homing_speed = 500;
+  long int max_speed = 5000;
+  long int acceleration = 1000;
+
   Atm_AccelStepper& move( long int stepRel );
   Atm_AccelStepper& moveTo( long int stepAbs );
   Atm_AccelStepper& rotate( long int speed );
   Atm_AccelStepper& homing( bool direction );
   int runMode = 0; // 0 uses run() for positioning, 1 uses runSpeed() for constant speed
 
-    Atm_AccelStepper& setEnablePin( int enablePin );
+  Atm_AccelStepper& setEnablePin( int enablePin );
   Atm_AccelStepper& enableReversed( bool reverse );
   bool enabled ;
 
 
   Atm_AccelStepper& limitLow_set(int mode = 0, int pin = -1, int reversed=0);
+  Atm_AccelStepper& limitLow_isHard(bool hardlimit = 1);
   Atm_AccelStepper& limitLow_setThresholds (int threshold_low=510, int threshold_high = 1024);
   Atm_AccelStepper& limitHigh_set(int mode = 0, int pin = -1, int reversed=0);
+  Atm_AccelStepper& limitHigh_isHard(bool hardlimit = 1);
   Atm_AccelStepper& limitHigh_setThresholds (int threshold_low=510, int threshold_high = 1024);
   bool limitLow_State;
   bool limitHigh_State;
 
 
  private:
-  enum { ENT_DISABLED, ENT_ENABLED,ENT_RUNNING, LP_RUNNING, ENT_STOP, LP_STOP, ENT_HOMING_LOW, EXT_HOMING_LOW, ENT_HOMING_HIGH, EXT_HOMING_HIGH, ENT_LIMIT_LOW, ENT_LIMIT_HIGH }; // ACTIONS
+  enum { ENT_DISABLED, ENT_ENABLED,ENT_RUNNING, LP_RUNNING, ENT_STOP, LP_STOP, ENT_HOMING_LOW, LP_HOMING_LOW, EXT_HOMING_LOW, ENT_HOMING_HIGH, LP_HOMING_HIGH, EXT_HOMING_HIGH, ENT_LIMIT_LOW, ENT_LIMIT_HIGH }; // ACTIONS
   enum { ON_CHANGEPOSITION, ON_CHANGESTATE, ON_ONLIMITHIGH, ON_ONLIMITLOW, ON_ONTARGET, ON_STOP, CONN_MAX }; // CONNECTORS
   atm_connector connectors[CONN_MAX];
   int event( int id );
   void action( int id );
 
+  void stepper_update(void);
+
   long int _currentStep = 0;
   long int _targetStep = 0;
   long int _maxStep ;
@@ -72,13 +86,15 @@ class Atm_AccelStepper: public Machine {
   int IDLE_TIMEOUT_DURATION = 500000 ;
 
   int _limitLow_Pin;
-  int _limitLow_Mode; //0 no limit, 1 digital, 2 analog with thresholds
+  int _limitLow_Mode = 0; //0 no limit, 1 digital, 2 analog with thresholds
   bool _limitLow_Reversed ; //invert logic of limit switches
   int _limitLow_Thresholds[2] ; //analog value  range for two analog limits
+  bool _limitLow_Hard = 1;
   int _limitHigh_Pin;
   int _limitHigh_Mode; //0 no limit, 1 digital, 2 analog with thresholds
   bool _limitHigh_Reversed ; //invert logic of limit switches
   int _limitHigh_Thresholds[2] ; //analog value  range for two analog limits
+  bool _limitHigh_Hard = 1 ;
   void updateLimitSwitch();
 
 };