소스 검색

limit management refactoring

moved to a state change version, limits only send event when changing
states
limits are states equivalent to running with one direction forbiden
titi 5 년 전
부모
커밋
aef283cf21
2개의 변경된 파일68개의 추가작업 그리고 50개의 파일을 삭제
  1. 59 47
      Atm_AccelStepper.cpp
  2. 9 3
      Atm_AccelStepper.h

+ 59 - 47
Atm_AccelStepper.cpp

@@ -7,15 +7,15 @@
 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  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,        LIMIT_LOW,        LIMIT_HIGH,            -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
+    /*                       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,        LIMIT_LOW,        LIMIT_HIGH,            -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,    LP_LIMIT_LOW,              -1,         -1,         -1,                  -1,     RUNNING,      STOP,              STOP,        LIMIT_LOW,                -1,            -1,            -1,              -1,   -1,
+    /*  LIMIT_HIGH */  ENT_LIMIT_HIGH,   LP_LIMIT_HIGH,              -1,         -1,         -1,                  -1,     RUNNING,      STOP,              STOP,               -1,        LIMIT_HIGH,            -1,            -1,              -1,   -1
   };
   // clang-format on
   Machine::begin( state_table, ELSE );
@@ -48,6 +48,7 @@ int Atm_AccelStepper::event( int id ) {
     case EVT_EMERGENCY_STOP:
       return 0;
     case EVT_ON_LIMIT_LOW:
+      previous_state = limitLow_State;
       switch(_limitLow_Mode) {
         case 0:
           return 0;
@@ -55,31 +56,31 @@ int Atm_AccelStepper::event( int id ) {
           // Serial.println("digital");
           limitLow_State = digitalRead(_limitLow_Pin);
           limitLow_State = _limitLow_Reversed ? !limitLow_State : limitLow_State;
-          return limitLow_State;
+          return limitLow_State != previous_state;
         case 2:
-
           int analogTemp = analogRead(_limitLow_Pin);
           limitLow_State = (_limitLow_Thresholds[0] < analogTemp) && (analogTemp < _limitLow_Thresholds[1]);
           limitLow_State = _limitLow_Reversed ? !limitLow_State : limitLow_State;
           if(limitLow_State){analogTemp = analogRead(_limitLow_Pin);
           limitLow_State = (_limitLow_Thresholds[0] < analogTemp) && (analogTemp < _limitLow_Thresholds[1]);
           limitLow_State = _limitLow_Reversed ? !limitLow_State : limitLow_State;}
-          return limitLow_State;
+          return limitLow_State != previous_state;
       }
     case EVT_ON_LIMIT_HIGH:
+      previous_state = limitHigh_State;
       switch(_limitHigh_Mode) {
         case 0:
           return 0;
         case 1: //digital INPUT
           limitHigh_State = digitalRead(_limitHigh_Pin);
           limitHigh_State = _limitHigh_Reversed ? !limitHigh_State : limitHigh_State;
-          return limitHigh_State;
+          return limitHigh_State != previous_state;
         case 2:
         //Serial.println("analog");
           int analogTemp = analogRead(_limitHigh_Pin);
           limitHigh_State = (_limitHigh_Thresholds[0] < analogTemp) && (analogTemp < _limitHigh_Thresholds[1]);
           limitHigh_State = _limitHigh_Reversed ? !limitHigh_State : limitHigh_State;
-          return limitHigh_State;
+          return limitHigh_State != previous_state;
       }
     case EVT_ON_TARGET:
       return runMode ? 0 : _currentStep == _targetStep;
@@ -122,7 +123,13 @@ void Atm_AccelStepper::action( int id ) {
     case ENT_RUNNING:
       push(connectors, ON_CHANGESTATE, 0,  state(), 0);
       _isHoming = 0;
+      //reset limit state so that they trigger again if we're stopped on it
+      limitLow_State = 0;
+      limitHigh_State = 0;
+      Serial.print("target ");
+      Serial.println(_targetStep);
       stepper->moveTo(_targetStep);
+      //stepper_update();
       //push(connectors, ON_CHANGEPOSITION, 0,  _currentStep, stepper->speed());
       position_timer.setFromNow(this, POSITION_SEND_TIMER);
       return;
@@ -193,40 +200,42 @@ void Atm_AccelStepper::action( int id ) {
       _targetStep = _currentStep;
       return;
     case ENT_LIMIT_LOW:
-      push( connectors, ON_ONLIMITLOW, 0, 0, 0 );
+      /*triggered by a change in limit state
+       if state is 0, we may leave this state for running
+       if state is 1 we stay in limit state loop, where moves are allowed only in
+            the free direction, until a trigger comes with state 0
+      */
+      push( connectors, ON_ONLIMITLOW, 0, limitLow_State, 0 );
+      if (!limitLow_State){trigger(EVT_MOVE);}
+      return;
+
+    case LP_LIMIT_LOW:
       //stop motor if going down, allow going up
-      if(_limitLow_Hard && (stepper->speed()<=0) ) {trigger(EVT_EMERGENCY_STOP);}
-      else{ stepper_update();trigger(EVT_MOVE);} // _isHoming ? trigger(EVT_STOP):
-       //   switch(_isHoming) {
-       //     case 0 :
-       //      trigger(EVT_MOVE);
-       //      break;
-       //     case 1 :
-       //      trigger(EVT_HOMING_LOW);
-       //      break;
-       //     case 2 :
-       //      trigger(EVT_HOMING_HIGH);
-       //      break;
-       //   }
-       // }
+      stepper_update();
+      if(_limitLow_Hard && (_targetStep < _currentStep)) {
+          // Serial.println("youpi");
+          _currentStep = stepper->currentPosition();
+          //stepper->moveTo(_currentStep);
+          //_targetStep = _currentStep;
+          stepper->setSpeed(0);
+        }
+      //else{} // _isHoming ? trigger(EVT_STOP):
       return;
     case ENT_LIMIT_HIGH:
-      push( connectors, ON_ONLIMITHIGH, 0, 1, 0 );
-      if(_limitHigh_Hard && (stepper->speed()>=0)) {trigger(EVT_EMERGENCY_STOP);}
-      else{ stepper_update(); trigger(EVT_MOVE);} //_isHoming ? trigger(EVT_STOP):
-       //  stepper_update();
-       //   switch(_isHoming) {
-       //     case 0 :
-       //      trigger(EVT_MOVE);
-       //      break;
-       //     case 1 :
-       //      trigger(EVT_HOMING_HIGH);
-       //      break;
-       //     case 2 :
-       //      trigger(EVT_HOMING_HIGH);
-       //      break;
-       //   }
-       // }
+      push( connectors, ON_ONLIMITHIGH, 0, limitHigh_State, 0 );
+      if (!limitHigh_State){trigger(EVT_MOVE);};
+      return;
+    case LP_LIMIT_HIGH:
+      //stop motor if going down, allow going up
+      stepper_update();
+      if(_limitHigh_Hard && (_targetStep > _currentStep)) {
+          // Serial.println("youpi");
+          _currentStep = stepper->currentPosition();
+          //stepper->moveTo(_currentStep);
+          //_targetStep = _currentStep;
+          stepper->setSpeed(0);
+        }
+      // else{}
       return;
   }
 }
@@ -256,8 +265,9 @@ int Atm_AccelStepper::state( void ) {
 */
 
 void Atm_AccelStepper::stepper_update(void) {
+
+
   switch (runMode) {
-    Serial.println(stepper->currentPosition());
     case 0: //positional modae
       stepper->run();
       break;
@@ -265,12 +275,14 @@ void Atm_AccelStepper::stepper_update(void) {
       stepper->runSpeed();
       break;
   }
+  // Serial.print("update ");
+  // Serial.println(stepper->speed());
   long int tempStep = stepper->currentPosition();
   if (tempStep != _currentStep){
     _currentStep =  tempStep;
+    //Serial.println(stepper->currentPosition());
     if (position_timer.expired(this)){
       push(connectors, ON_CHANGEPOSITION, 0,  _currentStep, stepper->speed());
-      //Serial.println(stepper->currentPosition());
       position_timer.setFromNow(this, POSITION_SEND_TIMER);
     }
   }

+ 9 - 3
Atm_AccelStepper.h

@@ -73,12 +73,18 @@ class Atm_AccelStepper: public Machine {
   Atm_AccelStepper& limitHigh_setThresholds (int threshold_low=510, int threshold_high = 1024);
   bool limitLow_State;
   bool limitHigh_State;
-
+  bool previous_state = limitLow_State;
 
 
  private:
-  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
+  // 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, LP_LIMIT_LOW, ENT_LIMIT_HIGH, LP_LIMIT_HIGH };
+  // CONNECTORS
+  enum { ON_CHANGEPOSITION, ON_CHANGESTATE, ON_ONLIMITHIGH,
+          ON_ONLIMITLOW, ON_ONTARGET, ON_STOP, CONN_MAX };
   atm_connector connectors[CONN_MAX];
   int event( int id );
   void action( int id );