Solartracker.ino



/*
  Sonnenstandberechnung und Solartracking,
  jetzt mit Arduino-Motor-Shield Rev3.
  und Nextion 5.0-Zoll-touch-Display.
  Läuft nicht auf dem Arduino-UNO. Wg. erhöhtem Speicherbedarf ist ein Arduino Mega erforderlich.
  Positionsangaben für Ort: Rönkhausen.
  Version 4.3, M. Schulte, 01. Oktober 2023.
  Achtung: Vin max. 7.5 Volt. Höhere Eingangsspannungen können zu Fehlfunktionen führen.
  Neu: LED-Ampel: rote LED = rückwärts, grüne LED = vorwärts, gelb = Zielposition, gelb blinkend = schneller Rückwärtslauf.
  Änderung: diverse Anpassungen, u.a.Definition Sonnenuntergang (Elevation <= -2).
  Änderung: neue Variablen: mvOst, mvSued, mvWest.
  Grenzwerte neu angepasst; auf Data-Seite "GW" hinzugefügt.
  15.08.23, Azimut-Ist (azimutHall): map-Funktionen neu kalbriert (Ost 258, Süd 510, West 768).
  Änderung: Ausgabe Data: Hall-Sensor Pin A2 statt Zeitgleichung
  Änderung: Longruner Servo gegen neuen 35 kg Servo ausgetauscht, Servo neu kalibriert
  2. Ampel eingebaut
  Temperatur von DS3231 hinzugefügt
  Zeitwerte nun mit RTClib.h, diverse Anpassungen
*/

#include "RTClib.h"                                // für die Zeitsteuerung
#include <DTutils.h>                               // Für DayOfYear-Funktion
#include <Servo.h>                                 // Include the Servo library
#include <Stepper.h>                               // Include the Stepper library

RTC_DS3231 rtc;                                    // DS3231 ist RealTimeClock
Servo servo;                                       // Servomotor für Elevation

#define pwmA 3                                     // stepper motor control pins
#define pwmB 11
#define dirA 12
#define dirB 13

const int stepsPerRevolution = 200;                // Define number of stepper steps per revolution
const int stepsV = 16;                             // Anzahl steps Vorwärtslauf,       ca. +0.5°
const int stepsR = -16;                            // Anzahl steps Rückwärtslauf,      ca. -0.5°
const int stepsSR = -200;                          // Anzahl steps Schneller Rücklauf, ca. -6°
float Deklination, Dekl;
char buffer[80];                                   // buffer für DateTime-Display-Ausgabe

Stepper myStepper = Stepper(stepsPerRevolution, dirA, dirB); // Initialize the stepper library on the motor shield

// Kalibrierung Hall-Sensor, Digitalwerte an Pin A2 bei Ost-, Süd- und Westrichtung

const int mvOst = 258;                             // OST,  15.08.23, neu kalibriert
const int mvSued = 510;                            // SÜD,  15.08.23, neu kalibriert
const int mvWest = 768;                            // WEST, 15.08.23, neu kalibriert

// Kalibrierung Servo

const int servomax = 115;
const int servomin = 33;


