/* SMC02 Stepper Motor Controller
  This is an attempt at providig the functionality of the
  SMC02 Stepper Motor Controller

  https://m.media-amazon.com/images/I/91s+3NPuv1L.pdf
  https://attach01.oss-us-west-1.aliyuncs.com/IC/Datasheet/GY20512.pdf

  The Serial port communication doesn't seem well documented.
  Here's a reference that says MODBUS 0x3 0x6, 0x10 on the registers
  https://www.landaelectronic.com/wp-content/uploads/2024/09/SMC02.pdf
  Perhaps: https://github.com/CMB27/ModbusRTUSlave

  Video running through the modes:
  https://www.youtube.com/watch?v=w4IOMUTZa48

  Some code for talking modbus:
  https://gitlab.com/OneGeekGuy/arduino-zksmc01-control/-/blob/main/main.cpp

  It has these parts:

  LCD 16x2
  3 buttons CW, CCW, Start/stop
  1 encoder w/switch function setting/speed
  2 LEDs CW, CCW

*/

////////// Example Reference for MoToStepper - attaching a bipolar stepper with step/dir and enable ////////////
// https://github.com/MicroBahner/MobaTools/blob/master/examples/_Stepper/Stepper_Reference/Stepper_Reference.ino
// https://wokwi.com/projects/410122241449166849
// for https://forum.arduino.cc/t/wokwi-simulations-for-arduino-built-in-examples/1304754/6


/*  Beispiel für die Ansteuerung eines bipolaren Steppers
   über 4 Taster und ein Poti ( für die Geschwindigkeit )
   In diesem Beispiel werden neben der Stepperklasse (MoToStepper), auch die MoToButtons
   und der MoToTimebase genutzt.
   Jedem Taster ist eine Position zugeordnet, die bei einem Klick auf den Taster
   angefahren wird.
   Ein Doppelklick führt zu endlosen Bewegungen:
        CWsw: vorwärts
        CCWsw  rückwärts
        Taster3  stop

   Wird Taster4 lang gedrückt, wird eine Referenzfahrt ausgelöst.
   In diesem Beispiel ist die Referenzfahrt als einfache blockierende Funktion ausgeführt.

   Die interne LED wird angesteuert, wenn der Referenzschalter aktiv ist.
*/
/* Example for the control of a bipolar stepper with 4 buttons and a potentiometer (for speed)
   In this example, besides the stepper class (MoToStepper), also the MoToButtons and the MoToTimebase are used.
   A position is assigned to each button, which is approached when the stepper is clicked.
   A double click leads to endless movements:
        Button1: forward
        Button2: backward
        Button3: stop

   If button4 is pressed and held down, a reference run is initiated.
   In this example, the reference run is a simple blocking function.

   The internal LED lights up when the reference switch is active.
*/

#include <Encoder.h> // https://github.com/PaulStoffregen/Encoder 
#include <Wire.h> // https://docs.arduino.cc/language-reference/en/functions/communication/Wire/ for lcd
#include <hd44780.h> // https://github.com/duinoWitchery/hd44780 
#include <hd44780ioClass/hd44780_I2Cexp.h> // i2c expander i/o class header
#include <MobaTools.h> // https://github.com/MicroBahner/MobaTools

#define MAX8BUTTONS // spart Speicher, da nur 4 Taster benötigt werden
const int STEPS_UMDREHUNG = 180;
//Stepper einrichten ( 800 Schritte / Umdrehung - 1/4 Microstep )
MoToStepper myStepper( STEPS_UMDREHUNG, STEPDIR );
const byte dirPin = 7;
const byte stepPin = 8;
const byte enaPin = 9;
const byte cwLed = 11;
const byte ccwLed = 12;
const byte encAPin = 3;
const byte encBPin =2;

// Taster einrichten ( die Taster müssen gegen Gnd schalten, keine Widerstände notwendig )
enum { CWsw, CCWsw, StopStartSw, EncSw } ; // Den Tasternamen die Indizes zuordnen
const byte tasterPins[] = {A1, A2, A3, 4 }; // muss als byte definiert sein, damit ein enfaches sizeof funktioniert
const byte tasterZahl = sizeof(tasterPins);
const long tasterPos[] = { 1600, 3200, 6400 };
MoToButtons taster( tasterPins, tasterZahl, 20, 500 );

hd44780_I2Cexp lcd; // declare lcd object: auto locate & auto config expander chip
Encoder enc(encAPin, encBPin);

