1 Joint Bewegung
Wegpunkt kartesisch angeben
Wenn der Wegpunkt kartesich angegeben werden soll, dann wird der Befehl moveJoint() verwendet.
Verwendung
moveJoint(x, y, z, q0, q1, q2, q3, geschwindigkeit);
Parameter
8 Parameter: x-, y- und z-Wert (in Meter) des Zielpunktes, die vier Quaternionen q0, q1, q2 und q3 sowie die Geschwindigkeit geschwindigkeit zwischen 0 und 1.
optionaler 9. Parameter zur Benennung der Bewegung.
Beispiel
moveJoint(0.62100, 0.00000, 0.69726, 0.70711, 0.00000, 0.70711, 0.00000, 0.50000, "kartesischer Wegpunkt");
Wegpunkt �ber Achswinkel angeben
Wenn der Wegpunkt �ber die Achswinkel angegeben werden soll, dann wird der Befehl joints() verwendet.
Verwendung
joints(joint1, joint2, joint3, joint4, joint5, joint6, geschwindigkeit);
Parameter
7 Parameter: 6 Joint-Werte (in Grad) und die Geschwindigkeit geschwindigkeit zwischen 0 und 1.
optionaler 8. Parameter zur Bennenung der Bewegung.
Beispiel
joints(-20.00, 0.00, 45.00, 78.25, 90.00, -130.5, 0.5, "Wegpunkt mit Achswinkeln");
2 Lineare Bewegung
Je nach Stellung des Roboters kann ein linearer Pfad nicht ausgef�hrt werden. Dies geschieht zum Beispiel wenn der Roboter mit sich selbst kollidieren w�rde, oder die Bewegung aufgrund der Kinematik nicht linear abgefahren werden kann.
2.1 Wegpunkt kartesisch angeben
Wenn der Wegpunkt kartesich angegeben werden soll, dann wird der Befehl moveLinear() verwendet.
Verwendung
moveLinear(x, y, z, q0, q1, q2, q3, Geschwindigkeit);
Parameter
8 Parameter: x-, y- und z-Wert (in Meter) des Zielpunktes, die vier Quaternionen q0, q1, q2 und q3 sowie die Geschwindigkeit zwischen 0 und 1.
optionaler neunter Parameter zur Benennung der Bewegung.
Beispiel
moveLinear(0.62100, 0.00000, 0.69726, 0.70711, 0.00000, 0.70711, 0.00000, 0.50000, "kartesischer Wegpunkt");
2.2 Wegpunkt �ber Achswinkel angeben
Wenn der Wegpunkt �ber die Achswinkel angegeben werden soll, dann wird der Befehl jointsLinear() verwendet.
Verwendung
jointsLinear(joint1, joint2, joint3, joint4, joint5, joint6, geschwindigkeit);
Parameter
7 Parameter: 6 Joint-Werte (in Grad) und die Geschwindigkeit geschwindigkeit zwischen 0 und 1.
optionaler 8. Parameter zur Bennenung der Bewegung.
Beispiel
jointsLinear(-20.00, 0.00, 45.00, 78.25, 90.00, -130.5, 0.5, "Wegpunkt mit Achswinkeln");
3 Komplexe Pfade
horstFX-Version: ab 2021.04 (nur im textuellen Programmieren)
Unter komplexen Pfaden versteht man Pfade, die weder eine Joint-Bewegung noch eine Linearbewegung sind. In horstFX k�nnen drei verschiedene Typen komplexer Pfade verwendet werden. Diese sind Kreis (circle), Spline-Kurve (spline) und Polygonzug (polygonChain).
Allgemein
Weicht die aktuelle Roboterposition von der Anfangsposition des Pfades ab, so wird automatisch eine Joint-Bewegung zum Pfadanfang gemacht. Dies l�sst sich unterbinden durch:
"moveToStart" : false // optional, standardm��ig true
Die Geschwindigkeit dieser Joint-Bewegung l�sst sich als Relativgeschwindigkeit bezogen auf die Maximalgeschwindigkeit angeben:
"moveToStart.speed.ratio" : 0.5 // optional, standardm��ig 1.0
Verz�gerte Ausg�nge und Stopp-Bedingungen k�nnen wie beim erweiterten Move-Befehl angegeben werden.
Angabe der Geschwindigkeit
Die Kontrolle der Geschwindigkeit des eigentlichen komplexen Pfades ist im Folgenden beschrieben. Die Angabe der Geschwindigkeit ist zwingend.
Sie kann als Relativgeschwindigkeit erfolgen:
"speed.ratio" : 0.35
Oder als kartesische Geschwindigkeit/Beschleunigung (mindestens eine der folgenden Angaben erforderlich):
"speed.vmax.xyz" : 0.02 (Meter/Sekunde)
"speed.accl.xyz" : 0.1 (Meter/Sekunde�)
"speed.vmax.orient" : 10 (Grad/Sekunde)
"speed.accl.orient" : 5 (Grad/Sekunde�)
Nicht angegebene Gr��en werden automatisch auf das jeweils zul�ssige Maximum gesetzt. Wenn speed.vmax.xyz angegeben wurde, so kann zus�tzlich durch
"speed.vmax.xyz.ensure" : true // optional, standardm��ig false
sichergestellt werden, dass die kartesische Geschwindigkeit w�hrend der gesamten Bewegung eingehalten wird.
Der Geschwindigkeitsregler wird f�r solche Pfade deaktiviert. Die ben�tigte Entfernung f�r die Beschleunigungs- und Bremsphase wird bei der Ausf�hrung eingeblendet. Falls die vorgegebene Geschwindigkeit nicht eingehalten werden kann, f�hrt dies zum Programmabbruch.
VORSICHT:
Die Bewegung wird auch dann mit der vorgegebenen Geschwindigkeit ausgef�hrt, wenn der Geschwindigkeitsregler davor nicht auf 100% war. Der Geschwindigkeitsregler wird f�r solche Pfade deaktiviert. Mit 10% bewegt sich der Roboter genauso schnell wie mit 100%!
3.1 Kreis
Eine Kreisbewegung kann auf zwei Arten definiert werden.
3.1.1 Definition durch Mittelpunkt, Pfadanfang und Vektor in Kreisebene
- Angabe durch Kreismittelpunkt (center), Pfadanfang (p1) und Vektor in Kreisebene (p2):
circle({
"speed.ratio" : 0.5,
"center" : {"xyz" : [ 0.4049, -0.0096, 0.3413]},
"p1" : {"xyz+quat" : [ 0.4049, 0.0395, 0.3413, -0.00008, 0.00000, 0.98613, -0.16600]},
"p2" : {"xyz" : [ 0.4360, 0.0395, 0.3413]},
"angle" : 120, // in Grad, zwingend
"fixedOrientation" : true // optional, standardm��ig true
}) - Die Kreisbewegung f�ngt immer bei der Position und mit der Orientierung an, die durch p1 vorgegeben wird.
- Die Kreisebene wird definiert durch die zwei Vektoren p1-center und p2-center. D. h. p2 liegt in der Kreisebene, aber nicht zwingend auf der Kreisbahn.
-
Eine eventuell vorhandene Orientierung in den Definitionen von center und p2 wird ignoriert. D. h. folgende Angaben sind �quivalent:
"center" : {"xyz" : [ 0.4049, -0.0096, 0.3413]}
"center" : {"xyz+euler" : [ 0.4049, -0.0096, 0.3413, 180, 0, 180]}
"center" : {"xyz+quat" : [ 0.4049, -0.0096, 0.3413, 0, 1, 0, 1]} - Der Winkel angle muss angegeben werden. Bei negativem Winkel erfolgt die Bewegung in die entgegengesetzte Richtung.
- Mit
"fixedOrientation" : false
wird die Anfangsorientierung mitrotiert.
3.1.2 Definition durch drei Punkte auf Kreisbogen
Angabe durch drei Punkte p1, p2, und p3 auf dem Kreisbogen:
circle({
"speed.ratio" : 0.5,
"p1" : {"xyz+quat" : [ 0.3471, 0.0000, 0.6932, 0.70711, 0.00000, 0.70711, 0.00000]},
"p2" : {"xyz" : [ 0.3471, 0.0668, 0.6515]},
"p3" : {"xyz" : [ 0.3471, 0.0225, 0.5967]},
"angle" : 120, // in Grad, optional
"fixedOrientation" : true // optional, standardm��ig true
})
- Die Kreisbewegung f�ngt immer bei der Position und mit der Orientierung an, die durch p1 vorgegeben wird.
- Eine eventuell vorhandene Orientierung in den Definitionen von p2 und p3 wird ignoriert.
- Wenn kein Winkel angle angegeben wird, geht die Kreisbewegung durch p2 und endet bei p3. Wird ein negativer Winkel angegeben, beginnt die Bewegung bei p1 in Richtung von p3 (entgegengesetzte Richtung).
-
Mit
"fixedOrientation" : false
wird die Anfangsorientierung mitrotiert.
3.2 Polygonzug
Ein Polygonzug ist eine Aneinanderreihung von Strecken durch vorgegebene Eckpunkte.
polygonChain({
"speed.ratio" : 0.5,
"blendradius.xyz" : 0.01, // in Meter, optional
"vertices" : [
{"xyz+quat": [ 0.350, -0.080, 0.380, 0.70711, 0.00000, 0.70711, 0.00000]},
{"xyz+quat": [ 0.350, -0.080, 0.390, 0.70711, 0.00000, 0.70711, 0.00000]},
{"xyz+quat": [ 0.350, -0.090, 0.390, 0.70711, 0.00000, 0.70711, 0.00000]},
{"xyz+quat": [ 0.350, -0.085, 0.395, 0.70711, 0.00000, 0.70711, 0.00000], "blendradius.xyz" : 0.05},
{"xyz+quat": [ 0.350, -0.080, 0.390, 0.70711, 0.00000, 0.70711, 0.00000]},
{"xyz+quat": [ 0.350, -0.090, 0.380, 0.70711, 0.00000, 0.70711, 0.00000]},
{"xyz+quat": [ 0.350, -0.080, 0.380, 0.70711, 0.00000, 0.70711, 0.00000]},
{"xyz+quat": [ 0.350, -0.090, 0.390, 0.70711, 0.00000, 0.70711, 0.00000]},
{"xyz+quat": [ 0.350, -0.090, 0.380, 0.70711, 0.00000, 0.70711, 0.00000]},
]
})
-
Ein f�r alle Eckpunkte g�ltiger �berschleifradius kann mit blendradius.xyz im Hauptblock vorgegeben werden.
- Die Eckpunkte k�nnen als xyz+euler, xyz+quat, joints oder eine beliebige Mischung davon angegeben werden (siehe auch Spline-Kurve).
- Jedem Eckpunkt (au�er dem ersten und letzten) kann ein gesonderter �berschleifradius mitgegeben werden.
4 Erweiterter Move-Befehl
Der erweiterte move-Befehl bietet eine Vielzahl an Einstellungen und kann stark parametrisiert werden.
Die Zielposition l�sst sich in Achswinkeln oder als TCP-Koordinaten mit einer Zielausrichtung absolut oder relativ �bergeben. Die nachfolgende Auflistung ist nach der Priorit�t der Parameter sortiert. Beispielsweise werden bei der �bergabe einer kartesischen und einer Achswinkel-Zielpostition die Achswinkel ignoriert.
Im Folgenden werden die einzelnen Parameter der Funktion beschrieben.
4.1. Funktion
Die Funktion ben�tigt eine beliebige Liste mit Parametern und Werten.
move( {Parameter : Wert, ...}, Wegpunktname);
4.2. Pflichtparameter
Die hier beschriebenen Parameter sind Pflichtparameter. Ohne diese Parameter ist der move Aufruf ung�ltig und der Roboter meldet einen Fehler.
4.2.1 Bewegungstyp
'movetype': WERT,
Je nachdem ob der Roboter in einer Jointbewegung oder Linear den Wegpunkt anfahren soll muss als Wert entweder 'JOINT' oder 'LINEAR' eingetragen werden.
4.2.2 Zielangabe
'poserelation': WERT,
Hier wird definiert ob die Zielposition absolut oder relativ angegeben wird.
Bei einer absoluten Zielposition f�hrt der Roboter an die angegebenen Werte. Hierf�r muss als Wert 'ABSOLUTE' eingetragen werden.
Soll die Zielposition relativ sein, d.h. relativ von der zu diesem Zeitpunkt aktuellen Position des Roboters muss als Wert 'RELATIVE' eingetragen werden.
4.2.3 Koordinatensystem
'coord': WERT,
Hier wird definiert in welchem Koordinatensystem der Zielpunkt angegeben wird.
F�r Positionen im kartesischen Koordinaten wird f�r den Wert entweder 'cartesian_basis' oder 'cartesian_tcp' eingetragen, je nachdem ob das Basis- oder das TCP-koordinatensystem verwendet werden soll.
Wird die Position in Achswinkeln definiert, so muss der Wert auf 'joint' gesetzt werden.
4.2.4 Zielposition
Die Zielposition kann generell in zwei Varianten angegeben werden. Entweder Kartesisch oder in Achswinkeln.
Wird die Zielposition Kartesisch angegeben muss die Position wie in Zielposition (kartesisch) angegeben werden. Au�erdem muss die Zielausrichtung angegeben werden. Hierf�r darf nur eine der drei Zielausrichtungsarten angegeben werden (Euler-Winkel, Rotationsachse, Quaternionen).
Wird die Zielposition in Achswinkeln angegeben, darf keine der zuvor beschriebenen Zielpositionen angegeben werden.
4.2.4.1. Zielposition (kartesisch)
'targetpose.x': X-WERT,
'targetpose.y': Y-WERT,
'targetpose.z': Z-WERT,
F�r die Zielposition m�ssen die entsprechenden Werte in Meter angegeben werden.
4.2.4.2. Zielausrichtung (Euler-Winkel)
'targetpose.rx': X-WERT,
'targetpose.ry': Y-WERT,
'targetpose.rz': Z-WERT,
4.2.4.3. Zielausrichtung (um Rotationsachsen)
'targetpose.rotationaxis.rx': X-WERT,
'targetpose.rotationaxis.ry': Y-WERT,
'targetpose.rotationaxis.rz': Z-WERT,
'targetpose.rotationaxis.angle': WINKEL,
F�r die Zielausrichtung um eine Rotationsachse muss die entsprechende Rotationsachse in dem jeweiligen Anteil und der Rotationswinkel in Grad angegeben werden.
4.2.4.4. Zielausrichtung (Quaternionen)
'targetpose.q0': Q0-WERT,
'targetpose.q1': Q1-WERT,
'targetpose.q2': Q2-WERT,
'targetpose.q2': Q3-WERT,
F�r die Zielausrichtung in Quaternionen muss die entsprechende Orientierung angegeben werden.
4.2.4.5. Zielposition (Achswinkel)
'targetjoints.j1': J1-WERT,
'targetjoints.j2': J2-WERT,
'targetjoints.j3': J3-WERT,
'targetjoints.j4': J4-WERT,
'targetjoints.j5': J5-WERT,
'targetjoints.j6': J6-WERT,
F�r die Zielausrichtung mit Achswinkeln m�ssen die entsprechenden Achswerte in Grad angegeben werden.
4.2.5. Geschwindigkeit
F�r einen move-Befehl muss und darf nur eine der folgenden Arten f�r die Geschwindigkeitsangabe genutzt werden.
4.2.5.1 Geschwindigkeit (Faktor)
'speep.ratio': WERT,
Die Geschwindigkeit des Pfades wird hier in Prozent angegeben (von 0 bis 1, entspricht 0-100%)
4.2.5.2. Beschleunigung / Geschwindigkeit (TCP)
Achtung!
Wird die Geschwindigkeit so definiert, dann hat der Slider keine Auswirkungen auf die Geschwindigkeit. Mit 10% bewegt sich der Roboter genauso schnell wie mit 100%.
Diese Parameter k�nnen nur bei Linearbewegungen verwendet werden.
'speed.accl.xyz': WERT,
'speed.vmax.xyz': WERT,
'speed.accl.orient': WERT,
'speed.vmax.orient': WERT,
Die �bergebenen Werte m�ssen jeweils double Werte sein.
-
speed.accl.xyz : Beschleunigung in XYZ-Richtung
-
speed.vmax.xyz : Maximalgeschwindigkeit in XYZ-Richtung
-
speed.accl.orient : Rotationsbeschleunigung
-
speed.vmax.orient : Maximale Rotationsgeschwindigkeit
4.2.5.3 Beschleunigung / Geschwindigkeit (Achsen)
Achtung!
Wird die Geschwindigkeit so definiert, dann hat der Slider keine Auswirkungen auf die Geschwindigkeit. Mit 10% bewegt sich der Roboter genauso schnell wie mit 100%.
'speed.accl.j1': WERT,
'speed.accl.j2': WERT,
'speed.accl.j3': WERT,
'speed.accl.j4': WERT,
'speed.accl.j5': WERT,
'speed.accl.j6': WERT,
'speed.vmax.j1': WERT,
'speed.vmax.j2': WERT,
'speed.vmax.j3': WERT,
'speed.vmax.j4': WERT,
'speed.vmax.j5': WERT,
'speed.vmax.j6': WERT,
Die �bergebenen Werte m�ssen jeweils double Werte sein.
-
speed.accl.j1: Beschleunigung Gelenk 1 in Grad/s�
-
speed.accl.j2: Beschleunigung Gelenk 2 in Grad/s�
-
speed.accl.j3: Beschleunigung Gelenk 3 in Grad/s�
-
speed.accl.j4: Beschleunigung Gelenk 4 in Grad/s�
-
speed.accl.j5: Beschleunigung Gelenk 5 in Grad/s�
-
speed.accl.j6: Beschleunigung Gelenk 6 in Grad/s�
-
speed.vmax.j1: Geschwindigkeit Gelenk 1 in Grad/s
-
speed.vmax.j2: Geschwindigkeit Gelenk 2 in Grad/s
-
speed.vmax.j3: Geschwindigkeit Gelenk 3 in Grad/s
-
speed.vmax.j4: Geschwindigkeit Gelenk 4 in Grad/s
-
speed.vmax.j5: Geschwindigkeit Gelenk 5 in Grad/s
-
speed.vmax.j6: Geschwindigkeit Gelenk 6 in Grad/s
4.3 Optionale, zus�tzliche Parameter
Die folgenden Parameter sind alle optional und werden nur f�r Zusatzfunktionalit�ten w�hrend eines Pfades ben�tigt.
4.3.1. �berschleifen
Beim �berschleifen wird ein Wegpunkt nicht direkt angefahren. Stattdessen wird in einem Bogen an dem Wegpunkt vorbeigefahren.
4.3.1.1. �berschleifen (Achswinkel)
'blendradius.j1': WERT,
'blendradius.j2': WERT,
'blendradius.j3': WERT,
'blendradius.j4': WERT,
'blendradius.j5': WERT,
'blendradius.j6': WERT,
F�r jede Achse muss definiert werden wie gro� die Achswinkeltoleranz in Grad jeweils maximal sein darf.
4.3.1.2 �berschleifen (TCP)
'blendradius.xyz': WERT,
'blendradius.orient': WERT,
Das erste Argument gibt den �berschleifradius in Meter an.
Das zweite Argument gibt den zul�ssigen Orientierungsradius in Grad an.
4.3.2 verz�gerte Outputs
Verz�gerte Outputs werden geschalten w�hrend der Roboter sich bewegt. Hier k�nnen beliebig viele Parameter �bergeben werden.
Das Argument des Parameters delayedOutput beinhaltet mehrere Parameter, welche alle angegeben werden m�ssen.
'delayedOutput':[
{
'on': WERT,
'output': WERT,
'time': WERT,
'type': WERT,
},
]
on : Auf diesen Wert wird der Ausgang geschalten (True oder False, f�r An oder Aus)
output : Name des Ausgangs als String
type : "PATH" oder "TIME"
time :
wenn type "PATH": Kommazahl von 0 bis 1 (1 = 100%)
wenn type "TIME": Wert in Millisekunden
4.3.2.1 Beispiel
"delayedOutput":[
{
"on": True,
"output": "OUTPUT_1",
"time": 0.5,
"type": "PATH",
},
]
4.3.3 Stopp-Bedingung
Stopp-Bedingungen werden dem move-Befehl hinzugef�gt wenn der entsprechende Pfad pausiert oder abgebrochen werden soll. Wird der Pfad pausiert, dann bremst der Roboter ab und bleibt so lange stehen wie die Bedingung g�ltig ist. Bei einem Abbruch f�hrt der Roboter direkt den n�chsten Wegpunkt im Programmablauf an.
Das Argument des Parameters interrupt beinhaltet mehrere Parameter, welche alle angegeben werden m�ssen.
'interrupt':[
{
'name': WERT,
'operator': WERT,
'type': WERT,
'value': WERT
},
]
name : Hier wird angegeben, auf welchen Wert gepr�ft wird, ob das Programm abgebrochen werden soll. Entweder INPUT_x, TOOL_INPUT_x, BOOL_REGISTER_x, INT_REGISTER_x, FLOAT_REGISTER_x, InOutBits_x, InBits_x, InOutRegister_x, InRegister_x.
operator : Gibt an, mit welchem Operator verglichen wird (>, <, >=, <=, ==, !=).
type : "PAUSE" oder "CANCEL" zum Pausieren des Programms bzw. Abbrechen des Wegpunkts.
value : Der Wert, der erreicht werden muss, damit die Stopbedingung greift.
4.3.3.1 Beispiel
'interrupt':[
{
'name': 'INPUT_1',
'operator': '==',
'type': 'PAUSE',
'value': 1.0
},
{
'name': 'FLOAT_REGISTER_3',
'operator': '>',
'type': 'CANCEL',
'value': 5.0
}
]
4.4 Beispiele
Im folgenden werden verschiedene Beispiele gezeigt.
4.4.1. Beispiel 1 Linearer Pfad mit verz�gerten Ausg�ngen und Abbruchbedingungen
move({
'movetype': 'LINEAR',
'poserelation': 'ABSOLUTE',
'coord' : 'cartesian_basis',
'speed.ratio': 0.75,
'targetpose.x': -0.255,
'targetpose.y': 0.60422 ,
'targetpose.z': 0.27460,
'targetpose.rx': -180,
'targetpose.ry': 0,
'targetpose.rz': 180,
'delayedOutput':[
{
'on': True,
'output': 'OUTPUT_1',
'time': 0.5,
'type': 'PATH',
},
{
'on': True,
'output': 'OUTPUT_2',
'time': 500,
'type': 'TIME',
},
],
'interrupt':[
{
'name': 'INPUT_1',
'operator': '==',
'type': 'PAUSE',
'value': 1.0
},
{
'name': 'FLOAT_REGISTER_3',
'operator': '>',
'type': 'CANCEL',
'value': 5.0
},
],
}, "Wegpunkt 1");
Der Befehl l�sst den Roboter linear an die Koordinaten X: -0.255, Y: 0.60422, Z: 0.27460, mit der Orientierung RX: -180, RY: 0, RZ: 180.
Nach 50% der Pfadzeit wird der Ausgang OUTPUT_1 geschaltet. Au�erdem wird nach 500ms der Ausgang OUTPUT_2 geschaltet.
Sollte INPUT_1 w�hrend der Roboter diesen Wegpunkt anf�hrt den Wert 1 erreichen, dann pausiert der Roboter solange der Wert auf 1 bleibt. Wird in FLOAT_REGISTER_3 ein Wert gr��er als 5.0 eingetragen, dann bricht der Roboter diesen Pfad ab und f�hrt den n�chsten Wegpunkt an.