void setup() {

  if (! rtc.begin())
  {
    while (1)
    {
      delay(10);
    }
  }

  // rtc.adjust(DateTime(F(__DATE__), F(__TIME__)));    // Hier Datum und aktuelle Uhrzeit (MEZ) setzen,
  // rtc.adjust(DateTime(2023, 10, 01, 16, 43, 00));    // danach diese Zeile(n) auskommentieren und sketch neu laden

  Serial2.begin(9600);                             // Starte Serial 2 Port für Nextion Display Ausgabe
  pinMode(pwmA, OUTPUT);                           // Set the PWM and brake pins so that the direction pins can be used to control the motor
  pinMode(pwmB, OUTPUT);
  digitalWrite(pwmA, HIGH);
  digitalWrite(pwmB, HIGH);
  myStepper.setSpeed(200);                         // Set the motor speed (200 RPMs)
  servo.attach(5);                                 // Servo Steuerung an Pin 5

  pinMode(A2, INPUT);                              // Spannung Hall-Sensor
  pinMode(5, OUTPUT);                              // Steuerpin Servo
  pinMode(A5, INPUT);                              // Spannung PV-Panel

  // Ampel links
  pinMode(A8, OUTPUT);                             // grüne Ampel-LED1, Anschluss an D4
  pinMode(A9, OUTPUT);                             // gelbe Ampel-LED1, Anschluss an D6
  pinMode(A10, OUTPUT);                            // rote Ampel-LED1,  Anschluss an D7

  // Ampel rechts
  pinMode(A11, OUTPUT);                            // gelbe Ampel-LED2, Anschluss an D8
  pinMode(A12, OUTPUT);                            // rote Ampel-LED2, Anschluss an D2
  pinMode(A13, OUTPUT);                            // grüne Ampel-LED2, Anschluss an D10


  // Alle Daten des Displays leeren (refresh):

  Serial2.print("ref=page0.t0.txt");  // refresh Seite 0 Textfeld 0
  endNextionCommand();
  Serial2.print("ref=page0.t1.txt");  // refresh Seite 0 Textfeld 1
  endNextionCommand();
  Serial2.print("ref=page0.t2.txt");  // refresh Seite 0 Textfeld 2
  endNextionCommand();
  Serial2.print("ref=page0.t3.txt");  // refresh Seite 0 Textfeld 3
  endNextionCommand();
  Serial2.print("ref=page0.t4.txt");  // refresh Seite 0 Textfeld 4
  endNextionCommand();

  Serial2.print("ref=page1.t0.txt");  // refresh Seite 1 Textfeld 0
  endNextionCommand();
  Serial2.print("ref=page1.t1.txt");  // refresh Seite 1 Textfeld 1
  endNextionCommand();
  Serial2.print("ref=page1.t2.txt");  // refresh Seite 1 Textfeld 2
  endNextionCommand();
  Serial2.print("ref=page1.t3.txt");  // refresh Seite 1 Textfeld 3
  endNextionCommand();
  Serial2.print("ref=page1.t4.txt");  // refresh Seite 1 Textfeld 4
  endNextionCommand();
  Serial2.print("ref=page1.t5.txt");  // refresh Seite 1 Textfeld 5
  endNextionCommand();
  Serial2.print("ref=page1.t6.txt");  // refresh Seite 1 Textfeld 6
  endNextionCommand();

  Serial2.print("ref=page2.t0.txt");  // refresh Seite 2 Textfeld 0
  endNextionCommand();
  Serial2.print("ref=page2.t1.txt");  // refresh Seite 2 Textfeld 1
  endNextionCommand();
  Serial2.print("ref=page2.t2.txt");  // refresh Seite 2 Textfeld 2
  endNextionCommand();
  Serial2.print("ref=page2.t3.txt");  // refresh Seite 2 Textfeld 3
  endNextionCommand();
  Serial2.print("ref=page2.t4.txt");  // refresh Seite 2 Textfeld 4
  endNextionCommand();
  Serial2.print("ref=page2.t5.txt");  // refresh Seite 2 Textfeld 5
  endNextionCommand();
  Serial2.print("ref=page2.t6.txt");  // refresh Seite 2 Textfeld 6
  endNextionCommand();

  Serial2.print("ref=page3.t0.txt");  // refresh Seite 3 Textfeld 0
  endNextionCommand();
  Serial2.print("ref=page3.t1.txt");  // refresh Seite 3 Textfeld 1
  endNextionCommand();
  Serial2.print("ref=page3.t2.txt");  // refresh Seite 3 Textfeld 2
  endNextionCommand();
}


// Beginn der Schleife