long currentEnc, oldEnc;

MoToTimebase speedIntervall;      // Zeitinterval zum Auslesen des Speedpotentiometers
enum Params {NullParam, WorkingMode, ForwardPulse, ForwardRPM,
             ReversePulse, ReverseRPM, Cycles, ForwardDelay, ReverseDelay, LCDmode,
             SlowStop, Accel, Address
            };
struct Parameters {
  const int8_t Fid;
  const char* name;
  uint32_t value;
  uint32_t low;
  uint32_t high;
  int8_t divisor;
} parameters[] = {
  {0, "NullParam", 0, 0, 0, 0},
  {1, "WorkingMode", 1, 1, 6, 1},
  {2, "ForwardPulse", 180, 1, 9999999, 1},
  {3, "ForwardRPM", 100, 1, 9999, 10},
  {4, "ReversePulse", 1600, 1, 9999999, 1},
  {5, "ReverseRPM", 100, 1, 9999, 10},
  {6, "Cycles", 1, -1, 9999, 1},
  {7, "ForwardDelay", 10, 0, 9999, 10},  // seconds/10
  {8, "ReverseDelay", 0, 0, 9999, 10},
  {9, "PulsePerRev", 180, 1, 9999, 1},
  {10, "LCDmode", 0, 0, 1, 1},
  {11, "Slow/Stop", 0, 0, 1, 1},
  {12, "Accel", 20, 1, 100, 1},
  {13, "Address", 1, 1, 255, 1},
};

int parameterIndex;
int parameterState;
enum DirectionEnum {CW,CCW} direction = CW;

enum WORKMODES {NullMode, KnobControl, MomentaryRPM, OnOffRPM, LoopOneDirRet, LoopBothDir,
                LoopFRRF, MomentaryReturn, LoopOneDir, AutoLoop
               } workmode = KnobControl;
struct WorkMode {
  uint8_t Mid;
  const char* name;
} workModes[] {
  {NullMode, "Null"},
  {KnobControl, "Knob"}, // motor turns with knob
  {2, "MomentaryRPM"}, // motor turns while CW or CCW pressed
  {3, "OnOffRPM"}, // motor start/stops when CW or CCW is pressed
  {4, "LoopOneDirRet"}, // keep going one dir in steps/delay & return to start
  {5, "LoopBothDir"}, // alternate dir steps+delay
  {6, "LoopFRRF"},
  {7, "MomentaryReturn"}, // momentary CW or CCW, autoreturn
  {8, "LoopOneDir"}, //
  {9, "AutoLoop"}, // alternate motion, no button needed
};

const int NumWorkModes = sizeof(workModes) / sizeof(workModes[0]);
const int NumParameters = sizeof(parameters) / sizeof(parameters[0]);

bool working = true; // Working or notParameterSettingMode
int parameter;
int menuLevel;

bool dirty = true;
uint32_t currentMillis = 0;
uint16_t loopCounter = 0;

const byte potiPin = A0;        //Poti fuer Geschwindigkeit
int vspeed = 0;                 //Steppergeschwindigkeit in U/min*10
int oldSpeed = 0;               // Zur Erkennung von Geschwindigkeitsänderungen

long initialPosition;  // for return-to-start modes
int modeState = 0; // for tracking progress in complex states;

void handleParameterMode() {
  if (taster.longPress(EncSw)) {  // Exit on long press
    working = true;
    workmode = parameters[WorkingMode].value ;
    dirty = true;
    initialPosition = myStepper.currentPosition();
    modeState = 0;
  }
  else if (menuLevel == 0) {
    {
      if (taster.shortPress(EncSw)) {
        menuLevel++;
        dirty = true;
      }
      if (currentEnc != oldEnc) {
        if (currentEnc > oldEnc) {
          if (parameter < NumParameters - 1) ++parameter;
        } else {
          if (parameter > WorkingMode ) --parameter;
        }
        oldEnc = currentEnc;
        dirty = true;
      }
    }
  }
  else // edit values
  {
    if (taster.shortPress(EncSw)) {
      menuLevel++;
      if (menuLevel > 1) menuLevel = 0;
      dirty = true;
    }
    if (currentEnc != oldEnc) {
      if (currentEnc > oldEnc) {
        if (parameters[parameter].value < parameters[parameter].high) {
          ++parameters[parameter].value;
        }
      } else {
        if (parameters[parameter].value > parameters[parameter].low) {
          --parameters[parameter].value;
        }
      }
      oldEnc = currentEnc;
      dirty = true;
    }
    switch (parameter) {
      case NullParam:
        break;
      case 1:
        break;
      default:
        ;
    }
  }
}

