viorelracoviteanu
Published © GPL3+

Arduino Antenna Controller for Rotators with Stepper Motors

This project aims to control a (home made) rotator or even a PAN-TILT head (for CCTV camera) equipped with stepper motors, with an Arduino.

IntermediateFull instructions provided24 hours8
Arduino Antenna Controller for Rotators with Stepper Motors

Things used in this project

Hardware components

Arduino UNO
Arduino UNO
×1
RGB Backlight LCD - 16x2
Adafruit RGB Backlight LCD - 16x2
×1
Rotary Encoder with Push-Button
Rotary Encoder with Push-Button
×2
TB6600 stepper driver
×2
Limit Switch, 5 A
Limit Switch, 5 A
×4

Software apps and online services

Arduino IDE
Arduino IDE

Hand tools and fabrication machines

Soldering iron (generic)
Soldering iron (generic)
Mastech MS8217 Autorange Digital Multimeter
Digilent Mastech MS8217 Autorange Digital Multimeter

Story

Read more

Schematics

Electric diagram for stepper motors

stepper rotator document

instructions and operating procedures

Code

ARDUINO CONTROLLER FOR STEPPER MOTORS

Arduino
This is the main code. It controls the antenna rotator equipped with stepper motors.
/*  AZ/EL Antenna Rotator controller for Arduino 
 *  STEPPER MOTOR Rotator, without feedback
 *  90 degrees elevation
 *  ========================================================
 *  Uses EasyComm II protocol for computer Tracking Software
 *  Manual command by means of two rotary encoders AZ - EL
 *   
 *  Viorel Racoviteanu
 *  https://www.youtube.com/@racov
 *  https://racov.ro
 *  YO3RAK@gmail.com
 *  
 *  I cannot take any responsibility for missuse of this code
 *  or any kind of damage it may occur from using this code.
 * 
 *  nov 2025 - first release
 */

#include <Wire.h>                     // Library for I2C communication
#include <AccelStepper.h>
// Motor Connections (unipolar motor driver)
/*
const int In1 = 8;
const int In2 = 9;
const int In3 = 10;
const int In4 = 11;
// Motor Connections (constant voltage bipolar H-bridge motor driver)
const int AIn1 = 8;
const int AIn2 = 9;
const int BIn1 = 10;
const int BIn2 = 11;
*/
// Pin Assignment
#define AzSwLo A3                      // safety switch azimuth zero position
#define AzSwHi A2
#define ElSwLo A1                      // safety switch elevation zero position
#define ElSwHi A0
#define AzEncoderPinA 2               // Az encoder right
#define AzEncoderPinB 4               // Az encoder left
#define AzClearButton 5               // Az encoder push
#define ElEncoderPinA 3               // El encoder right
#define ElEncoderPinB 6               // El encoder left
#define ElClearButton 7               // El encoder pus
// Motor Connections (TB6600 constant current, step/direction bipolar motor driver)
#define AzDirPin 9                    // direction pin
#define AzStepPin 8                   // pulse pin
#define AZ_ENA 12                     // enable pin ENA+ (ENA a GND)
#define ElDirPin 11
#define ElStepPin 10
#define EL_ENA 13                     // ENA+ EL  D13 (ENA a GND)

// Creates an instance - Pick the version you want to use and un-comment it. That's the only required change.
//AccelStepper myStepper(AccelStepper::FULL4WIRE, AIn1, AIn2, BIn1, BIn2);  // works for TB6612 (Bipolar, constant voltage, H-Bridge motor driver)
//AccelStepper AzMotor(AccelStepper::FULL4WIRE, In1, In3, In2, In4);        // works for ULN2003 (Unipolar motor driver)
//AccelStepper ElMotor(AccelStepper::FULL4WIRE, 12, 13, A6, A7);            // works for ULN2003 (Unipolar motor driver)
AccelStepper AzMotor(AccelStepper::DRIVER, AzStepPin, AzDirPin);          // works for TB6600, A4988 (Bipolar, constant current, step/direction driver)
AccelStepper ElMotor(AccelStepper::DRIVER, ElStepPin, ElDirPin);

#include <elapsedMillis.h>
elapsedMillis printTime;              // one second info printout timer.