void loop() {

  float Temp = float(rtc.getTemperature());             // Temperaturwert holen von DS3231 RTC
  DateTime now = rtc.now();                             // Zeitwert holen von RTC Echtzeituhr
  sprintf(buffer, "%02d.%02d.%04d  Zeit: %02d:%02d:%02d", now.day(), now.month(), now.year(), now.hour(), now.minute(), now.second());

  int Jahr = now.year();
  int Monat = now.month();
  int Tag = now.day();
  float Stunde = now.hour();
  float Minute = now.minute();
  float Sekunde = now.second();

  int yearday = DayOfYear(Jahr, Monat, Tag);                                               // Aufruf der Funktion zur Berechnung des Jahrestages

  float Elevation, Aufgang, Untergang, Deklination;                                        // Sonnen- Elevation, Aufgang, Untergang, Deklnation
  float AzS;                                                                               // Azimut Sollwert
  float Zeitgleichung;                                                                     // Differenz zwischen MOZ und WOZ
  float Zeitdifferenz;                                                                     // Zwischenwert für Berechnung von SunAngles
  float AufgangOrtszeit;
  float UntergangOrtszeit;
  float Tageslaenge, MEZ, MOZ, WOZ;                                                        // Tageslänge, Mitteleuropäische Zeit, Mittlere Ortszeit, Wahre Ortszeit
  float ZeitSeitMittag;                                                                    // Zwischenwert für Berechnung von SunAngles

  const float pi = 3.14159265;
  const float kwert = pi / 180;
  const float latitude = 51.222191;                                                        // Koordinaten für Rönkhausen
  const float longitude = 7.954169;
  const float BreiteR = latitude * kwert;                                                  // geogr. Breite in Radians
  const float hoeheSM = -(50.0 / 60.0) * kwert;                                            // Höhe des Sonnenmittelpunkts bei Aufgang
  const int Zeitzone = 1;                                                                  // Zeitzone Greenwich + 1 (MEZ, z.B. Berlin)
  String wr;

  int Grenzwert;                                                                           // Grenzwert für schnellen Rücklauf
  int AzI;                                                                                 // Azimut Ist-Wert
  int sensorValue;                                                                         // Digitaler Azimut-Ist-Wert (Hall-Sensor an Pin A2)
  int i2;                                                                                  // Hilfsvariable zur Bestimmung der Himmelsrichtung

  MEZ = Stunde + Minute / 60 + Sekunde / 3600;                                             // Mitteleuropäische Zeit

  Zeitgleichung = BerechneZeitgleichung (yearday);                                         // Aufruf der Funktion: BerechneZeitgleichung
  ZeitSeitMittag = MEZ + longitude / 15.0 - Zeitzone - 12 + Zeitgleichung;                 // Berechne ZeitSeitMittag
  Deklination = BerechneDeklination (yearday);                                             // Aufruf der Funktion: BerechneDeklination
  Zeitdifferenz = BerechneZeitdifferenz (hoeheSM, pi, latitude, kwert, Deklination);       // Aufruf der Funktion: BerechneZeitdifferenz
  AzS = SunAngles(Deklination, BreiteR, kwert, pi, ZeitSeitMittag, Elevation);             // Aufruf der Funktion: SunAngles
  Tageslaenge = BerechneTageslaenge (Zeitdifferenz, Zeitgleichung, longitude, Zeitzone, Aufgang, Untergang);   // Aufruf der Funktion: BerechneTageslaenge

  Elevation  = Elevation / kwert;
  Deklination = Deklination / kwert;

  MOZ = MEZ - (-longitude / 15) - 1;                                                       // Berechne Mittlere Ortszeit aus MEZ
  WOZ = MOZ + Zeitgleichung;                                                               // Berechne Wahre Ortszeit

  int WOZdez = (int)WOZ;
  int WOZmin = (WOZ - WOZdez) * 60;

  int MOZdez = (int)MOZ;
  int MOZmin = (MOZ - MOZdez) * 60;

  int StdL = (int)Tageslaenge;
  int MinL = (int)((Tageslaenge - StdL) * 60);

  int StdA = (int)Aufgang;
  int MinA = (int)((Aufgang - StdA) * 60);

  int StdU = (int)Untergang;
  int MinU = (int)((Untergang - StdU) * 60);

  // Grenzwerte für Rücklaufposition, abhängig von der Tageslänge (nur Stunde)

  switch (StdL) {
    case 7 ... 8: Grenzwert = 135; break;
    case 9 ... 10: Grenzwert = 115; break;
    case 11 ... 12: Grenzwert = 95; break;
    case 13 ... 14: Grenzwert = 75; break;
    case 15 ... 16: Grenzwert = 55; break;
    case 17 ... 18: Grenzwert = 35; break;
  }

  sensorValue = analogRead(A2);                              // Auslesen Hall-Sensor an Pin A2

  AzI = MotorenSteuerung (AzS, Elevation, sensorValue, Grenzwert, stepsV, stepsR, stepsSR, mvOst, mvSued, mvWest, servomax, servomin);  // Aufruf der Funktion: MotorenSteuerung
  wr = Windrichtung(AzI);                                    // Aufruf Funktion Windrichtung, abhängig von der Position des Drehtellers

  // 5-Volt-Solarpanel

  const int analogPin = A5;                                  // Solarspannung an Pin A5
  float pvmod = analogRead(analogPin);                       // Auslesen Solarspannung an Pin A5
  float Volt = Solarspannung (pvmod);                        // Aufruf Funktion: Solarspannung
  float Prozent = Volt / 4.75 * 100;                         // Berechnung % Vmax

  // Stunden, Minuten für Anzeige Tageslänge:

  int Std = (int)Tageslaenge;
  int Min = (int)((Tageslaenge - Std) * 60);


  // Ausgabe auf Nextion-5-Zoll-Display

  // Seite 0: Home

  Serial2.print("page0.t0.txt=\"");
  Serial2.print("Nextion-Solartracker-Projekt");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page0.t0.txt");
  endNextionCommand();

  Serial2.print("page0.t1.txt=\"");
  Serial2.print("Version 4.3 vom 01.10.2023");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page0.t1.txt");
  endNextionCommand();

  Serial2.print("page0.t2.txt=\"");
  Serial2.print("Dr. Michael Schulte");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page0.t2.txt");
  endNextionCommand();

  Serial2.print("page0.t3.txt=\"");
  Serial2.print("http://wetterstation.mi-schu.de");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page0.t5.txt");
  endNextionCommand();

  Serial2.print("page0.t4.txt=\"");
  Serial2.print("E-Mail: wetter.roenkhausen@gmx.de");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page0.t4.txt");
  endNextionCommand();

  // Seite 1: Time

  Serial2.print("page1.t0.txt=\"");
  Serial2.print("  Datum: " + String(buffer));
  Serial2.print(" h (MEZ)");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page1.t0.txt");
  endNextionCommand();

  Serial2.print("page1.t1.txt=\"");
  Serial2.print("   Tag im Jahr:                             " + String(yearday));
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page0.t1.txt");
  endNextionCommand();

  Serial2.print("page1.t2.txt=\"");
  if (WOZmin >= 0 && WOZmin < 10)  {
    Serial2.print("   Wahre Ortszeit (WOZ):           " + String (WOZdez) + ":" + "0" + String (WOZmin) + " h");
  }
  else
  { Serial2.print("   Wahre Ortszeit (WOZ):           " + String (WOZdez) + ":" + String (WOZmin) + " h");
  }
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page1.t2.txt");
  endNextionCommand();

  Serial2.print("page1.t3.txt=\"");
  if (MOZmin >= 0 && MOZmin < 10)  {
    Serial2.print("   Mittlere Ortszeit (MOZ):         " + String (MOZdez) + ":" + "0" + String (MOZmin) + " h");
  }
  else
  { Serial2.print("   Mittlere Ortszeit (MOZ):         " + String (MOZdez) + ":" + String (MOZmin) + " h");
  }
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page1.t3.txt");
  endNextionCommand();

  Serial2.print("page1.t4.txt=\"");
  if (MinA >= 0 && MinA < 10)  {
    Serial2.print("   Sonnenaufgang:                      " + String (StdA) + ":" + "0" + String (MinA) + " h");
  }
  else
  { Serial2.print("   Sonnenaufgang:                      " + String (StdA) + ":" + String (MinA) + " h");
  }
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page1.t4.txt");
  endNextionCommand();

  Serial2.print("page1.t5.txt=\"");
  if (MinU >= 0 && MinU < 10)  {
    Serial2.println("   Sonnenuntergang:                " + String (StdU) + ":" + "0" + String (MinU) + " h");
  }
  else
  { Serial2.println("   Sonnenuntergang:                " + String (StdU) + ":" + String (MinU) + " h");
  }
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page1.t5.txt");
  endNextionCommand();

  Serial2.print("page1.t6.txt=\"");
  if (MinL >= 0 && MinL < 10)  {
    Serial2.print("   Tageslaenge:                         " + String (StdL) + ":" + "0" + String (MinL) + " h");
  }
  else
  { Serial2.print("   Tageslaenge:                         " + String (StdL) + ":" + String (MinL) + " h");
  }
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page1.t6.txt");
  endNextionCommand();

  // Seite 2: Data

  Serial2.print("page2.t0.txt=\"");
  Serial2.print("  Datum: " + String(buffer));
  Serial2.print(" h (MEZ)");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page2.t0.txt");
  endNextionCommand();

  Serial2.print("page2.t1.txt=\"");
  Serial2.print(" Azimut-Soll:                " + String(AzS) + " Grd " + "(" + String(wr) + ")");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page2.t1.txt");
  endNextionCommand();

  Serial2.print("page2.t2.txt=\"");
  Serial2.print(" Azimut-Ist:  (GW " + String(Grenzwert) + ")   " + String(AzI) + "      Grd " + "(" + String(wr) + ")");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page2.t2.txt");
  endNextionCommand();

  Serial2.print("page2.t3.txt=\"");
  Serial2.print(" Elevation:                      " + String(Elevation) + " Grd");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref = page2.t3.txt");
  endNextionCommand();

  Serial2.print("page2.t4.txt=\"");
  Serial2.print(" Deklination:                   " + String(Deklination) + " Grd");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page2.t4.txt");
  endNextionCommand();

  Serial2.print("page2.t5.txt=\"");
  Serial2.print(" Hall-Sensor (Pin2): " + String(sensorValue) + "   Temp: " + String(Temp, 1) + " Grd C");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page2.t5.txt");
  endNextionCommand();

  Serial2.print("page2.t6.txt=\"");
  Serial2.print(" Solarspannung:     " + String(Volt) + " V    " + "(" + String (int (Prozent)) + "% Vmax" + ")");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page2.t6.txt");
  endNextionCommand();

  // Seite 3: Sun

  Serial2.print("page3.t0.txt=\"");
  Serial2.print(" Azimut-Soll: " + String(AzS) + " Grd");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref = page3.t5.txt");
  endNextionCommand();

  Serial2.print("page3.t1.txt=\"");
  Serial2.print(" Azimut-Ist:   " + String(AzI) + "      Grd");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page2.t2.txt");
  endNextionCommand();

  Serial2.print("page3.t2.txt=\"");
  Serial2.print(" Elevation:    " + String(Elevation) + "   Grd");
  Serial2.write('"');
  endNextionCommand();
  Serial2.print("ref=page2.t5.txt");
  endNextionCommand();
}