void updateLeds(){
}

void updateDisplay() {
  const uint32_t interval = 100;
  static uint32_t last = -interval;
  if (dirty || currentMillis - last >= interval) {
    last = currentMillis;
    if (working) {
      lcd.setCursor(0, 0);
      lcd.print("W");
      lcd.print(parameters[WorkingMode].value);
      lcd.print("  ");
      lcd.print(myStepper.getSpeedSteps() * 6 / 180.0);
      lcd.print("/");
      lcd.print(parameters[ForwardRPM].value / 10.0, 1);
      lcd.print("   ");
      lcd.setCursor(0, 1);
      lcd.print(workModes[workmode].name);
      lcd.print("      ");
      lcd.noBlink();
    } else { // Parameter mode
      if (dirty) {
        lcd.clear();
        lcd.setCursor(0, 0);
        lcd.print("F");
        lcd.print(parameters[parameter].Fid);
        lcd.print(":");
        lcd.print(parameters[parameter].value);
        lcd.print(" ");
        if (parameter == WorkingMode) {
          lcd.print(workModes[parameters[parameter].value].name);
        }
        lcd.setCursor(0, 1);
        lcd.print(parameters[parameter].name);
        lcd.print("       ");
        lcd.setCursor(menuLevel == 0 ? 1 : 4, 0);
        lcd.blink();
      }
    }
  }
  dirty = false;
}

void report() {
  const uint32_t interval = 1000;
  static uint32_t last = -interval;
  if (currentMillis - last >= interval) {
    last += interval;
    char buff[80];
    snprintf(buff, 79, "Working:%hd F%d:%s P%d:%s %d %d, sm: %d loops:%u\n",
             working, workmode, workModes[workmode].name,
             parameter, (parameters[parameter]).Fid,parameters[parameter].name,
             parameters[parameter].value, modeState, loopCounter );
    Serial.print(buff);

  }
}


void doKnobMotion() {
  if (currentEnc != oldEnc) {
    if ( currentEnc > oldEnc) {
      myStepper.move(1);
    }
    else
    {
      myStepper.move(-1);
    }
    oldEnc = currentEnc;
    dirty = true;
  }
}

void doMomentaryRPMMotion() {
  const int pIx = ForwardRPM;
  //Serial.print("xxRPm");
  if (taster.state(CWsw)) {
    myStepper.rotate(1);
  }
  if (taster.pressed(CCWsw)) {
    myStepper.rotate(-1);
  }
  if (taster.released(CWsw)) {
    myStepper.rotate(0);
  }
  if (taster.released(CCWsw)) {
    myStepper.rotate(0);
  }
  if (currentEnc != oldEnc) {
    if ( currentEnc > oldEnc) {
      if (parameters[pIx].value < parameters[pIx].high) {
        parameters[pIx].value++;
      }
    }
    else
    {
      if (parameters[pIx].value > parameters[pIx].low) {
        parameters[pIx].value--;
      }
    }
    oldEnc = currentEnc;
    myStepper.setSpeed(parameters[pIx].value);
  }
}

void doOnOffRPMMotion() {
  const int pIx = ForwardRPM;
  static int running = false;
  //Serial.print("xxRPm");
  if (taster.pressed(CWsw)) {
    if (running) {
      myStepper.rotate(0);
      running = false;
    } else {
      myStepper.rotate(1);
      myStepper.setSpeed(parameters[ForwardRPM].value);
      running = true;
    }
  }
  if (taster.pressed(CCWsw)) {
    if (running) {
      myStepper.rotate(0);
      running = false;
    } else {
      myStepper.rotate(-1);
      myStepper.setSpeed(parameters[ReverseRPM].value);
      running = true;
    }
  }
  if (currentEnc != oldEnc) {
    if ( currentEnc > oldEnc) {
      if (parameters[pIx].value < parameters[pIx].high) {
        parameters[pIx].value++;
      }
    }
    else
    {
      if (parameters[pIx].value > parameters[pIx].low) {
        parameters[pIx].value--;
      }
    }
    oldEnc = currentEnc;
    myStepper.setSpeed(parameters[pIx].value);
  }
};