#include <LiquidCrystal_I2C.h> // https://www.arduinolibraries.info/libraries/liquid-crystal-i2-c (Library for LCD)
// Wiring: SDA pin is connected to A4 and SCL pin to A5.
// Connect to LCD via I2C, default address 0x27 (A0-A2 not jumpered)
LiquidCrystal_I2C lcd(0x27, 16, 2);   // address, chars, rows.

// declaring custom symbol for up/down arrow
 byte DownArrow[8] = {
  B00000,
  B00100,
  B00100,
  B00100,
  B10101,
  B01110,
  B00100,
  B00000
};
 byte UpArrow[8] = {
  B00000,
  B00100,
  B01110,
  B10101,
  B00100,
  B00100,
  B00100,
  B00000
};

// ========= PARAMETERS TO MODIFY ACCORDING TO YOUR MOTORS =========
  const long AzPulsPerTurn = 8140;    // azimuth step pulses per 360 (depends on microstep settings and gears)
  const long ElPulsPerTurn = 2050 ;   // elevation step pulses per 90
  const int AzPark = 120;             // azimuth and elevation coordinates
  const int ElPark = 0;               // for antenna parking
  const int Speed = 500;              // speed depends on microstepping
  inline float Accel = 0.8*Speed;     // acceleration smaller than speed. The closer value, the faster it accelerates
// =================================================================
  
// Antenna variables
  float TruAzim = 359;                // real position of the antenna azimuth
  float TruElev = 90;
  int ComAzim = 0;                    // command azimuth, where the antenna should go
  int ComElev = 0;
  int OldComAzim = ComAzim;
  int OldComElev = ComElev;
  long AzMovePuls;                    // absolute positionn of the target (in steps)
  long ElMovePuls;
  inline float AzPulsToDeg = 360.0/AzPulsPerTurn;
  inline float ElPulsToDeg = 90.0/ElPulsPerTurn;
  bool Activ = false;                 // ENABLE pin status -> LOW is ENABLE
  char AzDir;                         // symbol for azim rotation display (arrow left or right)
  bool AzMove = true;
  bool ElMove = true;

// variables for serial comm
  String Azimuth = "";
  String Elevation = "";
  String ComputerRead;
  String ComputerWrite;

// Az encoder variables
  bool AzPush = 0;                    // variable to toggle with encoder push button
  volatile boolean AzEncRot;          // if rotation occured
  volatile boolean AzEncUp;           // direction of rotation
  int increment = 1;                  // degrees to increment at encoder rotation
  
// El encoder variables
  bool ElPush = 0;
  volatile boolean ElEncRot;
  volatile boolean ElEncUp;

//========================== END DECLARATIONS ======================


