- 3D-Druck Einstieg und Tipps         
Ergebnis 1 bis 10 von 10

Thema: RP6 Gleichlauf der Motoren

  1. #1

    RP6 Gleichlauf der Motoren

    Anzeige

    Praxistest und DIY Projekte
    Hallo Community,

    ich habe mir vor einem Monat den RP6 zugelegt. Im Moment passe ich mir die RP6 Library an, und hier vor allem die Antriebsfunktionen.
    Und zwar habe ich selbst einen PI-Regler programmiert. Er funktioniert sehr gut, beim freien Geradeausfahren habe ich eine Abweichung von ca. 5mm/m. Damit kann ich leben. Jedoch beim Starten habe ich das Problem, dass einer der beiden Motoren früher zu drehen beginnt und sich daraus natürlich gleich von Anfang an eine falsche Richtung ergibt.

    Meine Ansätze wären Folgende:
    1.) Einen zweiten Regler, der die Drehzahldifferenz auf 0 hält.
    2.) Einen Distanzregler laufen lassen, der die Distanzdifferenz der beiden Motoren auf 0 hält, und den Geschwindigkeitssollwert anpasst.

    Daraus ergeben sich jetzt zwei Fragen:
    1.) Haben diese Ansätze Erfolgsaussichten?
    2.) Habt ihr selbst Ideen, wie man das mach bzw. hat sich schon jemand damit befasst und eine Lösung gefunden?


    Mit freundlichen Grüßen

    Schwammi

  2. #2
    Erfahrener Benutzer Begeisterter Techniker
    Registriert seit
    09.04.2008
    Beiträge
    384
    Die zwei Motoren von RP6 habe moglich eine unterschiedliche Wiederstand / Getriebe Verlust. Am ersten sollst du die Curven aufzeichnen von beide Motoren : PWM von 0 bis 100% in kleine Schritten erhohen und jedesmal die gemessene Speed via Terminal ausgeben (wie eigentlich in Testprogram). Dan sehen sie schnell wo die Unterschiede sind. Dan entsprechend ihre Regelparameter fon L/R separat einstellen. Meistens ist das Startpunkt nicht gleich : die eine Motor fangt schon an bei20% PWM, den andere benotigt 25%.
    Zweitens soll das I -Anteil schone eine Recht-Auslauf bewerkstelligen ! Den Integral von Speed ist Abstand !! Aber auch ihre Forschlag functioniert : Differenz L/R wiederum in eine zweite Regler fuhren und damit die Sollwert von Speed anpassen.

  3. #3
    Erfahrener Benutzer Roboter Genie Avatar von SlyD
    Registriert seit
    27.11.2003
    Ort
    Paderborn
    Alter
    39
    Beiträge
    1.516
    Hallo,

    Du kannst zunächst auch mal schauen ob die Stellringe an einer Seite etwas zu fest angezogen sind o.ä.


    > 1.) Einen zweiten Regler, der die Drehzahldifferenz auf 0 hält.

    Jep so könnte man das machen.
    Du hast dann einen PI Regler links, einen Regler rechts und einen zusätzlichen der die beiden miteinander verkoppelt (dabei kann direkt auf den Ausgang der beiden Regler eingegriffen werden also vom linken abziehen und beim anderen draufaddieren und umgekehrt)

    Du kannst sogar den Regler so programmieren das er eine Solldifferenz hält um damit auch Kurven fahren zu können, Vorteil ist das man dann ganz normal einfach nur beide Geschwindigkeiten setzen kann, den Rest macht der Regler.

    Hatte ich vor vielen Jahren mal für meinen großen Roboter implementiert, hat recht gut funktioniert.


    Einfacher wäre es natürlich, wenn man dem Motor der später losläuft beim Start direkt etwas mehr Power gibt.
    (also nur beim Start z.B. dem Integrierer eine Konstante hinzuaddieren... )


    MfG,
    SlyD

  4. #4
    Erfahrener Benutzer Robotik Einstein Avatar von Geistesblitz
    Registriert seit
    15.03.2011
    Ort
    Dresden
    Alter
    36
    Beiträge
    1.937
    Für einen besseren Anlauf wäre auch ein D-Anteil vorteilhaft, da dieser auf starke Änderungen der Geschwindigkeit (=Beschleunigung) reagiert. Verändert allerdings wieder die ganze Dynamik, müsste man austesten.

    Ansonsten könnte das mit diesem kombinierenden Regler gut klappen. Der müsste dann so aussehen, dass er Istweg links und Istweg rechts vergleicht und je nachdem das Gas auf der einen Seite wegnimmt und auf der anderen Seite zugibt. Ansonsten kenn ich das mit dem Anlaufen erst ab einer bestimmten Spannung auch, mein Motor lief sogar in beide Richtungen zu jeweils unterschiedlichen Spannungen an. Könntest du da nicht die Losbrechspannung für beide Motoren unabhängig eingeben? Eine Identifikation der Charakteristiken beider Motoren wäre natürlich sinnvoll.

  5. #5
    So hier kommt einmal ein kleines Update:
    Die Variante mit der Drehzahldifferenz auf 0 zu halten hat keine Besserung gebracht, weil die Differenz am Anfang trotzdem sehr groß ist. Dann habe ich es mit einem D-Anteil versucht der natürlich sehr schnell reagiert. Ich habe nach einer gewissen Zeit aufgegeben diesen Regler dann zu parametrieren. Der war viel zu aggressiv dann und ich habe nicht so große Erfahrung im parametrieren. Ich glaube da würde ich in eine Sackgasse laufen.

    Die Variante von Geistesblitz mit dem kombinierenden Regler, weil es dann kein reiner Geschwindigkeitsregler mehr ist. Einen Distanzregler möchte ich dann sowieso auch programmieren, der als Stellgröße den Sollwert des Geschwindigkeitsreglers hat. Deshalb möchte ich einen perfekt funktionierenden Geschwindigkeitsregler haben.

    Jetzt habe ich mal geschaut bei welchen Pulsweiten die Motoren vorwärts bzw. rückwärts anlaufen. Es war nicht sehr überraschend, dass diese Werte sehr Unterschiedlich sind (Rechts bei 10% Links bei 22%).
    Aber wie korrigiere ich das jetzt. Da habe ich länger daran geknabbert. Ich habe jetzt versucht den Regler zu täuschen und zwar folgendermaßen:
    Meine Pulsweite kann ich einstellen zwischen 0 und 210. Der linke Motor läuft ab einer PW von 46. Der Regler gibt mir jetzt eine Stellgröße zwischen 0 und 210 (210 Stufen), physikalisch kann die Strecke aber nur von 46 bis 210 (164 Stufen)) einstellen. Die 210 Stufen vom Regler rechne ich dann auf die 164 Stufen der Strecke um (y = 46 + y*(164/210)). Beim zweiten Motor bin ich gleich verfahren. Funktioniert hat es noch immer nicht.

    Ein Problem war da nämlich noch: Der eine Motor hat 164 Stufen (210-46) und der andere hat 190 Stufen (210-20). Die Regelparameter waren aber gleich. Jetzt habe ich einen kleinen Korrekturfaktor verwendet und jetzt fährt er gleichzeitig los

    Leider hat auch dieses System jetzt eine Schwäche gezeigt. Bei niedriegen Drehzahlen (benötigte Pulsweite von ca. 50) reichen kleine Schwingungen beim Regler aus, damit er vom Vorwärts- in den Retourgang schaltet und in diesem Schwingen bleibt er dann stecken und stottert nur mehr hin und her. Ich werde jetzt versuchen eine gewisse Grauzone zu lassen in der der Motor nicht dreht. Und diesen Bereich werde ich jetzt noch mit einer Hyterese versehen, je nachdem ob er vorwärts fahren möchte oder rückwärts.

    Ich hoffe ich konnte alles mal einigermaßen verständlich erklären. Wenn alles so läuft, wie ich es mir vorstelle, werde ich den C-Code vom Regler hier reinstellen.

    Mit freundlichen Grüßen

    Schwammi

  6. #6
    Erfahrener Benutzer Roboter Genie Avatar von SlyD
    Registriert seit
    27.11.2003
    Ort
    Paderborn
    Alter
    39
    Beiträge
    1.516
    Zitat Zitat von SlyD Beitrag anzeigen

    Einfacher wäre es natürlich, wenn man dem Motor der später losläuft beim Start direkt etwas mehr Power gibt.
    (also nur beim Start z.B. dem Integrierer eine Konstante hinzuaddieren... )

    Hattest Du das mal probiert oder meintest Du das mit Korrekturfaktor?

    Ich meinte damit die Integral Variablen left_i und right_i beim standard I Regler in der Lib.
    Die Regelparameter aber sonst für beide Seiten gleich lassen.

    Muss man ggf. noch bissel was anderes am Code ändern da der I Anteil an manchen Stellen auf 0 zurückgesetzt wird (change direction...).


    Der linke Motor läuft ab einer PW von 46.
    Läuft los ja, aber hält er bei 46 auch wieder an?
    Das ist nämlich meistens nicht der Fall
    Wenns mal läuft dann läufts leichter...


    Ich sollte auch noch darauf hinweisen das die PWM im Timerinterrupt mit einer Rampe langsam geändert wird (eigentlich recht schnell aber beim D Regler könnte das evtl. Probleme machen)

    MfG,
    SlyD

  7. #7
    Zitat Zitat von SlyD
    Läuft los ja, aber hält er bei 46 auch wieder an?
    Das ist nämlich meistens nicht der Fall
    Wenns mal läuft dann läufts leichter...
    Danke für den Hinweis, hab ich ganz vergessen, aber wär mir bestimmt bald aufgefallen
    Mit der Hyterese sollte das dann auch kein Problem sein.

    Zitat Zitat von SlyD
    Einfacher wäre es natürlich, wenn man dem Motor der später losläuft beim Start direkt etwas mehr Power gibt.
    (also nur beim Start z.B. dem Integrierer eine Konstante hinzuaddieren... )
    Zitat Zitat von SlyD
    Ich meinte damit die Integral Variablen left_i und right_i beim standard I Regler in der Lib.
    Also da muss ich jetzt ein bissl was erzählen. Und zwar habe ich einen völlig eigenen Regler programmiert und den anderen Regler aus dem Code entfernt. Grund: Eingreifen in das Regelgeschehen war nicht einfach, wegen dem Soft-PWM etc. und ich wollte nicht Speed und Direction getrennt angeben. Ich habe jetzt die Funktion runSpeedController(int left, int right) und da kann ich die Geschwindigkeit in mm/s von -300mm/s bis +300mm/s eingeben. Was bei einer Positionsregelung dann auch von Vorteil ist, weil wenn die Dirfferenz negativ ist, ich nicht die Richtung ändern muss sondern der zweite Regler einfach mit Minus weiterrechnen kann.
    Deshalb brauch ich auch eine Hyterese um den Nullpunkt, da happerts im Moment noch.

    Ich stell mal den Code hier rein. Im Code siehst du auch den Grund, warum ich das mit einer Voreinstellung des I-Wertes nicht machen kann, weil mein Regler nicht einen I-Wert speichert sondern immer zur momentan eingestellten Stellgröße dazurechnet oder abzieht. Der Korrekturfaktor ist der Wert, wo ich die maximale Pulsweite(180, eigentlich 210 aber von meinem Programm begrenzt auf 180) durch die daraus resultierende Geschwindigkeit in [mm/s] dividiere.
    Der Code läuft im Timer0 Interrupt ab:

    Code:
    if(speedController == 1)
    	{
    		if(speedControllCounter++ >= speedControllTimer)
    		{
    			//Linke Raupe
    			speedControllCounter = 0;
    			sclE = sclW - getLSpeed();
    			
    			if(speedKp > 0)
    			delta_y = speedKp * (180/267.0) * ((sclE - sclE1) + speedKi * sclE * speedControllTimer/10000.0 + 
    					  speedTv * (sclE - 2*sclE1 + sclE2)/(speedControllTimer/10000.0));
    			else
    			delta_y = (180.0/267.0) * (speedKi * sclE * speedControllTimer/10000.0 + 
    					  speedTv * (sclE - 2*sclE1 + sclE2)/(speedControllTimer/10000.0));
    			
    			difE2 = difE1;
    			difE1 = difE;
    
    			if(delta_y > scMaxUp)
    				delta_y = scMaxUp;
    			
    			if(delta_y < scMaxDown)
    				delta_y = scMaxDown;
    
    			
    			if((PORTC & 0x04) >= 1) //BWD?
    				y1 = OCR1BL * (-1);  //=>y ist dann eigentlich negativ
    			else
    				y1 = OCR1BL;		    //sonst positiv
    
    
    			//Umwandeln von PW 46 bis 180 auf 0 bis 180 zur Kompatibilität zum Regler
    			//bzw. bei Rückwärtlauf von PW -42 bis -180 auf 0 bis -180
    			if(y1 >= 46)
    				y1 = (y1-46) * (180.0/(180.0-46.0));
    			else if(y1 <= (-42))
    				y1 = (y1-(-42)) * ((-180.0)/((-180.0)-(-42.0)));
    			else
    				y1 = 0;
    
    			//neues delta_y einfließen lassen und Signal in den vorgegebenen Grenzen halten
    			y1 += delta_y;
    
    			if(y1 > 180)
    				y1 = 180;
    			
    			if(y1 < -180)
    				y1 = -180;
    
    			//Zurückrechnen auf Werte zwischen 46 und 180 bzw. -42 bis -180
    
    			if(y1 > 0 || (y1 == 0 && delta_y >= 0))
    				y1 = 46 + y1 * ((180.0-46.0)/180.0);
    			else if(y1 < 0 || (y1 == 0 && delta_y < 0))
    				y1 = -42 + y1 * (((-180.0)-(-42.0))/(-180.0));
    
    			if(y1 < 0)
    			{
    				PORTC |= (1<<PORTC2); //BWD
    				y1 *= (-1); //y muss wieder positive Zahl sein weils auf OCR geschrieben wird
    			}
    			else
    			{
    				PORTC &= ~(1<<PORTC2); //FWD
    			}
    
    			sclE2 = sclE1;
    			sclE1 = sclE;
    
    			OCR1BL = y1;
    
    
    
    
    
    
    
    			//Rechte Raupe
    			
    			scrE = scrW - getRSpeed();
    			
    			if(speedKp > 0)
    				delta_y = speedKp * (180.0/284.0) * ((scrE - scrE1) + speedKi * scrE * speedControllTimer/10000.0 + speedTv * (scrE - 2*scrE1 + scrE2)/(speedControllTimer/10000.0));
    			else
    					delta_y = (180.0/284.0) * (speedKi * scrE * speedControllTimer/10000.0 + speedTv * (scrE - 2*scrE1 + scrE2)/(speedControllTimer/10000.0));
    			
    
    			if(delta_y > scMaxUp)
    				delta_y = scMaxUp;
    			
    			if(delta_y < scMaxDown)
    				delta_y = scMaxDown;
    
    			if((PORTC & 0x08) >= 1) //BWD?
    				y2 = OCR1AL * (-1);  //=>y ist dann eigentlich negativ
    			else
    				y2 = OCR1AL;		    //sonst positiv
    
    			//Umwandeln von PW 20 bis 180 auf 0 bis 180 zur Kompatibilität zum Regler
    			//bzw. bei Rückwärtlauf von PW -18 bis -180 auf 0 bis -180
    			if(y2 >= 20)
    				y2 = (y2-20) * (180.0/(180.0-20.0));
    			else if(y2 <= (-18))
    				y2 = (y2-(-18)) * ((-180.0)/((-180.0)-(-18.0)));
    			else
    				y2 = 0;
    
    			//neues delta_y einfließen lassen und Signal in den vorgegebenen Grenzen halten
    			y2 += delta_y;
    
    			if(y2 > 180)
    				y2 = 180;
    			
    			if(y2 < -180)
    				y2 = -180;
    
    			//Zurückrechnen auf Werte zwischen 20 und 180 bzw. -18 bis -180
    
    			if(y2 > 0 || (y2 == 0 && delta_y >= 0))
    				y2 = 20 + y2 * ((180.0-20.0)/180.0);
    			else if(y2 < 0 || (y2 == 0 && delta_y < 0))
    				y2 = -18 + y2 * (((-180.0)-(-18.0))/(-180.0));
    
    			if(y2 < 0)
    			{
    				PORTC |= (1<<PORTC3); //BWD
    				y2 *= (-1); //y muss wieder positive Zahl sein weil auf OCR geschrieben wird
    			}
    			else
    			{
    				PORTC &= ~(1<<PORTC3); //FWD
    			}
    
    			scrE2 = scrE1;
    			scrE1 = scrE;
    
    			OCR1AL = y2;
    		}	
    	}
    Mit freundlichen Grüßen

    Schwammi

  8. #8
    Erfahrener Benutzer Roboter Genie Avatar von SlyD
    Registriert seit
    27.11.2003
    Ort
    Paderborn
    Alter
    39
    Beiträge
    1.516
    Ah OK

    Ich würde jedoch sowieso empfehlen das etwas aufzusplitten also P und I getrennt vom Reset berechnen in eigenen Variablen dann wäre das auch kein Problem. Den Integrierer separat limitieren.

    So eine lange Rechnung hier in einer einzigen Zuweisung:

    delta_y = speedKp * (180/267.0) * ((sclE - sclE1) + speedKi * sclE * speedControllTimer/10000.0 +
    speedTv * (sclE - 2*sclE1 + sclE2)/(speedControllTimer/10000.0));


    ist nicht optimal da der Compiler aus sowas oft ineffizienten Code produziert.
    Bei 8 Bit Controllern immer alles schrittweise auseinanderbrechen und die Codegröße beim Übersetzen beachten.


    Insbesondere auch: 180/267.0
    ist böse weil große Teile der Rechnung ggf. mit Floatingpoint durchgeführt werden (auch da wo nicht notwendig).
    Alles was nicht float sein muss auf int umstellen!
    Divisionen sind auch böse, wenn möglich anders skalieren.

    Das aber nur nebenbei


    MfG,
    SlyD

  9. #9
    Ok über Codeeffizienz hab ich mir noch sehr wenig Gedanken gemacht. Hab eigentlich auch keine Ahnung davon. Die Divisionen müssen so sein 180/267 wäre sonst 0, und die Kommazahl jetzt schon anschreiben mag ich nicht, weil ich den Code dann schwerer nachvollziehen kann. Aber gut Codeoptimierung ist jetzt ein anderes Thema, jedoch würde mich interessieren, welchen Sinn es hat den I-Regler getrennt zu limitieren bzw. warum überhaupt?

    Mit freundlichen Grüßen

    Schwammi

  10. #10
    Erfahrener Benutzer Begeisterter Techniker
    Registriert seit
    09.04.2008
    Beiträge
    384
    Zum code efficienz und 8-bit µ : wen moglich mit eine 8bit int rechnen, dan 16 bit int, dan 32 bit int und allerletze float. Die Rechenaufwand geht sehr schnell ind die Hohe !! Dividieren durch 2, 4, 8.. geht sehr schnell : ist eine reine Schieb operation von binaire Zaehlen. Alles andere kostet mehr Rechenzeit.
    Limitieren von I-regler ist standard bei jeden PI(D) Regelung : Wen die Regelung aus irgendeine Grund die "Error" nicht ausregelen kan, bleibt der I-regler bei jeden Durchlauf seine Wert erhohen, selbst wen das absolut kein Sinn mehr macht (Beispiel : PWM Wert schon 100 %). Wen das Regelen dan wieder Sinn macht, muss das I-Anteil erst wieder abgebaut werden, und das kan sehr lange daeuern... Dafur werd meistend das I-Anteil begrenzt (anti Wind up). Auch wen sie iher Setpoint anderen (Beispiel : RP6 : STOP !), macht ess Sinn das I-Anteil zu nullen.

Ähnliche Themen

  1. Gleichlauf bei DC Motoren???
    Von Teslafan im Forum Motoren
    Antworten: 14
    Letzter Beitrag: 28.03.2012, 11:19
  2. Motoren und RCX
    Von firestorm_ im Forum Motoren
    Antworten: 0
    Letzter Beitrag: 08.06.2008, 08:45
  3. Antworten: 2
    Letzter Beitrag: 16.04.2007, 05:22
  4. Ct-Bot Motoren
    Von Sven04 im Forum Motoren
    Antworten: 2
    Letzter Beitrag: 23.03.2006, 11:29
  5. DC Motoren und PWM
    Von cavegn im Forum Motoren
    Antworten: 5
    Letzter Beitrag: 02.08.2005, 20:35

Berechtigungen

  • Neue Themen erstellen: Nein
  • Themen beantworten: Nein
  • Anhänge hochladen: Nein
  • Beiträge bearbeiten: Nein
  •  

12V Akku bauen