void doLoopOneDirRetMotion() {
  static bool running = false;
  static int dir = 0;
  static uint32_t stepMillis, delayTime;
  static long stepAmount;
  if (modeState == 0) { // initialize
    //modeState = 0;
    //loopCounter = parameters[];
    ;
  }
  if (taster.pressed(CWsw)) {
    if (running) {
      myStepper.rotate(0);
      running = false;
    } else {
      initialPosition = myStepper.currentPosition();
      dir = 1 ; // CW
      loopCounter = parameters[Cycles].value; 
      stepAmount = parameters[ForwardPulse].value;
      delayTime = parameters[ForwardDelay].value * 100UL; // millis
      myStepper.move(stepAmount);
      myStepper.setSpeed(parameters[ForwardRPM].value);
      running = true;
      char buff[50];
      snprintf(buff,49,"CW %dX step %ld delay %lu",loopCounter, stepAmount, delayTime );
      Serial.println(buff);
      modeState = 1;
    }
  }
  if (taster.pressed(CCWsw)) {
    Serial.print("XXX not done");
  }
  // operate
  switch (modeState) {
    case 0: ; break;
    case 1: // rotating
      if (myStepper.stepsToDo() == 0) {
        stepMillis = currentMillis;
        modeState = 2;
      }
      break;
    case 2:
      if (currentMillis - stepMillis >= delayTime ) {
        --loopCounter;
        if (loopCounter > 0 ) {
          modeState = 1;
          myStepper.move(stepAmount);
        }
        else // out of loops, return
        {
          myStepper.moveTo(initialPosition);
          modeState = 3;
        }
      }
      break;
    case 3:
      if (myStepper.stepsToDo() == 0 ) {
        Serial.println("XXX ms3 all done");
        modeState = 0;
        running = false;
      }
      break;
    default:
      Serial.print("XXX unknown modeState");
  }
};
void doLoopBothDirMotion() {};
void doLoopFRRFMotion() {};
void doMomentaryReturnMotion() {};
void doLoopOnDirMotion() {};
void doAutoLoopMotion() {};

void handleWorkingMode() {
  switch (workmode) {
    case KnobControl: doKnobMotion(); break;
    case MomentaryRPM: doMomentaryRPMMotion() ; break;
    case OnOffRPM: doOnOffRPMMotion() ; break;
    case LoopOneDirRet: doLoopOneDirRetMotion() ; break;
    case LoopBothDir: doLoopBothDirMotion() ; break;
    case LoopFRRF: doLoopFRRFMotion() ; break;
    case MomentaryReturn: doMomentaryReturnMotion() ; break;
    case LoopOneDir: doLoopOnDirMotion() ; break;
    case AutoLoop: doAutoLoopMotion() ; break;
    default:
      Serial.print("Unknown/unimplemented workmode\n");
  }
  if (taster.longPress(EncSw)) {
    myStepper.stop();
    working = false;
    dirty = true;
  }
}

void setup()
{ Serial.begin(115200); while (!Serial);
  myStepper.attach( stepPin, dirPin );
  myStepper.attachEnable( enaPin, 10, LOW );        // Enable Pin aktivieren ( LOW=aktiv )
  myStepper.setSpeed( 200 );
  vspeed = 200;
  myStepper.setRampLen( 100 );                       // Rampenlänge 100 Steps bei 20U/min
  speedIntervall.setBasetime( 100 );                  // 100ms Tickerzeit
  pinMode(LED_BUILTIN, OUTPUT);
  lcd.begin(16, 2);

  //workmode = MomentaryRPM;
workmode = LoopOneDirRet;

  parameters[WorkingMode].value = workmode;
  parameter = WorkingMode;
  menuLevel = 0;
  myStepper.setSpeed(parameters[ForwardRPM].value);
  initialPosition = myStepper.currentPosition();
}

void loop() {
  currentMillis = millis();
  taster.processButtons();          // Taster einlesen und bearbeiten
  currentEnc = enc.read() / 4; // one inc per detent

  // Speed alle 100ms neu einlesen und setzen
  if ( speedIntervall.tick() ) {
    ;
  }

  if (working == true) {
    handleWorkingMode();
  }
  else // parameter setting mode
  {
    handleParameterMode();
  }
  updateDisplay();
  report();
}
A4988
CW
CCW
Start/Stop
Adjust/Set