Desired Force und Trig by Contact mit LBR IV+

  • Hallo Zusammen,
    ich versuche momentan mit einem Kuka LBR 4+ (C2 lr) ein Programm zu schreiben, mit welchem der Roboter auf Kontakt fährt (rel. dünne Bleche) und bei Kontakt in den karth. steifigkeitsregler zu wechseln. Dann soll er mit 5 N eine Kraft in Y-richtung aufbringen und danach einen Ausgangs setzen, warten und die kraft wieder wegnehmen ...hat jemand einen tip für mich?


    LG Dominik

  • Schritt für Schritt zum Roboterprofi!
  • Tachjen Dominik 0815,
    hier vieleicht nen paar Hilfreiche vorschläge. Die Programme von mir hab ich
    getestet und sollten eigentlich funktionieren.


    01) ...der Roboter auf Kontakt fährt
    > Vieleicht mit Hilfe eines Interuptes, einen Näherungssensor (mit einem
    hohen Schaltabstand um rechtzeitig ab zu bremse) um langsam weiter zu
    fahren bis dann ein Sensor den Roboter anhält, wenn er einen Kontakt
    meldet.
    > Das anghongene Suchfahrt Programm ist noch nicht ganz fertig. Aber ich
    glaub ganz gut beschrieben, auch wenn das für relativ dicke Matten ist.



    02) ...mit 5 N eine Kraft in Y-richtung aufbringen
    > Je nachdem wie dein Robi steht, könntest du mit der 1. Achse deine 5N
    aufbringen. Dazu wäre das Thema Achsen weich schalten vieleicht intres-
    sant. Da müssteste diese dann die Prozentangabe für die Achsströme er-
    höhen bis du die 5N erreichst (Also Probieren).

    KRC 2 - Aktuell
    > http://www.roboterforum.de/rob…-11311/msg54233/#msg54233


    KRC 4 - Zum lesen (Im Anhang sollte aktueller sein)
    > http://www.roboterforum.de/rob…halten/msg53205/#msg53205
    > http://www.roboterforum.de/rob…kartesisch-weichschalten/


    Gruß toud.

  • nene, er meint den LBR- Das ist da e bissel anders.


    Sieh mal im LBR-Handbuch "KSS5.6 lr SI V6 DE" nach auf etwa Seite 140-150... Da sind Beispiele für sowas.

    Wolfram (Cat) Henkel

    never forget Asimov's Laws at the programming of robots...

    "Safety is an integral part of function. No safety, no production. I don't buy a car without brakes."


    Messages und Mails mit Anfragen wie "Wie geht das..." werden nicht beantwortet.

    Diese Fragen und die Antworten interessieren jeden hier im Forum.


    Messages and Mails with questions like "how to do..." will not be answered.

    These questions and the answers are interesting for everyone here in the forum.

  • So, hier nochmal etwas konkreter:


    Alle Angaben natürlich ohne Gewähr und auch die Bewegungsprogramme rund um die Funktionen bitte selbst machen :)


    Ich geh mal davon aus, dass dein Werkstück auch auf der vermessenen Base liegt- also Z liegt normal zu X_Y in der Vertikalen von oben drauf (-Z Richtung bewegt Robi zum Werkstück) und du auch im Base- KS arbeitest.


    1) Kontaktfahrt mit TrigByContact:


    Stiffness- Parameter belegen:



    Gewünschte Stiffness- Parameter eintragen:

    Code
    $stiffness.strategy=10 ; zuerst Positions- Regler Aktivieren- muss normal nicht sein da du ja sowieso zuerst im Positionsregler bist- oder?
    $stiffness.commit=true ; Regler Bestätigen und Aktivieren
    
    
    userstiff=defaultstiff ; Gesamten Parametersatz in eigenen Satz kopieren (userstiff muss ggf. deklariert werden...) 
    userstiff.cpstiffness.x=1000 ;Gewünschte Steifigkeit in X
    userstiff.cpstiffness.y=1000 ; " - " Y
    userstiff.cpstiffness.z=1000 ; " - " Z
    userstiff.tool=tool_data[1] ; Greifer Zuweisen


    Papas Parameter deklarieren (natürlich im Deklarationsteil ganz oben...):

    Code
    DECL INT md_int[16]
    DECL REAL md_float[16]
    DECL INT n
    DECL INT result
    ;Initialisieren der Papas- Paramteter:
    for n=1 to 16
    md_int[n]=0
    md_float[n]=0
    endfor


    TrigByContact aktivieren:
    (Hier bitte auf die genaue Vermessung des Werkstücks achten, da sonst schon Kräfte entstehen, die das Auslösen verursachen könnten- sprich Gewicht und Lage des Gewichts)


    Code
    md_float[1]= 0.5 ; Schwelle in rel.% der maximalen Kräfte an den Gelenken- Sprich Ansprechschwelle fürs Auslösen TbC
    result=MD_CMD("PAPAS","TRIGBYCONTACT",md_int[],md_float[]) ; PAPAS- Treiber beschreiben
    $stiffness=userstiff ; PAPAS- Treiber wird mit Setzen der Stiffness- Parameter aktiviert
    ; ab hier Bewegungsfahrt und auf Kontakt warten z.B:
    lin_rel{z -100} ; 100mm Richtung Werkstück



    Jetzt ist dein Robi bei Kontakt (50% des max. Wertes) mit dem Werkstück im kart. Steifigkeitsregler mit cp- Stiffness jeweils 1000




    2) Desired Force:


    Damit dein LBR nach dem Kontakt auch stehenbleibt, musst du das natürlich auch programmieren:


    Dazu im cell oder sonstigem Oberprogramm einen Interrupt definieren, der auf das Auslösen des kart. Steifigkeitsregler reagiert- etwa so:



    Code
    ;Roboterstop wegen Trig by contact 
    INTERRUPT DECL 10 WHEN $stiff_strat_act == 20 DO stopp( ) 
    INTERRUPT ON 10


    Im Stopp() dann so etwa:


    Code
    brake	f ;Roboter Stop
    ptp $axis_act_mes ;SAK herstellen
    INTERRUPT OFF 10


    Jetzt Steht der Robi mal (im kart. Steifigkeitsregler) und wartet auf weitere Befehle;



    Jetzt Kraft aufschalten:




    3) Ausgang setzten:


    Code
    $cycflag[1] = $torque_tcp_est.ft.y > 5 ; Hier bitte wieder beachten, dass dein Werkzeug genau vermessen ist, da ja sonst der Robi dessen Gewicht schon als Kraft empfindet. (leicht zu testen mit GravComp- Achtung :-))
    interrupt decl 20 when $cycflag[1] do savepoint()


    Du kannst statt den Flag normalerweise auch einen Ausgang setzen anstatt dem Programmaufruf. Ich kanns nur jetzt nicht Probieren. Aber beim Ausgang dann bitte ein continue verwenden, damit kein Vorlaufstopp ausgelöst wird.


    4) Kraft löschen und wieder in Pos- Regler:


    Code
    FOR n=1 TO 16
    md_int[n] = 0
    md_real[n] = 0
    ENDFOR
    result=MD_CMD("PAPAS","DESIREDFORCECLEAR",md_int[],md_real[])
    ptp $pos_act_mes
    $stiffness.strategy=10
    $stiffness.commit=true




    Sollte so funktionieren;


    Ob du den Robi anhältst oder direkt auf die Kraft umschaltest musst du selbst wissen (Trial&error).
    Ob du vor der Kraftschwelle nochmal in den Positionsregler umschaltest ebenso- bedenke, dass der Robi ja schon mit den eingestellten Parametern weichgeschalten ist. Du müsstest gegebenenfalls die X und Z- Werte vorher auf 5000 schalten, damit er in diese Richtung steif ist. Wo und wie du das Warten einbauen willst überlasse ich auch ganz dir. Hier ist mal ein solider Syntax- Grundstock, mit dem das zu realisieren sein sollte :)


    Ich hoffe ich konnte bissen helfen- für weitere Fragen stehe ich gerne zur Verfügung und auf eine RM obs geklappt hat freue ich mich natürlich...



    mfg Stups

    Einmal editiert, zuletzt von Stups ()

  • Zunächst nochmal Danke für die kompetente Hilfe :danke:,
    die Parametrierung hatte ich entsprechend in meinem Programm enthalten, jedoch komme ich nicht dazu diese zu testen, da entweder die Fehlermeldung "Gravitationskompesation Illegal State" <-- also vermutlich falsche Lastdaten oder "XYZABC-Toolkoordinaten nicht programmiert" (habe bei der XYZ 4 Punkt-Methode eine Abweichung von 1,87mm....ist das zu viel? :waffen100: )


    Das montierte Werkzeug habe ich im Programm angewählt und auch die Prgrammierung der Bewegungen mit entsprechendem Werkzeug angewählt ... Habe das Werkzeug gewogen komme aber nur schlecht an den tatsächlichen Schwerpunkt bzw. die Massenträgheitsmomente. Kann die Gravitationskompensation bei falschen Massenträgheitsmomenten dazu führen, dass der Roboter nach oben schnellt bzw. garnicht erst in den Regler der Gravitationskompensation wechselt? Bzw. hat jemand einen Tip wie ich die Lastdaten des Werkzeugs genauer ermitteln kann und das #Toolkoordinatensystem genauer ermitteln kann?


    Verzweifle gerade an dem Thema ein wenig :(

  • Bitteschön!


    Welche KSS- Version hast du?
    Abweichung zu was? Wenn der TCP abweicht sollte es egal sein...
    Illegal State sagt aus, das die Lastdaten nicht stimmen. Der TCP hat normal keinen Einfluss auf die Berechnung der Lastdaten- er ist nur führ die Bahnberechnungen und Positionierung nötig.


    Es gibt die Möglichkeit, die Lastdaten vom Roboter automatisch ermitteln zu lassen. Ich hab das auch schon versucht und es funktioniert- wenn es funktioniert- recht gut :)


    Die Funktion heißt LOADIDENT und ist ein undokumentiertes Feature beim LBR 4+.


    Die Lastdaten eines unbekannten Tools (momentan Masse und Schwerpunkt) können mit dieser Funktion aus den Robotermesswerten ermittelt werden. Dazu sind mehrere Messungen in verschiedenen Roboterposen nötig. Zum Zeitpunkt des Aufrufs mit dem Softkey LoadIdentStart sollte der Roboter ruhig stehen. Bei der ersten Messung wird der interne Zustand zurückgesetzt, darauffolgende Aufrufe mit LoadIdentNext in anderen Posen verbessern das Ergebnis sukzessive. Die Softkeys sollten links unten in den DLRRC- Funktionen zu finden sein...


    Die Funktion gibt nach jedem Aufruf die ermittelte Masse, den Schwerpunkt und eine Aussage über die Güte der Messung zurück. Dies erfolgt im folgenden Format, die Werte sind unten näher erläutert:
    LoadIdent good 1 num Exp 15 condition 2.677171
    LoadIdentMass 3.583514 cm X 2.103062 Y 0.628391 Z 140.1607



    Bedeutung:
    Lastschätzung zuverlässig = 1, sonst 0
    Anzahl der gemachten Messungen (1-15)
    Masse in kg
    Schwerpunkt x in mm
    Schwerpunkt y in mm
    Schwerpunkt z in mm
    Konditonierung => Güte der Messung


    Der Aufruf blockiert, bis die Berechnung abgeschlossen ist. Die Konditionierung gibt die Güte der Parameteranregung an und sollte möglichst klein (nahe bei 1) sein. Werte unter 10 ergeben bereits eine sehr gute Schätzung der identifizierten Last. Unabhängig von der Konditionierung kann die Güte der Messung weiter verbessert werden, wenn von allen Roboterposen zwei Messungen gemacht werden, die positionsgeregelt aus unterschiedlichen Richtungen angefahren werden. Dadurch können Hysterese-Fehler der Drehmomentmessung durch die Abtriebslager-Reibung minimiert werden.



    Nach der 15. Messung die Werte in die Lastdaten deines Werkzeuges eintragen. Wenn alles geklappt hat sollte im GravComp der Roboter ruhig stehen und auch die Meldung IllegalState verschwinden. Wenn die Meldung nicht verschwindet- im Positionsregler mit Hand ein bisschen verfahren- dann sollte sie endgültig weg sein...


    Mann kann diese Messung auch aus dem Programm heraus automatisch mit den PAPAS bzw. DLRRC- Kommandos machen- da würd ich aber mal abraten, wenn man es nur einmalig zu ermitteln hat...


    Alle Angaben natürlich ohne Anspruch auf Vollständigkeit und Richtigkeit! :angel:



    Für weitere Fragen und Anregungen stehe ich natürlich gerne zur Verfügung!


    LG
    Stups

  • Ach ja nochwas-


    Normal macht man Änderungen bzw. automatische Programmabläufe in den anderen Reglern- aber auf keinen Fall im GravComp- Modus. Den sollte man nur manuell verwenden für Techingaufgaben und ähnlichen Dingen... Danach sofort wieder zurück in den Positionsregler!


    LG

  • Ich würde mich da auch noch gern zu dem Thema am Rande einklinken (hoffe ich klaue nicht den Thread):


    Gibt es irgendwo mal eine Liste aller PAPAS/MotionDrive-Befehle? Ich habe so das Gefühl, es gibt noch 'ne ganze Reihe von Befehlen und zusätzlichen Reglerarten, die im KUKA LBR Handbuch nicht dokumentiert sind (wenn ich mir so die DLR-DLL anschaue usw.).


    Bspw. gibt es ein DESIREDFORCEX, -Y und -Z, aber da müsste es doch auch ein DESIREDTORQUE -A, -B, -C geben ... ;)


    Hintergrund ist, dass ich gerade versuche in eine in zwei Achsen verdrehte Platte mit Bohrung einzufädeln (das geht mit der kart. Steifigkeit gut), will mich dann aber senkrecht zur Bohrung ausrichten. Mit einem KUKA mit ForceTorque würde ich jetzt eine Kraftregelung auf die Momente und X-,Y-Kräfte in Gleichgewicht gehen, mit dem LBR geht das scheinbar ja nicht so einfach.


    Jemand eine Idee? (Bisheriger "schlechter" Ansatz sind REPEAT UNTIL Bedingungen, die das Tool bis zu einer Kraftabbruchbedingung [würde so eine Bedingung eigentlich als Interrupt gesetzt höher auflösend ausgewertet als bei Prüfung des UNTIL-Teils?] erst in eine Richtung, dann in die andere Richtung verfahren - das ist aber recht vermurkst)

  • Hi,


    ja es gibt in der Tat noch viele Features, die nicht im HB beschrieben sind. Diese werden aber als "Hidden Features" ausgewiesen, da sie nicht ausreichend getestet wurden usw. und somit offiziell nicht für den Endanwender zur Verfügung stehen...


    Das andere kann ich dir leider auf die schnelle nicht beantworten. Da müsste man sich ein bisschen Zeit nehmen. Aber beim Herumprobieren sollte es eigentlich zu schaffen sein...


    Was die Befehle angeht, würde ich mich an KUKA wenden bzw. da mal nachsehen: http://kuka-labs-forum.com/


    LG

  • Ja, danke, im Kuka-Labs-Forum habe ich mich angemeldet - das dauert nur noch mit der persönlichen Freischaltung. ;)


    KUKA gibt bzw. gab sich leider selbst bei Forschungsrobotern recht zugeknöpft, was Informationen, Befehle etc. anbelangt.

  • Da habe ich gerade nachgesehen (KSS 5.3 lr) steht es explizit NICHT drin.


    Zitat:
    Mit DESIREDFORCE kann beim kartesischen Steifigkeitsregler für jede kartesische
    Richtung eine kartesische Sollkraft einzeln aufgeschaltet werden:
    ???? DESIREDFORCEX
    ???? DESIREDFORCEY
    ???? DESIREDFORCEZ


    Gibt's da jetzt auch verschiedene Versionen des Handbuchs bzw. der Softwarestände? :D

  • Wenn du den richtigen Ansprechpartner hast, geht das recht unkompliziert über FTP...


    Die sind da auch recht aufgeschlossen wenn man gemeinsam schon recht viele Probleme gelöst hat :zwink:

Erstelle ein Benutzerkonto oder melde dich an um zu kommentieren

Du musst ein Benutzerkonto haben um einen Kommentar hinterlassen zu können

Benutzerkonto erstellen
Neues Benutzerkonto für unsere Community erstellen. Geht einfach!
Neues Benutzerkonto erstellen
Anmelden
Du hast bereits ein Benutzerkonto? Melde dich hier an.
Jetzt anmelden