Projekt 40: Regelung eines fertigen Laborversuchsaufbaus "Lageregelung": Unterschied zwischen den Versionen

Aus HSHL Mechatronik
Zur Navigation springen Zur Suche springen
Keine Bearbeitungszusammenfassung
 
(44 dazwischenliegende Versionen von 2 Benutzern werden nicht angezeigt)
Zeile 1: Zeile 1:
[[Kategorie:Projekte]]
[[Kategorie:Projekte]]


Autoren: Martins, Raza<br/>
Autoren: [[Benutzer:Madleine_Kahr| Madleine Kahr]], [[Benutzer:Adam_Fankhauser| Adam Fankhauser]]<br/>
Betreuer: [[Benutzer:mirekgoebel| Prof. M. Göbel]]
Betreuer: [[Benutzer:mirekgoebel| Prof. M. Göbel]]


[[Datei:Versuchsaufbau1.jpg|500px|right]]  
[[Datei:Versuchsaufbau1.jpg|400px|thumb|right|Versuchsaufbau Lageregelung]]
===Aufgabe ===
 
Entwurf eines Reglers für einen mechanisch und elektrisch fertigen Laborversuch.
==Aufgabe==
 
Die Aufgabe in diesem Projekt bestand darin, einen Regler für einen fertigen Laborversuchsaufbau zu entwickeln, welcher die Lage eines Schlittens regelt. Der Regler soll auf der Hardware eines Arduino Uno Boards laufen, dieser soll sich außerhalb des Aufbaus befinden und über einen 50 poligen Stecker angeschlossen werden. Sowohl der Aufbau, als auch das Arduino-Board waren zum Projektbeginn vorhanden, wodurch keine Beschaffung von Hardware notwendig war.
Die Vorgehensweise bei diesem Projekt richtete sich klassisch nach den vier Projektphasen: Vorbereitung, Planung, Durchführung und Präsentation/Dokumentation.




Zeile 14: Zeile 17:
*Recherche zu bestehenden Lösungen
*Recherche zu bestehenden Lösungen
*Systemidentifikation (Übertragungsfunktion der Regelstrecke bestimmen)
*Systemidentifikation (Übertragungsfunktion der Regelstrecke bestimmen)
*Vergleichen und bewerten Sie verschiedene Regleransätze (2-Punkt, 3-Punkt, P, I, D), Darstellung der Soll-/Istgrößen.
*Vergleichen und bewerten Sie verschiedene Regleransätze (P, I, D), Darstellung der Soll-/Istgrößen.
*Programmiersprache: C
*Programmiersprache: C
*Test und wiss. Dokumentation  
*Test und wiss. Dokumentation  
Zeile 25: Zeile 28:




==Vorbereitung==


Zur Vorbereitung auf das Projekt wurde der aktuelle Stand des Projekts analysiert. Dazu wurde die Dokumentation auf der HSHL-Wiki Seite zur Rate gezogen, sowie die Informationen, die im Projektordner abgelegt wurden.
Aus den Unterlagen des letzten Projektes ging hervor, dass schon einmal ein funktionierender PI-Regler entwickelt wurde, dieser wurde zur Einarbeitung analysiert und getestet. Dabei sind mehrere Sachen aufgefallen. Zum einen wurde in der Programmierung des Arduino der Befehl digitalWrite() benutzt, um den Motor mit einem PWM-Signal anzusteuern . Die Funktion lässt aber nur zu, dass der Ausgang die Signale HIGH und LOW liefert, was in der Regelung nur genauso lange funktioniert, wie der I-Anteil des Reglers klein bleibt. Die eigentliche Funktion des Ausgangs zur Erzeugung eines PWM-Signals wird mit der Funktion analogWrite() erzeugt, welche Werte von 0 bis 255 als Eingangsgrößen akzeptiert.
Im Gegensatz zu der letzten Projektbearbeitung sollte dieses Mal selber Softwaretechnisch ein Regler entwickelt werden, d.h. ohne Unterstützung einer Library. Dazu wurden die Ansätze eines digitalen Zeitdiskreten PID Reglers recherchiert. Aus der Vorlesung Mess- & Regelungstechnik wurde entnommen, dass der D-Anteil gefiltert werden muss, hierzu wurde aus den Vorlesungsunterlagen das PT1-Filter entnommen.


===Versuchsaufbau===