void setup() {
  // pin declaration
  pinMode(AzEncoderPinA, INPUT_PULLUP);
  pinMode(AzEncoderPinB, INPUT_PULLUP);
  pinMode(AzClearButton, INPUT_PULLUP);
  pinMode(ElEncoderPinA, INPUT_PULLUP);
  pinMode(ElEncoderPinB, INPUT_PULLUP);
  pinMode(ElClearButton, INPUT_PULLUP);
  pinMode(AzSwLo, INPUT_PULLUP);
  pinMode(AzSwHi, INPUT_PULLUP);
  pinMode(ElSwLo, INPUT_PULLUP);
  pinMode(ElSwHi, INPUT_PULLUP);
  pinMode(AZ_ENA, OUTPUT);
  pinMode(EL_ENA, OUTPUT);
// Interrupt Service Routine for Az and El encoder
  attachInterrupt(0, doAzEnc, CHANGE);// Az encoder
  attachInterrupt(1, doElEnc, CHANGE);// El Encoder
// start serial port
  Serial.begin(9600);
  Serial.setTimeout(50);              // miliseconds to wait for USB data (default 1000). That's about 50 characters
// Start the LCD:
  lcd.init();
  lcd.backlight();
// creating custom symbol for up/dwn arrow
  lcd.createChar(1, DownArrow);
  lcd.createChar(2, UpArrow);

// write on display name and version
  lcd.setCursor(0, 0);                // Set the cursor on the first column first row.(counting starts at 0!)
  lcd.print("STEPPER EASYCOMM");
  lcd.setCursor(0, 1);                // Set the cursor on the first column the second row
  lcd.print("YO3RAK  NOV.2025");
  delay(2000);                        // wait 2 seconds

// display fixed text
  lcd.setCursor(0, 0);
  lcd.print("Azm.---" + String(char(223)) + "=Cd.---" + String(char(223)));  // char(223) is degree symbol
  lcd.setCursor(0, 1); 
  lcd.print("Elv. --" + String(char(223)) + "=Cd. --" + String(char(223)));
  DisplValue(round(TruAzim), 4,0);
  DisplValue(ComAzim,12,0);
  DisplValue(round(TruElev), 4,1);
  DisplValue(ComElev,12,1);

// set the maximum speed, acceleration factor
  AzMotor.setMaxSpeed(Speed);
  ElMotor.setMaxSpeed(Speed);
  AzMotor.setAcceleration(Accel);
  ElMotor.setAcceleration(Accel);
  AzMotor.setSpeed(-1*Speed);                 // rotate backwards at boot at constant speed
  ElMotor.setSpeed(-1*Speed);                 // untill it reaches 0 end-stop
// start to move antenna to ZERO at start-up
  AzMotor.setCurrentPosition(AzPulsPerTurn);  // assume antenna is all the way back
  AzMovePuls = 0;                             // set target 0
  ElMotor.setCurrentPosition(ElPulsPerTurn);
  ElMovePuls = 0;
  lcd.setCursor(8, 0);                        // display arrows
  lcd.print(String(char(127)));
  lcd.setCursor(8, 1);
  lcd.write(1);
  AntennaInit();                              // move antenna to zero
}  // end SETUP

/*========================== THE WHOLE CODE TAKES ONLY 16ms TO EXECUTE ======================*/
void loop() {
// read the command from encoder
  ReadAzimEncoder();
  ReadElevEncoder();
// read the command from computer
  if (Serial.available()) {
    SerialCommand();                          // read USB data
  }

// if there is a new target direction
  if (OldComAzim != ComAzim) {
    DisplValue(ComAzim,12,0);                 // display
    OldComAzim = ComAzim;
    AzMovePuls = ComAzim/AzPulsToDeg;         // absolute position in pulses where motor should go
    AzMove = true;                            // prepare movement
    if (ComAzim > TruAzim) {AzDir = char(126);}   // "->"
    else {AzDir = char(127);}                     // "<-"
    lcd.setCursor(8, 0);
    lcd.print(String(AzDir));
  }
  if (OldComElev != ComElev) {
    DisplValue(ComElev,12,1);
    OldComElev = ComElev;
    ElMovePuls = ComElev/ElPulsToDeg;
    ElMove = true;
    if (ComElev > TruElev) {
      lcd.setCursor(8, 1);
      lcd.write(2);                           // arrow up
    }
    else {
      lcd.setCursor(8, 1);
      lcd.write(1);                           // arrow dn
    }
  }
// move the antenna
  if (AzMove || ElMove){                      // if need to move in Azim. OR Elev.
    AntennaMove();
  }
}   // end main LOOP

/**************************************************************************************/
/* =============================== FUNCTION DEFINITIONS ============================= */
/**************************************************************************************/