void endNextionCommand()
{
  Serial2.write(0xff);
  Serial2.write(0xff);
  Serial2.write(0xff);
}


// Funktion: Windrichtung

String Windrichtung (int AzI) {
  int i;
  switch (AzI) {
    case 0 ... 11: i = 0; break;
    case 12 ... 34: i = 1; break;
    case 35 ... 56: i = 2; break;
    case 57 ... 79: i = 3; break;
    case 80 ... 101: i = 4; break;
    case 102 ... 124: i = 5; break;
    case 125 ... 146: i = 6; break;
    case 147 ... 169: i = 7; break;
    case 170 ... 191: i = 8; break;
    case 192 ... 214: i = 9; break;
    case 215 ... 236: i = 10; break;
    case 237 ... 259: i = 11; break;
    case 260 ... 281: i = 12; break;
    case 282 ... 304: i = 13; break;
    case 305 ... 326: i = 14; break;
    case 327 ... 349: i = 15; break;
  }
  const char* windrichtung[16] = {"N ", "NNO", "NO ", "ONO", "O ", "OSO", "SO ", "SSO", "S ", "SSW", "SW ", "WSW", "W ", "WNW", "NW ", "NNW"};
  String wr = windrichtung[i];
  return wr;
}


// Funktion: SunAngles für die Berechnung von Azimut und Elevation