==Einleitung==
{|width=22% border="2" cellpadding=0px align=right style = "background:rgb(250,250,250);color:rgb(0,0,0)"
 
Dieses Projekt wurde im Rahmen des Elektrotechnikfachpraktikums angeboten und von
mir ausgewählt. Die Hauptaufgabe des Projektes besteht darin, einen Regler softwaremäßig zu entwickeln, der am besten für dieses System geeignet ist. Dabei soll das
Verhalten verschiedener Regeltypen untersucht und verglichen werden.
 
 
 
 
==Ablauf des Projektes==
 
Im Folgenden ist das Gantt-Diagramm dargestellt. Das Diagramm zeigt den zeitlichen
Ablauf des Projektes.
 
[[Datei:Ablauf.jpg|800px|thumb|center|Abbildung 1: Ablauf des Projektes]]
 
 
 
 
 
==Beschreibung des Versuchsaufbaus==
 
[[Datei:Versuchsaufbau.jpg|600px|thumb|right|Abbildung 2: Schematische Darstellung des Versuchsaufbaus ]]
 
In Abbildung 2 ist die schematische Darstellung des Versuchsaufbaus dargestellt.
 
Mithilfe des Servomotors 1, der in beiden Richtungen betrieben werden kann, wird
die Kugelgewindespindel 2 in die Rotationsbewegung gebracht. Die Rotationsbewegung
der Gewindespindel soll den Schlitten 3 in die gew¨unschte Position entlang der
Spindelachse bringen. Die aktuelle Position des Schlittens wird mithilfe des Positionssensors
(Linearpotentiometer) 4 ermittelt. F¨ur die Betreibung des Versuchsaufbaus sind
zwei Spannungsquellen erforderlich. Mithilfe der ersten Quelle werden Sensoren versorgt,
w¨ahrend die zweite Quelle die Versorgung f¨ur den Motor sicherstellt. Das System
wird mithilfe des Arduino-Boards angesteuert. Der Arduino-Board soll mit dem PC
verbunden werden, da die Spannungsversorgung des Arduinos durch USB-Anschluss
erfolgt.
 
 
 
 
 
 
 
 
 
 
 
 
 
In der Tabelle 1 ist die Pinbelegung von den verwendeten Pins dargestellt:
 
 
{|width=50% border="2" cellpadding=10px align=center style = "background:rgb(230,240,230);color:rgb(0,0,0)"
|+ Tabelle 1: Pinbelegung
!  
!  
! Pin an Arduino Uno
! Pin an Arduino
! Pin/Bezeichnung an dem Laborversuchsaufbau
! Pin/Bezeichnung an dem Laborversuchsaufbau (Signale)
|-
|-
!1  
!1  
|A0
|A0
| Poti - "Sollwert"
| Potentiometer - "Sollwert" (0-1023)
|-
|-
! 2  
! 2  
| A1
| A1
| Poti - "P-Anteil"
| Potentiometer - "P-Anteil" (0-1023)
|-
|-
! 3  
! 3  
| A2
| A2
| Poti - "I-Anteil"
| Potentiometer - "I-Anteil" (0-1023)
|-
|-
! 4
! 4
|A3
|A3
| Poti - "D-Anteil"
| Potentiometer - "D-Anteil" (0-1023)
|-
|-
! 5
! 5
| A4
| A4
| Poti - Linear
| Potentiometer - Linear (0-1023)
|-
|-
! 6  
! 6  
|3 (PWM)
|3 (PWM)
| Motor rechts (an der H-Brucke Schaltung)
| Motoransteuerung Rechtslauf (LOW , 0-255)  
|-
|-
! 7
! 7
|4 (PWM)
|4
| Motor ENB (an der H-Brucke Schaltung)
| Motoransteuerung (LOW, HIGH)
|-
|-
! 8  
! 8  
|5 (PWM)
|5 (PWM)
| Motor links (an der H-Brucke Schaltung)
| Motoransteuerung Linkslauf (LOW , 0-255)
|}
|}


==Ersatz des defekten Bauteils==
[[Datei:Versuchsaufbau.jpg|350px|thumb|left|Versuchsaufbau, Sicht von Oben]]
 
 