// _________________ Moving ANTENNA to zero at STARTUP ______________________
void AntennaInit() {
  while (AzMove || ElMove) {                    // as long as we are moving in AZ or EL
    if (printTime >= 1000) {                    // every second
          printTime = 0;
          TruAzim = AzMotor.currentPosition()*AzPulsToDeg;  // calculate antenna position
          TruElev = ElMotor.currentPosition()*ElPulsToDeg;
          DisplValue(round(TruAzim), 4,0);                  // display antenna position
          DisplValue(round(TruElev), 4,1);
          if (Serial.available()) {SerialRequest();}        // read USB to send back the coordinates if asked
        }
    if (AzMove){
      digitalWrite(AZ_ENA, Activ);              // enable the driver
      AzMotor.moveTo(AzMovePuls);               // this set target coordinates
      AzMotor.runSpeed();                       // motor move to target at constant speed (once it reached the target, stops automatically)
      ReadAzSw();                               // verify safety switches
      if (!AzMotor.run()){                      // if motor not move (reached the target)
        AzMove = false;
        digitalWrite(AZ_ENA, !Activ);           // disable the driver
        TruAzim = AzMotor.currentPosition()*AzPulsToDeg;    // final position
        DisplValue(round(TruAzim), 4,0);
        lcd.setCursor(8, 0);
        lcd.print("=");
      }
    }

    if (ElMove){
      digitalWrite(EL_ENA, Activ);
      ElMotor.moveTo(ElMovePuls);
      ElMotor.runSpeed();
      ReadElSw();
      if (!ElMotor.run()){
        ElMove = false;
        digitalWrite(EL_ENA, !Activ);
        TruElev = ElMotor.currentPosition()*ElPulsToDeg;
        DisplValue(round(TruElev), 4,1);
        lcd.setCursor(8, 1);
        lcd.print("=");
      }
    }
  }
} // end AntennaInit()

// _________________ START A MOVE ______________________
void AntennaMove() {
  while (AzMove || ElMove) {                    // as long as we are moving in AZ or EL
    if (printTime >= 1000) {                    // every second
          printTime = 0;
          TruAzim = AzMotor.currentPosition()*AzPulsToDeg;  // calculate antenna position
          TruElev = ElMotor.currentPosition()*ElPulsToDeg;
          DisplValue(round(TruAzim), 4,0);                  // display antenna position
          DisplValue(round(TruElev), 4,1);
          if (Serial.available()) {SerialRequest();}        // read USB to send back the coordinates if asked
        }
    if (AzMove){
      digitalWrite(AZ_ENA, Activ);              // enable the driver
      AzMotor.moveTo(AzMovePuls);               // this set target coordinates
      AzMotor.run();                            // this makes motor move to the target (once it reached the target, stops automatically)
      ReadAzSw();                               // verify safety switches
      if (!AzMotor.run()){                      // if motor not move (reached the target)
        AzMove = false;
        digitalWrite(AZ_ENA, !Activ);           // disable the driver
        TruAzim = AzMotor.currentPosition()*AzPulsToDeg;    // final position
        DisplValue(round(TruAzim), 4,0);
        lcd.setCursor(8, 0);
        lcd.print("=");
      }
    }

    if (ElMove){
      digitalWrite(EL_ENA, Activ);
      ElMotor.moveTo(ElMovePuls);
      ElMotor.run();
      ReadElSw();
      if (!ElMotor.run()){
        ElMove = false;
        digitalWrite(EL_ENA, !Activ);
        TruElev = ElMotor.currentPosition()*ElPulsToDeg;
        DisplValue(round(TruElev), 4,1);
        lcd.setCursor(8, 1);
        lcd.print("=");
      }
    }
  }
} // end AntennaMove()

void DisplValue(int x, int y, int z) {
  char displayString[17] = "";
  sprintf(displayString, "%3d", x);         // outputs a fixed lenght number (3 integer)
  lcd.setCursor(y, z);                      // for leading zeros '007' use "%03d"
  lcd.print(displayString);
}  // end DisplValue()

// Interrupt Service Routine for a change to encoder pin A and B
void doAzEnc () {
  if (digitalRead (AzEncoderPinA))
    AzEncUp = digitalRead (AzEncoderPinB);
  else
    AzEncUp = !digitalRead (AzEncoderPinB);
    AzEncRot = true;
}  // end doAzEnc

void doElEnc () {
  if (digitalRead (ElEncoderPinA))
    ElEncUp = digitalRead (ElEncoderPinB);
  else
    ElEncUp = !digitalRead (ElEncoderPinB);
    ElEncRot = true;
}  // end doElEnc