float SunAngles (float Deklination, float BreiteR, float kwert, float pi, float ZeitSeitMittag, float & Elevation) {
  float DK = Deklination;
  float cosdec = cos(DK);
  float sindec = sin(DK);
  float lha = ZeitSeitMittag * (1.0027379 - 1 / 365.25) * 15 * kwert;
  float coslha = cos(lha);
  float sinlha = sin(lha);
  float coslat = cos(BreiteR);
  float sinlat = sin(BreiteR);
  float N = -cosdec * sinlha;
  float D = sindec * coslat - cosdec * coslha * sinlat;
  Elevation = asin(sindec * sinlat + cosdec * coslha * coslat);      // Höhe des Sonnenmittelpunktes über dem Horizont
  float AzS = atan2(N, D);
  if (AzS < 0) {
    AzS += 2 * pi;
  }
  return (AzS / kwert);
}


// Funktion: BerechneZeitgleichung

float BerechneZeitgleichung (int yearday) {
  float Zeitgleichung = -0.170869921174742 * sin(0.0336997028793971 * yearday + 0.465419984181394) - 0.129890681040717 * sin(0.0178674832556871 * yearday - 0.167936777524864);
  return Zeitgleichung;
}


// Funktion: BerechneDeklination

float BerechneDeklination(int yearday) {
  float Deklination = 0.409526325277017 * sin(0.0169060504029192 * (yearday - 80.0856919827619));
  return Deklination;
}