[[Datei:L298N.jpg|200px|thumb|right|Abbildung 3: L298N <ref>[http://www.amazon.com/Generic-Module-Stepper-Controller-Arduino/dp/B00HHYBW0E]
Der Laborversuch ist so aufgebaut, dass durch einen Servomotor eine Spindel angetrieben wird. Dieser Motor lässt sich im Links- und Rechtslauf antreiben. Auf der Spindel befindet sich ein Schlitten, welcher sich durch die Drehung der Spindel auf dieser nach links und rechts bewegt. Der Fahrweg des Schlittens beträgt ca. 14 cm Durch ein Linearpotentiometer, das parallel zur Spindel angebracht ist, lässt sich die Position des Schlittens bestimmen. An den Endpositionen des Potentiometers befinden sich Endschalter, welche die Stromversorgung für den Motor ausschalten, um einen Überlauf des Schlittens zu verhindern.  
www.amazon.com/Generic-Module-Stepper-Controller-
Über vier Drehpotentiometer, die sich an der Vorderseite des Aufbaus befinden lassen sich zum einen  die gewünschte Sollposition, sowie die verschiedenen Regleranteile einstellen.  
Arduino/dp/B00HHYBW0E, abgerufen am 20.01.2015, 10:39</ref>]]
Der Versuchsaufbau wird über ein Arduino Uno Board gesteuert, welches mit einem PC verbunden ist.  
Die Pinbelegung des ist in der nachfolgenden Tabelle dargestellt:


Bei den ersten Versuchen den Programmkode auszuführen, hat der Servomotor keine
Reaktionen gezeigt. Nach der genaueren Untersuchung und in Absprache mit dem betreuenden
Professor hat sich herausgestellt, dass der L298N Motortreiber beschädigt
ist. Der L298N Motortreiber ist eine H-Brücke Schaltung, siehe Abbildung 3, die für
die Motoransteuerung zuständig ist. Diese Schaltung wurde von mir ausgetauscht. Die
Ursache für die Funktionsbeeinträchtigung des Motortreibers ist unklar geblieben.




Zeile 142: Zeile 90:




==Planung==


Bei der Planung des Projektes sollte die Regelung des Aufbaus bestimmt und simuliert werden. Dafür wurde die Theorie dargestellt, ein Regelkreis entworfen und das System mithilfe von Matlab/Simulink simuliert.
Da die Programmieroberfläche von Arduino keine Logging Funktionen bietet wurde hier auf das Tool Terminal.exe zurückgegriffen. Damit wurden die Messergebnisse aufgenommen, um sie mit Excel oder Matlab zu visualisieren.


===Theorie===


 
Die Übergangsfunktionen der zeitdiskreten Regler P, PI und PID sind [http://rn-wissen.de/wiki/index.php/Regelungstechnik#Digitaler_Regler hier] entnommen.
 
Die Regelstrecke weist ein I-Verhalten auf. Dies wurde experimentell ermittelt, indem ein Einheitssprung in die Regelstrecke eingeführt wurde. Praktisch bedeutet dies, den Motor anzuschalten. Das bedeutet wiederum, dass der zurückgelegte Weg sich über die Zeit aufintegriert. Die Messdaten wurden visualisiert, über die Steigung der Geraden konnte der Faktor <math>K_i</math> der Regelstrecke bestimmt werden.
==Realisierung==
 
Im Folgenden wird die Realisierung des Projektes beschrieben.
 


===Regelkreis===
===Regelkreis===


[[Datei:RegelkreisLageregelung.jpg|650px|thumb|right|Abbildung 4: Regelkreis ]]
[[Datei:RegelkreisLageregelung.jpg|330px|thumb|right|Regelkreis Lageregelung]]
 
In Abbildung 4 ist der Entwurf des Regelkreises des Systems dargestellt. Mithilfe des
Potentiometers (Potiwert) an dem Versuchsaufbau wird der Soll-Wert eingestellt. Arduino
Board gilt als Regler. Die Regelstrecke ist hier der Servomotor, die Kugelgewindespindel
und der PWM-Signal. Der Ist-Wert wird mithilfe des Positionssensors
(Potentiometer) ermittelt.
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
===PI-Regler===
 
 
[[Datei:SprungantwortPI.JPG|650px|thumb|right|Abbildung 5: Sprungantwort PI-Regler ]]
 
 
Die Reglergleichung des PI-Reglers ist definiert durch:
 
<math>y(t) = k_p \cdot e(t) + k_i \cdot \int\limits_{0}^{t} e(\tau) \mathrm{d}\tau </math>
 
===Programmkode===
 
Im Folgenden ist der Programmkode:
 
[[Datei:Programmkode.jpg|400px|left ]]
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 


Die Sollgröße wird über das Drehpotentiometer bestimmt und in den Regelkreis eingebracht. Die Regelabweichung wird an den Regler, welcher als P, PI oder PID-Regler realisiert werden soll, übergeben. Dieser übergibt dann ein PWM-Signal an die Regelstrecke. Diese besteht aus dem Motor und der Spindel. Durch das Linearpotentiometer wird die Ist-Position bestimmt, welche als Rückführgröße wieder in den Regelkreis eingeht.


===Simulation mit Matlab/Simulink===


Mithilfe von Matlab/Simulink wurde die Regelstrecke simuliert. Mithilfe dieser Simulation konnten die Einflüsse der verschiedenen Reglertypen und die Veränderung von ihren Kennwerten prinzipiell veranschaulicht werden. Dadurch wurden die Abläufe im Regelkreis deutlich.




==Durchführung==


[[Datei:P_Sprungantwort.png|250px|thumb|right|Sprungantwort des P-Reglers ]]
[[Datei:PI_Sprungantwort.png|250px|thumb|right|Sprungantwort des PI-Reglers ]]
[[Datei:PID_Sprungantwort.png|250px|thumb|right|Sprungantwort des PID-Reglers ]]


Bei der Durchführung wurde zunächst der Regler in der Programmiersprache C umgesetzt. Danach wurde der P-Regler eingesetzt, um die Regleranteile nach Ziegler/Nichols zu ermitteln. Dazu wurde der <math>K_p</math> Faktor so hoch gedreht, bis das System instabil wurde, d.h. dass der Schlitten über den eingestellten Sollwert hin- und hergefahren ist. Dies ergab: <math>K_{p,krit} = 2800</math> und <math>T_{krit} = 1,5s</math>. Die Berechnung mithilfe dieser Ergebinisse ergab folgende Einstellungen:




P-Regler: <math>K_p = 1400</math>


PI-Regler: <math>K_p = 1260</math>  <math>K_i = 988</math>


PID-Regler: <math>K_d = 1680</math>  <math>K_i = 2240</math>  <math>K_d = 302</math>


Mit diesen Einstellungen wurden nun die Regler getestet und folgende Sprungantworten aufgenommen.






===Programmcode===


<source lang=c>


//--------------------------------------------------------
//PID Regler für Laborversuchsaufbau "Lageregelung"
//Hochschule Hamm-Lippstadt
//Fachpraktikum Elektrotechnik
//
//Datum:  14.12.2015
//Autoren:  Madleine Kahr, Adam Fankhauser
//--------------------------------------------------------


//PINs definieren
#define MotorAnsteuerung 4
#define MotorRechts 3
#define MotorLinks 5
#define SollPoti A0
#define KpPoti A1
#define KiPoti A2
#define KdPoti A3
#define LinearPoti A4


//Größen definieren
double SollPosition, IstPosition, Stellgroesse, Regeldifferenz;
double Kp, Ki, Kd;
double PAnteil, IAnteil, DAnteil, RegeldifferenzSumme;
int Wertebereich_Kp, Wertebereich_Ki, Wertebereich_Kd;


//Zeiten definieren
double now, then, dt;


//Variablen für PT1_Filter definieren
float k_f,T0_f, Regeldifferenz_filt_neu_f, Regeldifferenz_filt_alt_f;


void setup()
{
  Serial.begin(9600); //Kommunikation mit Baudrate 9600 starten


  //Digitale Pins als OUTPUT definieren
  pinMode(MotorAnsteuerung, OUTPUT);
  pinMode(MotorRechts, OUTPUT);
  pinMode(MotorLinks, OUTPUT);


  //Variablen setzen
  Wertebereich_Kp = 3000;
  Wertebereich_Ki = 2500;
  Wertebereich_Kd = 1000;
  RegeldifferenzSumme = 0;
  T0_f = 0.001;  // T0_f << T_d
 
  then = millis(); //Startzeit holen
}


void loop()
{
  //Werte der Proportinalbeiwerte auslesen und umrechnen
  Kp = analogRead(KpPoti);
  Kp = Kp/1023*Wertebereich_Kp;
  Ki = analogRead(KiPoti);
  Ki = Ki/1023*Wertebereich_Ki;
  Kd = analogRead(KdPoti);
  Kd = Kd/1023*Wertebereich_Kd;


  //Soll- und Istposition auslesen und umrechnen, Regeldifferenz berechnen
  SollPosition = analogRead(SollPoti);
  SollPosition = SollPosition/1023*14;
  IstPosition = analogRead(LinearPoti);
  IstPosition = 14 - (IstPosition - 157)/(850-157)*14;


  Regeldifferenz = SollPosition - IstPosition;


  //aktuelle Zeit holen, Zeitdifferenz berechnen (Abtastzeit)
  now = millis();
  dt = (now-then)/1000;
  then = now;


  //Anti-Windup Strategie
  if((Stellgroesse < 255) && (Stellgroesse > 0))
    RegeldifferenzSumme = RegeldifferenzSumme + Regeldifferenz;


  //Signal filtern für D-Anteil
  k_f = dt/(T0_f+dt);
  Regeldifferenz_filt_neu_f = (1-k_f) * Regeldifferenz_filt_alt_f + k_f * Regeldifferenz;
 
  //Anteile berechnen und zu Stellgröße addieren
  PAnteil = Regeldifferenz*Kp;
  IAnteil = RegeldifferenzSumme*dt*Ki;
  DAnteil = ((Regeldifferenz_filt_neu_f-Regeldifferenz_filt_alt_f)/dt)*Kd;
 
  Stellgroesse = abs(PAnteil + IAnteil + DAnteil);


  //Stellgröße für Übergabe an Motor vorbereiten
  if(Stellgroesse > 255)
    Stellgroesse = 255;
  if(Stellgroesse < 1)
    Stellgroesse = 0;


  //Ausgabe an Konsole für Überwachung und Logging 
  Serial.print(now);
  Serial.print(";    Ist; ");
  Serial.print(IstPosition);
  Serial.print(" ;cm; Soll; ");
  Serial.print(SollPosition);
  Serial.print(" ;cm;");
  Serial.print("    Kp; ");
  Serial.print(Kp);
  Serial.print(" ; Ki; ");
  Serial.print(Ki);
  Serial.print(" ; Kd; ");
  Serial.print(Kd);
  Serial.print(" ;    Stellgroesse; ");
  Serial.print(Stellgroesse);
  Serial.print(" ; Regelabweichung; ");
  Serial.print(Regeldifferenz);
  /*Serial.print(" ; esummme; ");
  Serial.print(RegeldifferenzSumme); */
  Serial.print(" ;  PAnteil; ");
  Serial.print(PAnteil);
  Serial.print(" ; IAnteil; ");
  Serial.print(IAnteil);
  Serial.print(" ; DAnteil; ");
  Serial.print(DAnteil);
  Serial.println(" ,");


  //Übergabe der Stellgröße an Motor
  if(Regeldifferenz > 0) // Schlitten nach rechts fahren lassen
  { 
    digitalWrite(MotorLinks, LOW);
    analogWrite(MotorRechts, Stellgroesse);
    digitalWrite(MotorAnsteuerung, HIGH);
  }
  else if(Regeldifferenz < 0) // Schlitten nach links fahren lassen
  {
    digitalWrite(MotorRechts, LOW);
    analogWrite(MotorLinks, Stellgroesse);
    digitalWrite(MotorAnsteuerung, HIGH);
  }


}


</source>


==Präsentation/Dokumentation==


Die Präsentation des Projektes erfolgte über einen Messeauftritt in der Hochschule Hamm-Lippstadt. Bei dieser Messe wurden alle Projekte des Elektrotechnikfachpraktikums vom Wintersemester 15/16 vorgestellt. Bei dieser Präsentation wurden mithilfe des Versuchsaufbaus und einer Visualisierung über Matlab die im Semester erreichten Projektziele gezeigt. Zur Veranschaulichung wurden Plakate mit den wichtigsten Informationen in der Nähe des Versuchsaufbaus aufgestellt.
Die Dokumentation erfolgte über diesen Artikel im HSHL-Wiki und über ein [https://youtu.be/huDHaNF7fQY Präsentationsvideo]


==Fazit==
==Fazit==


Im Laufe dieses Projektes konnten neue Erfahrungen aus der Regelungstechnik gesammelt werden. Es hat sich auch gezeigt, dass es manchmal nicht so einfach das theoretische Wissen in der Praxis umzusetzen ist. Das Projekt ist nicht abgeschlossen, da aus zeitlichen Gründen nicht alle Regelansätze untersucht und nicht alle Erwartungen aus der Aufgabenstellung an das Projekt erfüllt werden konnten.
Als Fazit lässt sich sagen, dass das Projekt zum größten Teil, aber nicht vollständig abgeschlossen werden konnte. Das System konnte erfolgreich identifiziert werden, ebenso konnte ein funktionierender Regler in der Programmiersprache C implementiert werden. Schon in der Theorie konnte nachgewiesen werden, dass ein einfacher P-Regler bei Betrachtung der Führungsgröße keine statische Regelabweichung hinterlässt. Die Messergebnisse haben allerdings gezeigt, dass der P-Regler trotzdem eine statische Regelabweichung hinterlässt. Zurückzuführen ist dies darauf, dass auch Störeinflüsse einfließen, die in der Theorie nicht berücksichtigt wurden.
Die Auswertung des PI-Reglers zeigt, was auch die Theorie besagt, dass keine stationäre Regelabweichung zurück bleibt, der Regler aber langsamer reagiert.
Leider konnte bei dieser Projektbearbeitung der PID-Regler nicht so eingestellt werden, dass dieser vernünftige Ergebnisse liefert. Dies bleibt als Anregung für die Studierenden zurück, die dieses Projekt als nächstes bearbeiten.
Außerdem wurde von Prof. Schneider als Anregung gegeben, die Implementierung des Reglers in Matlab/Simulink umzusetzen, um aus der Simulation des Systems einen einfachen Übertrag zum anwendbaren Regler und eine gute Vergleichsmöglichkeit zwischen Simulation und Realität zu haben.
==Quellen==


==Quellen==
Vorlesung Mess- und Regelungstechnik von Prof. Göbel


[http://rn-wissen.de/wiki/index.php/Regelungstechnik#Digitaler_Regler Digitaler Regler]


<references />
<references />


----
----

Aktuelle Version vom 5. Februar 2016, 23:21 Uhr


Autoren: Madleine Kahr, Adam Fankhauser
Betreuer: Prof. M. Göbel

Versuchsaufbau Lageregelung

Aufgabe

Die Aufgabe in diesem Projekt bestand darin, einen Regler für einen fertigen Laborversuchsaufbau zu entwickeln, welcher die Lage eines Schlittens regelt. Der Regler soll auf der Hardware eines Arduino Uno Boards laufen, dieser soll sich außerhalb des Aufbaus befinden und über einen 50 poligen Stecker angeschlossen werden. Sowohl der Aufbau, als auch das Arduino-Board waren zum Projektbeginn vorhanden, wodurch keine Beschaffung von Hardware notwendig war. Die Vorgehensweise bei diesem Projekt richtete sich klassisch nach den vier Projektphasen: Vorbereitung, Planung, Durchführung und Präsentation/Dokumentation.


Erwartungen an die Projektlösung

  • Darstellung der Theorie
  • Entwurf eines Regelkreises
  • Recherche zu bestehenden Lösungen
  • Systemidentifikation (Übertragungsfunktion der Regelstrecke bestimmen)
  • Vergleichen und bewerten Sie verschiedene Regleransätze (P, I, D), Darstellung der Soll-/Istgrößen.
  • Programmiersprache: C
  • Test und wiss. Dokumentation
  • Live Vorführung während der Abschlusspräsentation


Schwierigkeitsgrad

Anspruchsvoll (***)


Vorbereitung

Zur Vorbereitung auf das Projekt wurde der aktuelle Stand des Projekts analysiert. Dazu wurde die Dokumentation auf der HSHL-Wiki Seite zur Rate gezogen, sowie die Informationen, die im Projektordner abgelegt wurden. Aus den Unterlagen des letzten Projektes ging hervor, dass schon einmal ein funktionierender PI-Regler entwickelt wurde, dieser wurde zur Einarbeitung analysiert und getestet. Dabei sind mehrere Sachen aufgefallen. Zum einen wurde in der Programmierung des Arduino der Befehl digitalWrite() benutzt, um den Motor mit einem PWM-Signal anzusteuern . Die Funktion lässt aber nur zu, dass der Ausgang die Signale HIGH und LOW liefert, was in der Regelung nur genauso lange funktioniert, wie der I-Anteil des Reglers klein bleibt. Die eigentliche Funktion des Ausgangs zur Erzeugung eines PWM-Signals wird mit der Funktion analogWrite() erzeugt, welche Werte von 0 bis 255 als Eingangsgrößen akzeptiert. Im Gegensatz zu der letzten Projektbearbeitung sollte dieses Mal selber Softwaretechnisch ein Regler entwickelt werden, d.h. ohne Unterstützung einer Library. Dazu wurden die Ansätze eines digitalen Zeitdiskreten PID Reglers recherchiert. Aus der Vorlesung Mess- & Regelungstechnik wurde entnommen, dass der D-Anteil gefiltert werden muss, hierzu wurde aus den Vorlesungsunterlagen das PT1-Filter entnommen.

Versuchsaufbau

Pin an Arduino Pin/Bezeichnung an dem Laborversuchsaufbau (Signale)
1 A0 Potentiometer - "Sollwert" (0-1023)
2 A1 Potentiometer - "P-Anteil" (0-1023)
3 A2 Potentiometer - "I-Anteil" (0-1023)
4 A3 Potentiometer - "D-Anteil" (0-1023)
5 A4 Potentiometer - Linear (0-1023)
6 3 (PWM) Motoransteuerung Rechtslauf (LOW , 0-255)
7 4 Motoransteuerung (LOW, HIGH)
8 5 (PWM) Motoransteuerung Linkslauf (LOW , 0-255)
Versuchsaufbau, Sicht von Oben

Der Laborversuch ist so aufgebaut, dass durch einen Servomotor eine Spindel angetrieben wird. Dieser Motor lässt sich im Links- und Rechtslauf antreiben. Auf der Spindel befindet sich ein Schlitten, welcher sich durch die Drehung der Spindel auf dieser nach links und rechts bewegt. Der Fahrweg des Schlittens beträgt ca. 14 cm Durch ein Linearpotentiometer, das parallel zur Spindel angebracht ist, lässt sich die Position des Schlittens bestimmen. An den Endpositionen des Potentiometers befinden sich Endschalter, welche die Stromversorgung für den Motor ausschalten, um einen Überlauf des Schlittens zu verhindern. Über vier Drehpotentiometer, die sich an der Vorderseite des Aufbaus befinden lassen sich zum einen die gewünschte Sollposition, sowie die verschiedenen Regleranteile einstellen. Der Versuchsaufbau wird über ein Arduino Uno Board gesteuert, welches mit einem PC verbunden ist. Die Pinbelegung des ist in der nachfolgenden Tabelle dargestellt:






Planung

Bei der Planung des Projektes sollte die Regelung des Aufbaus bestimmt und simuliert werden. Dafür wurde die Theorie dargestellt, ein Regelkreis entworfen und das System mithilfe von Matlab/Simulink simuliert. Da die Programmieroberfläche von Arduino keine Logging Funktionen bietet wurde hier auf das Tool Terminal.exe zurückgegriffen. Damit wurden die Messergebnisse aufgenommen, um sie mit Excel oder Matlab zu visualisieren.

Theorie

Die Übergangsfunktionen der zeitdiskreten Regler P, PI und PID sind hier entnommen. Die Regelstrecke weist ein I-Verhalten auf. Dies wurde experimentell ermittelt, indem ein Einheitssprung in die Regelstrecke eingeführt wurde. Praktisch bedeutet dies, den Motor anzuschalten. Das bedeutet wiederum, dass der zurückgelegte Weg sich über die Zeit aufintegriert. Die Messdaten wurden visualisiert, über die Steigung der Geraden konnte der Faktor der Regelstrecke bestimmt werden.

Regelkreis

Regelkreis Lageregelung

Die Sollgröße wird über das Drehpotentiometer bestimmt und in den Regelkreis eingebracht. Die Regelabweichung wird an den Regler, welcher als P, PI oder PID-Regler realisiert werden soll, übergeben. Dieser übergibt dann ein PWM-Signal an die Regelstrecke. Diese besteht aus dem Motor und der Spindel. Durch das Linearpotentiometer wird die Ist-Position bestimmt, welche als Rückführgröße wieder in den Regelkreis eingeht.

Simulation mit Matlab/Simulink

Mithilfe von Matlab/Simulink wurde die Regelstrecke simuliert. Mithilfe dieser Simulation konnten die Einflüsse der verschiedenen Reglertypen und die Veränderung von ihren Kennwerten prinzipiell veranschaulicht werden. Dadurch wurden die Abläufe im Regelkreis deutlich.


Durchführung

Sprungantwort des P-Reglers
Sprungantwort des PI-Reglers
Sprungantwort des PID-Reglers

Bei der Durchführung wurde zunächst der Regler in der Programmiersprache C umgesetzt. Danach wurde der P-Regler eingesetzt, um die Regleranteile nach Ziegler/Nichols zu ermitteln. Dazu wurde der Faktor so hoch gedreht, bis das System instabil wurde, d.h. dass der Schlitten über den eingestellten Sollwert hin- und hergefahren ist. Dies ergab: und . Die Berechnung mithilfe dieser Ergebinisse ergab folgende Einstellungen:


P-Regler:

PI-Regler:

PID-Regler:

Mit diesen Einstellungen wurden nun die Regler getestet und folgende Sprungantworten aufgenommen.


Programmcode

//--------------------------------------------------------
//PID Regler für Laborversuchsaufbau "Lageregelung"
//Hochschule Hamm-Lippstadt
//Fachpraktikum Elektrotechnik
//
//Datum:  14.12.2015
//Autoren:  Madleine Kahr, Adam Fankhauser
//--------------------------------------------------------

//PINs definieren
#define MotorAnsteuerung 4
#define MotorRechts 3
#define MotorLinks 5
#define SollPoti A0
#define KpPoti A1
#define KiPoti A2
#define KdPoti A3
#define LinearPoti A4

//Größen definieren
double SollPosition, IstPosition, Stellgroesse, Regeldifferenz;
double Kp, Ki, Kd;
double PAnteil, IAnteil, DAnteil, RegeldifferenzSumme;
int Wertebereich_Kp, Wertebereich_Ki, Wertebereich_Kd;

//Zeiten definieren
double now, then, dt;

//Variablen für PT1_Filter definieren
float k_f,T0_f, Regeldifferenz_filt_neu_f, Regeldifferenz_filt_alt_f;

void setup()
{
  Serial.begin(9600); //Kommunikation mit Baudrate 9600 starten

  //Digitale Pins als OUTPUT definieren
  pinMode(MotorAnsteuerung, OUTPUT);
  pinMode(MotorRechts, OUTPUT);
  pinMode(MotorLinks, OUTPUT);

  //Variablen setzen
  Wertebereich_Kp = 3000;
  Wertebereich_Ki = 2500;
  Wertebereich_Kd = 1000;
  RegeldifferenzSumme = 0;
  T0_f = 0.001;   // T0_f << T_d
  
  then = millis(); //Startzeit holen
}

void loop()
{
  //Werte der Proportinalbeiwerte auslesen und umrechnen
  Kp = analogRead(KpPoti);
  Kp = Kp/1023*Wertebereich_Kp;
  Ki = analogRead(KiPoti);
  Ki = Ki/1023*Wertebereich_Ki;
  Kd = analogRead(KdPoti);
  Kd = Kd/1023*Wertebereich_Kd;

  //Soll- und Istposition auslesen und umrechnen, Regeldifferenz berechnen
  SollPosition = analogRead(SollPoti);
  SollPosition = SollPosition/1023*14;
  IstPosition = analogRead(LinearPoti);
  IstPosition = 14 - (IstPosition - 157)/(850-157)*14;

  Regeldifferenz = SollPosition - IstPosition;

  //aktuelle Zeit holen, Zeitdifferenz berechnen (Abtastzeit)
  now = millis();
  dt = (now-then)/1000;
  then = now;

  //Anti-Windup Strategie
  if((Stellgroesse < 255) && (Stellgroesse > 0))
    RegeldifferenzSumme = RegeldifferenzSumme + Regeldifferenz;

  //Signal filtern für D-Anteil
  k_f = dt/(T0_f+dt);
  Regeldifferenz_filt_neu_f = (1-k_f) * Regeldifferenz_filt_alt_f + k_f * Regeldifferenz;
  
  //Anteile berechnen und zu Stellgröße addieren
  PAnteil = Regeldifferenz*Kp;
  IAnteil = RegeldifferenzSumme*dt*Ki;
  DAnteil = ((Regeldifferenz_filt_neu_f-Regeldifferenz_filt_alt_f)/dt)*Kd;
  
  Stellgroesse = abs(PAnteil + IAnteil + DAnteil); 

  //Stellgröße für Übergabe an Motor vorbereiten
  if(Stellgroesse > 255)
    Stellgroesse = 255;
  if(Stellgroesse < 1)
    Stellgroesse = 0; 

  //Ausgabe an Konsole für Überwachung und Logging  
  Serial.print(now);
  Serial.print(";     Ist; ");
  Serial.print(IstPosition);
  Serial.print(" ;cm; Soll; ");
  Serial.print(SollPosition);
  Serial.print(" ;cm;");
  Serial.print("     Kp; ");
  Serial.print(Kp);
  Serial.print(" ; Ki; ");
  Serial.print(Ki);
  Serial.print(" ; Kd; ");
  Serial.print(Kd);
  Serial.print(" ;     Stellgroesse; ");
  Serial.print(Stellgroesse);
  Serial.print(" ; Regelabweichung; ");
  Serial.print(Regeldifferenz);
  /*Serial.print(" ; esummme; ");
  Serial.print(RegeldifferenzSumme); */
  Serial.print(" ;   PAnteil; ");
  Serial.print(PAnteil);
  Serial.print(" ; IAnteil; ");
  Serial.print(IAnteil);
  Serial.print(" ; DAnteil; ");
  Serial.print(DAnteil);
  Serial.println(" ,");

  //Übergabe der Stellgröße an Motor 
  if(Regeldifferenz > 0) // Schlitten nach rechts fahren lassen
  {   
    digitalWrite(MotorLinks, LOW);
    analogWrite(MotorRechts, Stellgroesse);
    digitalWrite(MotorAnsteuerung, HIGH);
  }
  else if(Regeldifferenz < 0) // Schlitten nach links fahren lassen
  {
    digitalWrite(MotorRechts, LOW);
    analogWrite(MotorLinks, Stellgroesse);
    digitalWrite(MotorAnsteuerung, HIGH);
  }

}

Präsentation/Dokumentation

Die Präsentation des Projektes erfolgte über einen Messeauftritt in der Hochschule Hamm-Lippstadt. Bei dieser Messe wurden alle Projekte des Elektrotechnikfachpraktikums vom Wintersemester 15/16 vorgestellt. Bei dieser Präsentation wurden mithilfe des Versuchsaufbaus und einer Visualisierung über Matlab die im Semester erreichten Projektziele gezeigt. Zur Veranschaulichung wurden Plakate mit den wichtigsten Informationen in der Nähe des Versuchsaufbaus aufgestellt. Die Dokumentation erfolgte über diesen Artikel im HSHL-Wiki und über ein Präsentationsvideo

Fazit

Als Fazit lässt sich sagen, dass das Projekt zum größten Teil, aber nicht vollständig abgeschlossen werden konnte. Das System konnte erfolgreich identifiziert werden, ebenso konnte ein funktionierender Regler in der Programmiersprache C implementiert werden. Schon in der Theorie konnte nachgewiesen werden, dass ein einfacher P-Regler bei Betrachtung der Führungsgröße keine statische Regelabweichung hinterlässt. Die Messergebnisse haben allerdings gezeigt, dass der P-Regler trotzdem eine statische Regelabweichung hinterlässt. Zurückzuführen ist dies darauf, dass auch Störeinflüsse einfließen, die in der Theorie nicht berücksichtigt wurden. Die Auswertung des PI-Reglers zeigt, was auch die Theorie besagt, dass keine stationäre Regelabweichung zurück bleibt, der Regler aber langsamer reagiert. Leider konnte bei dieser Projektbearbeitung der PID-Regler nicht so eingestellt werden, dass dieser vernünftige Ergebnisse liefert. Dies bleibt als Anregung für die Studierenden zurück, die dieses Projekt als nächstes bearbeiten. Außerdem wurde von Prof. Schneider als Anregung gegeben, die Implementierung des Reglers in Matlab/Simulink umzusetzen, um aus der Simulation des Systems einen einfachen Übertrag zum anwendbaren Regler und eine gute Vergleichsmöglichkeit zwischen Simulation und Realität zu haben.

Quellen

Vorlesung Mess- und Regelungstechnik von Prof. Göbel

Digitaler Regler




→ zurück zum Hauptartikel: Fachpraktikum Elektrotechnik (WS 14/15)