void ReadAzimEncoder() {
  if (digitalRead(AzClearButton) == LOW ) {       // if encoder switch depressed
    AzPush = true;                                // we have a manual input
// refresh all the writings on the screen with "*" symbol
    lcd.setCursor(0, 0);
    lcd.print("Azm.   " + String(char(223)) + "*Cd.   " + String(char(223)));  // char(223) is degree symbol
    lcd.setCursor(0, 1); 
    lcd.print("Elv.   " + String(char(223)) + "=Cd.   " + String(char(223)));
    DisplValue(round(TruAzim), 4,0);
    DisplValue(ComAzim,12,0);
    DisplValue(round(TruElev), 4,1);
    DisplValue(ComElev,12,1);
    delay(500);                                   // debounce
  }
  while (AzPush){
// read AZ encoder rotation
    if (AzEncRot){
      delay(20);                                  // debouncing
      if (AzEncUp) ComAzim += increment;
      else ComAzim -= increment;
      ComAzim = ((ComAzim + 360) % 360);          // Az Cmd between 0 and 359 deg continuous
      ComAzim = constrain (ComAzim, 0, 359);
      AzEncRot = false;
      DisplValue(ComAzim,12,0);
    }
// read EL encoder rotation
    if (ElEncRot){
      delay(20);
      if (ElEncUp) ComElev += increment;
      else ComElev -= increment;
      ElEncRot = false;
      ComElev = constrain(ComElev, 0, 90);         // keep El Cmd value in range
      DisplValue(ComElev,12,1);
    }
    if (digitalRead(AzClearButton) == LOW ) {       // if encoder switch depressed
      AzPush = false;                               // we exit manual input
      lcd.setCursor(8, 0);
      lcd.print("-");
      delay(500);   
    }
  }
} //end ReadAzimEncoder()

void ReadElevEncoder() {
  if (digitalRead(ElClearButton) == LOW ) {       // set Park Position Command Az/El
    ComAzim = AzPark;                             // set parking position
    ComElev = ElPark;
    DisplValue(ComAzim,12,0);
    DisplValue(ComElev,12,1);
    lcd.setCursor(8, 1);
    lcd.print("%");                               // display P symbol for parking
    delay (2000);
  }
}  // end ReadElevEncoder()

//____________________VERIFY SAFETY SWITCHES____________________
void ReadAzSw() {
  bool a = digitalRead(AzSwLo);
  if (!a) {                                       // the antenna hit zero position
    AzMotor.setCurrentPosition(0);
    TruAzim = 0;
// if the antenna was offset and the switch was hit unexpectedly,
// this will send the antenna back to target
    OldComAzim = 0;
    lcd.setCursor(7, 0);
    lcd.print(String(char(223)));
  }
  bool b = digitalRead(AzSwHi);
  if (!b) {                                       // the antenna hit full turn
    AzMotor.setCurrentPosition(AzPulsPerTurn);
    TruAzim = 359;
    OldComAzim = 359;
    lcd.setCursor(7, 0);
    lcd.print(String(char(223)));
  }
} // end ReadAzSw()
void ReadElSw() {
  bool a = digitalRead(ElSwLo);
  if (!a) {
    ElMotor.setCurrentPosition(0);
    TruElev = 0;
    OldComElev = 0;
    lcd.setCursor(7, 1);
    lcd.print(String(char(223)));
  }
  bool b = digitalRead(ElSwHi);
  if (!b) {
    ElMotor.setCurrentPosition(ElPulsPerTurn);
    TruElev = 90;
    OldComElev = 90;
    lcd.setCursor(7, 1);
    lcd.print(String(char(223)));
  }
} // end ReadElSw()