// Funktion: BerechneZeitdifferenz

float BerechneZeitdifferenz(float hoeheSM, float pi, float latitude, float kwert, float Deklination) {
  float Zeitdifferenz;
  Zeitdifferenz = 12 * acos((sin(hoeheSM) - sin(latitude * kwert) * sin(Deklination)) / (cos(latitude * kwert) * cos(Deklination))) / pi;
  return Zeitdifferenz;
}


// Funktion: BerechneTageslaenge

float BerechneTageslaenge (float Zeitdifferenz, float Zeitgleichung, float longitude, int Zeitzone, float & Aufgang, float & Untergang)  {
  float AufgangOrtszeit = 12 - Zeitdifferenz - Zeitgleichung;
  float UntergangOrtszeit = 12 + Zeitdifferenz - Zeitgleichung;
  Aufgang = AufgangOrtszeit - longitude / 15 + Zeitzone;
  Untergang = UntergangOrtszeit - longitude / 15 + Zeitzone;
  float Tageslaenge = Untergang - Aufgang;
  return Tageslaenge;
}


// Funktion: MotorenSteuerung, Ansteuerung von Steppermotor, Servo und Status-LEDs

int MotorenSteuerung (float AzS, float Elevation, int sensorValue, int Grenzwert, const int stepsV, const int stepsR, const int stepsSR, const int mvOst, const int mvSued, const int mvWest, const int servomax, const int servomin)
{
  float AzI;

  if (sensorValue >= 0 && sensorValue < mvSued)  {
    AzI = map(sensorValue, mvOst, mvSued, 90, 180);          // 15.08.23, neu kalibriert: Skalierung der Hall-Sensorwerte in Gradwerte 90-180 Grad
  }
  if (sensorValue >= mvSued && sensorValue <= 900)  {
    AzI = map(sensorValue, mvSued, mvWest, 180, 270);        // 15.08.23, neu kalibriert: Skalierung der Hall-Sensorwerte in Gradwerte 180-270 Grad
  }
  constrain(AzI, 40, 320);                                   // Begrenzung des Azimut-Ist-Wertebereichs auf Werte zwischen 40 und 320 Grad
  if (Elevation > -1) {                                      // Solange Elevation > -1 --> Sonnenmittelpunkt steht über dem Horizont

    int E2 = int(Elevation);
    int elevation = map(E2, 90, 0, servomax, servomin);      // Servo-Kalibrierung
    constrain(elevation, 20, 130);
    servo.write(elevation);                                  // Schreiben der kalibrierten Servoposition (Nachführung)

    if ((int)AzI < (int)AzS) {                               // Azimut-Nachführung: Wenn Azimut-Ist kleiner als Azimut-Soll, dann:
      digitalWrite(pwmA, HIGH);                              // Stepper Strom an
      digitalWrite(pwmB, HIGH);                              // Stepper Strom an
      digitalWrite(A10, HIGH);                               // LED1 grün an
      digitalWrite(A11, HIGH);                               // LED2 grün an
      myStepper.step(stepsV);                                // Step one revolution in one direction, FORWARD
      delay (250);
      digitalWrite(A10, LOW);                                // LED1 grün aus
      digitalWrite(A11, LOW);                                // LED2 grün aus
      digitalWrite(A8, LOW);                                 // LED1 rot aus
      digitalWrite(A13, LOW);                                // LED2 rot aus
      digitalWrite(A9, LOW);                                 // LED1 gelb aus
      digitalWrite(A12, LOW);                                // LED2 gelb aus
      digitalWrite(pwmA, LOW);                               // Stepper stromlos schalten
      digitalWrite(pwmB, LOW);                               // Stepper stromlos schalten
    }

    if ((int)AzI > (int)AzS) {                               // Azimut-Nachführung: Wenn Azimut-Ist grösser als Azimut-Soll, dann:
      digitalWrite(pwmA, HIGH);                              // Stepper Strom an
      digitalWrite(pwmB, HIGH);                              // Stepper Strom an
      digitalWrite(A8, HIGH);                                // LED1 rot an
      digitalWrite(A13, HIGH);                               // LED2 rot an
      digitalWrite(A9, LOW);                                 // LED1 gelb aus
      digitalWrite(A12, LOW);                                // LED2 gelb aus
      myStepper.step(stepsR);                                // Step one revolution in one direction, BACKWARD
      delay (250);
      digitalWrite(A8, LOW);                                 // LED1 rot aus
      digitalWrite(A13, LOW);                                // LED2 rot aus
      digitalWrite(A10, LOW);                                // LED1 grün aus
      digitalWrite(A11, LOW);                                // LED2 grün aus
      digitalWrite(pwmA, LOW);                               // Stepper stromlos schalten
      digitalWrite(pwmB, LOW);                               // Stepper stromlos schalten
    }
  }
  else  {                                                    // Sonne ist untergegangen --> Rückführung auf Anfangsposition
    if (Elevation <= -1 && AzI >= Grenzwert)  {              // Azimut-Rückführung: Wenn Elevation < -1 (Sonne ist vollständig untergegangen), dann:
      delay(250);
      digitalWrite(pwmA, HIGH);
      digitalWrite(pwmB, HIGH);
      myStepper.step(stepsSR);                               // Step one revolution in one direction
      delay (250);
      digitalWrite(A9, LOW);                                 // LED1 gelb aus
      digitalWrite(A12, LOW);                                // LED2 gelb aus
      delay(250);
      digitalWrite(A9, HIGH);                                // LED1 gelb an
      digitalWrite(A12, HIGH);                               // LED2 gelb an
      delay(250);
      digitalWrite(A9, LOW);                                 // LED1 gelb aus
      digitalWrite(A12, LOW);                                // LED2 gelb aus
      delay(250);
      digitalWrite(A9, HIGH);                                // LED1 gelb an
      digitalWrite(A12, HIGH);                               // LED2 gelb an
      delay (250);
      digitalWrite(A9, LOW);                                 // LED1 gelb aus
      digitalWrite(A12, LOW);                                // LED2 gelb aus
      delay(250);
      digitalWrite(A9, HIGH);                                // LED1 gelb an
      digitalWrite(A12, HIGH);                               // LED2 gelb an
      delay (250);
      digitalWrite(A9, LOW);                                 // LED1 gelb aus
      digitalWrite(A12, LOW);                                // LED2 gelb aus
      delay (250);
      digitalWrite(A9, HIGH);                                // LED1 gelb an
      digitalWrite(A12, HIGH);                               // LED2 gelb an
      delay (250);
      digitalWrite(pwmA, LOW);                               // Stepper stromlos schalten
      digitalWrite(pwmB, LOW);                               // Stepper stromlos schalten
      delay(250);
    }
  }
  if (int(AzI) == int(AzS)) {                                // Stepper aus und gelbe LED an beim Erreichen der Zielposition (AzI == AzS)
    digitalWrite(A9, HIGH);                                  // LED1 gelb an
    digitalWrite(A12, HIGH);                                 // LED2 gelb an
    digitalWrite(pwmA, LOW);                                 // Stepper stromlos schalten
    digitalWrite(pwmB, LOW);                                 // Stepper stromlos schalten
  }
  return AzI;                                                // Rückgabewert: Azimut-Ist
}


// Funktion: Solarspannung

float Solarspannung(float pvmod)                             // Funktion: Solarspannung
{
  float Volt;
  Volt = pvmod / 1023 * 4.75;                                // Umrechnung Analogwert in Spannungswert (Volt)
  return Volt;
}