//________ SERIAL  COMMUNICATION - receiving a command and answering a position Request ________
void SerialCommand() {
  // initialize readings
  ComputerRead = "";
  Azimuth = "";
  Elevation = "";

  while(Serial.available()) {
    ComputerRead= Serial.readString();           // read the incoming data as string
//    Serial.println(ComputerRead);              // echo the reception for testing purposes
  }
  
// looking for command <AZxxx.x>
    for (int i = 0; i <= ComputerRead.length(); i++) {
     if ((ComputerRead.charAt(i) == 'A')&&(ComputerRead.charAt(i+1) == 'Z')){ // if read AZ
      for (int j = i+2; j <= ComputerRead.length(); j++) {
        if (isDigit(ComputerRead.charAt(j))) {                                // if the character is number
          Azimuth = Azimuth + ComputerRead.charAt(j);
        }
        else {break;}
      }
     }
    }
    
// looking for command <ELxxx.x>
    for (int i = 0; i <= (ComputerRead.length()-2); i++) {
      if ((ComputerRead.charAt(i) == 'E')&&(ComputerRead.charAt(i+1) == 'L')){ // if read EL
        if ((ComputerRead.charAt(i+2)) == '-') {                               // if received elevation negative
          ComElev = 0;                                                         // keep antenna to zero
          break;
        }
        for (int j = i+2; j <= ComputerRead.length(); j++) {
          if (isDigit(ComputerRead.charAt(j))) {                               // if the character is number
            Elevation = Elevation + ComputerRead.charAt(j);
          }
          else {break;}
        }
      }
    }
    
// if <AZxx> received
    if (Azimuth != ""){
      ComAzim = Azimuth.toInt();
      ComAzim = constrain(ComAzim, 0, 359); // keeping values in range
    }

// if <ELxx> received
    if (Elevation != ""){
      ComElev = Elevation.toInt();
      ComElev = constrain(ComElev, 0, 90); // we won't tolerate no funny elevation values 
    }
    
// looking for <AZ EL> interogation for antenna position
  for (int i = 0; i <= (ComputerRead.length()-4); i++) {
    if ((ComputerRead.charAt(i) == 'A')&&(ComputerRead.charAt(i+1) == 'Z')&&(ComputerRead.charAt(i+3) == 'E')&&(ComputerRead.charAt(i+4) == 'L')){
    // send back the antenna position <+xxx.x xx.x>
      ComputerWrite = "+"+String(round(TruAzim))+".0 "+String(round(TruElev))+".0";
 //ComputerWrite = "AZ"+String(TruAzim)+".0 EL"+String(TruElev)+".0"; //that's for Gpredict and HamLib
      Serial.println(ComputerWrite);
    }
  }
}  // end SerialCommand()

//________ SERIAL  COMMUNICATION - answering a position Request ________
void SerialRequest() {
  ComputerRead = "";
  while(Serial.available()) {ComputerRead = Serial.readString();}     // read the incoming data as string
// looking for <AZ EL> interogation for antenna position
  for (int i = 0; i <= (ComputerRead.length()-4); i++) {
    if ((ComputerRead.charAt(i) == 'A')&&(ComputerRead.charAt(i+1) == 'Z')&&(ComputerRead.charAt(i+3) == 'E')&&(ComputerRead.charAt(i+4) == 'L')){
    // send back the antenna position <+xxx.x xx.x>
      ComputerWrite = "+"+String(round(TruAzim))+".0 "+String(round(TruElev))+".0";
//ComputerWrite = "AZ"+String(TruAzim)+".0 EL"+String(TruElev)+".0"; //that's for Gpredict and HamLib
      Serial.println(ComputerWrite);
    }
  }
}  // end SerialRequest()

step-count.ino

Arduino
This sketch comes in support of the main software. It counts the steps the motor does for a full turn between the end-switches.
/*  This program counts the steps of a stepper motor
 *  between two limit switches
 *  and prints the result on a LCD
 *  ========================================================
 *  It comes to supplement the main software
 *  which is an Antenna Tracker Controller with Stepper Motors
 *   
 *  Viorel Racoviteanu
 *  https://www.youtube.com/@racov
 *  https://racov.ro
 *  YO3RAK@gmail.com
 *  
 *  I cannot take any responsibility for missuse of this code
 *  or any kind of damage it may occur from using this code.
 * 
 *  nov 2025 - first release
 */

#include <LiquidCrystal_I2C.h>
// Wiring: SDA pin is connected to A4 and SCL pin to A5.
// Connect to LCD via I2C, default address 0x27 (A0-A2 not jumpered)
LiquidCrystal_I2C lcd(0x27, 16, 2);   // create a LCD object
#include <Wire.h> // Library for I2C communication
#include <AccelStepper.h>

// Limit switch pins
#define AzSwLo A3                      // safety switch azimuth zero position
#define AzSwHi A2
#define ElSwLo A1                      // safety switch elevation zero position
#define ElSwHi A0

// Motor Connections (TB6600 constant current, step/direction bipolar motor driver)
#define AzDirPin 9                    // direction pin
#define AzStepPin 8                   // pulse pin
#define AZ_ENA 12                     // enable pin ENA+ (ENA a GND)
#define ElDirPin 11
#define ElStepPin 10
#define EL_ENA 13

// Stepper setup (change pins and driver type as needed)
// Motor Connections (unipolar motor driver)
/*AccelStepper AzStepper(AccelStepper::FULL4WIRE, In1, In3, In2, In4);  // create a motor object
AccelStepper ElStepper(AccelStepper::FULL4WIRE, In1, In3, In2, In4);*/
AccelStepper AzStepper(AccelStepper::DRIVER, AzStepPin, AzDirPin);
AccelStepper ElStepper(AccelStepper::DRIVER, ElStepPin, ElDirPin);

long startPosition = 0;
long endPosition = 0;
int Speed = 1000;
bool AzReachedFirst = false;
bool AzReachedSecond = false;
bool ElReachedFirst = false;
bool ElReachedSecond = false;
bool Activ = false;

void setup() {
  Serial.begin(9600);
  Serial.println("counting steps...");
  lcd.init();
  lcd.backlight();
  pinMode(AzSwLo, INPUT_PULLUP);  // active LOW
  pinMode(AzSwHi, INPUT_PULLUP);
  pinMode(ElSwLo, INPUT_PULLUP);  // active LOW
  pinMode(ElSwHi, INPUT_PULLUP);
  pinMode(AZ_ENA, OUTPUT);
  pinMode(EL_ENA, OUTPUT);
  digitalWrite(AZ_ENA, Activ);
  digitalWrite(EL_ENA, Activ);
//  AzStepper.setMinPulseWidth(5);
//  ElStepper.setMinPulseWidth(5);
  AzStepper.setMaxSpeed(2000);
  AzStepper.setSpeed(-1*Speed);     // rotate backwards
  ElStepper.setMaxSpeed(2000);
  ElStepper.setSpeed(-1*Speed);
}

void loop() {
// AZIMUTH step count
  AzStepper.runSpeed();
  lcd.setCursor(0, 0);
  lcd.print("Az-");
  // Check first limit
  if (!digitalRead(AzSwLo) && !AzReachedFirst) {
    startPosition = AzStepper.currentPosition();
    AzReachedFirst = true;
    Serial.print("Az_Low...");
    lcd.setCursor(3, 0);
    lcd.print("L1-");
    delay(500);
    AzStepper.setSpeed(Speed);       // rotate forward
  }
  // Check second limit
  if (!digitalRead(AzSwHi) && !AzReachedSecond && AzReachedFirst) {
    AzStepper.stop();
    endPosition = AzStepper.currentPosition();
    AzReachedSecond = true;
    Serial.print("Az_Hi -> ");
    lcd.setCursor(6, 0);
    lcd.print("L2-");
    long stepsTravelled = abs(endPosition - startPosition);
    Serial.println(stepsTravelled);
    lcd.print(stepsTravelled);
    AzStepper.setSpeed(0);
    digitalWrite(AZ_ENA, !Activ);
    delay(500);
  }
// ELEVATION step count
  ElStepper.runSpeed();
  lcd.setCursor(0, 1);
  lcd.print("El-");
  // Check first limit
  if (!digitalRead(ElSwLo) && !ElReachedFirst) {
    startPosition = ElStepper.currentPosition();
    ElReachedFirst = true;
    Serial.print("El_Low...");
    lcd.setCursor(3, 1);
    lcd.print("L1-");
    delay(500);
    ElStepper.setSpeed(Speed);
  }
  // Check second limit
  if (!digitalRead(ElSwHi) && !ElReachedSecond && ElReachedFirst) {
    ElStepper.stop();
    endPosition = ElStepper.currentPosition();
    ElReachedSecond = true;
    Serial.print("El_Hi -> ");
    lcd.setCursor(6, 1);
    lcd.print("L2-");
    long stepsTravelled = abs(endPosition - startPosition);
    Serial.println(stepsTravelled);
    lcd.print(stepsTravelled);
    ElStepper.setSpeed(0);
    digitalWrite(EL_ENA, !Activ);
  }
}

Credits

viorelracoviteanu
6 projects • 59 followers

Comments