8. Roboter-Statusabfrage

8.1. Aktuelle Gelenkposition (Winkel) abrufen

1/**
2* @brief  Gibt die aktuelle Gelenkposition (Winkel) zurück.
3* @param  [in] flag 0-blockierend, 1-nicht blockierend.
4* @param  [out] jPos Positionen der sechs Gelenke, Einheit deg.
5* @return  Fehlercode.
6*/
7int GetActualJointPosDegree(byte flag, ref JointPos jPos);

8.2. Aktuelle Gelenkposition (Bogenmaß) abrufen

1/**
2* @brief  Gibt die aktuelle Gelenkposition (Bogenmaß) zurück.
3* @param  [in] flag 0-blockierend, 1-nicht blockierend.
4* @param  [out] jPos Positionen der sechs Gelenke, Einheit rad.
5* @return  Fehlercode.
6*/
7int GetActualJointPosRadian(byte flag, ref JointPos jPos);

8.3. Gelenk-Rückmeldegeschwindigkeit abrufen

1/**
2* @brief Gibt die Gelenk-Rückmeldegeschwindigkeit in deg/s zurück.
3* @param [in] flag 0-blockierend, 1-nicht blockierend.
4* @param [out] speed Geschwindigkeiten der sechs Gelenke.
5* @return Fehlercode.
6*/
7int GetActualJointSpeedsDegree(byte flag, ref double[] speed);

8.4. Gelenk-Rückmeldebeschleunigung abrufen

1/**
2* @brief Gibt die Gelenk-Rückmeldebeschleunigung in deg/s² zurück.
3* @param [in] flag 0-blockierend, 1-nicht blockierend.
4* @param [out] acc Beschleunigungen der sechs Gelenke.
5* @return Fehlercode.
6*/
7int GetActualJointAccDegree(byte flag, ref double[] acc);

8.5. TCP-Sollgeschwindigkeit (resultierend) abrufen

1/**
2* @brief Gibt die resultierende TCP-Sollgeschwindigkeit zurück.
3* @param [in] flag 0-blockierend, 1-nicht blockierend.
4* @param [out] tcp_speed Lineare Geschwindigkeit.
5* @param [out] ori_speed Ausrichtungsgeschwindigkeit.
6* @return Fehlercode.
7*/
8int GetTargetTCPCompositeSpeed(byte flag, ref double tcp_speed, ref double ori_speed);

8.6. TCP-Istgeschwindigkeit (resultierend) abrufen

1/**
2* @brief Gibt die resultierende TCP-Istgeschwindigkeit zurück.
3* @param [in] flag 0-blockierend, 1-nicht blockierend.
4* @param [out] tcp_speed Lineare Geschwindigkeit.
5* @param [out] ori_speed Ausrichtungsgeschwindigkeit.
6* @return Fehlercode.
7*/
8int GetActualTCPCompositeSpeed(byte flag, ref double tcp_speed, ref double ori_speed);

8.7. TCP-Sollgeschwindigkeit (Komponenten) abrufen

1/**
2* @brief Gibt die TCP-Sollgeschwindigkeit als Komponenten zurück.
3* @param [in] flag 0-blockierend, 1-nicht blockierend.
4* @param [out] speed Geschwindigkeiten [x, y, z, rx, ry, rz].
5* @return Fehlercode.
6*/
7int GetTargetTCPSpeed(byte flag, ref double[] speed);

8.8. TCP-Istgeschwindigkeit (Komponenten) abrufen

1/**
2* @brief Gibt die TCP-Istgeschwindigkeit als Komponenten zurück.
3* @param [in] flag 0-blockierend, 1-nicht blockierend.
4* @param [out] speed Geschwindigkeiten [x, y, z, rx, ry, rz].
5* @return Fehlercode.
6*/
7int GetActualTCPSpeed(byte flag, ref double[] speed);

8.9. Aktuelle Werkzeugpose abrufen

1/**
2* @brief  Gibt die aktuelle Werkzeugpose zurück.
3* @param  [in] flag 0-blockierend, 1-nicht blockierend.
4* @param  [out] desc_pos Werkzeugpose.
5* @return  Fehlercode.
6*/
7int GetActualTCPPose(byte flag, ref DescPose desc_pos);

8.10. Nummer des aktuellen Werkzeugkoordinatensystems abrufen

1/**
2* @brief  Gibt die Nummer des aktuellen Werkzeugkoordinatensystems zurück.
3* @param  [in] flag 0-blockierend, 1-nicht blockierend.
4* @param  [out] id Nummer des Werkzeugkoordinatensystems.
5* @return  Fehlercode.
6*/
7int GetActualTCPNum(byte flag, ref int id);

8.11. Nummer des aktuellen Werkstückkoordinatensystems abrufen

1/**
2* @brief  Gibt die Nummer des aktuellen Werkstückkoordinatensystems zurück.
3* @param  [in] flag 0-blockierend, 1-nicht blockierend.
4* @param  [out] id Nummer des Werkstückkoordinatensystems.
5* @return  Fehlercode.
6*/
7int GetActualWObjNum(byte flag, ref int id);

8.12. Aktuelle Pose des Endflansches abrufen

1/**
2* @brief  Gibt die aktuelle Pose des Endflansches zurück.
3* @param  [in] flag 0-blockierend, 1-nicht blockierend.
4* @param  [out] desc_pos Flanschpose.
5* @return  Fehlercode.
6*/
7int GetActualToolFlangePose(byte flag, ref DescPose desc_pos);

8.13. Aktuelles Gelenkdrehmoment abrufen

1/**
2* @brief Gibt das aktuelle Gelenkdrehmoment zurück.
3* @param  [in] flag 0-blockierend, 1-nicht blockierend.
4* @param  [out] torques Gelenkdrehmomente.
5* @return  Fehlercode.
6*/
7int GetJointTorques(byte flag, float[] torques);

8.14. Systemzeit abrufen

1/**
2* @brief  Systemzeit abrufen
3* @param  [out] t_ms Einheit ms, kann gemäß UTC-Zeit konvertiert werden. Im Fehlerzustand des Roboters gibt GetSystemClock 0 zurück und einen Fehlercode.
4* @return  Fehlercode
5*/
6public int GetSystemClock(ref double t_ms)

8.15. Abfragen, ob die Roboterbewegung abgeschlossen ist

1/**
2* @brief  Fragt ab, ob die Roboterbewegung abgeschlossen ist.
3* @param  [out] state 0-nicht abgeschlossen, 1-abgeschlossen.
4* @return  Fehlercode.
5*/
6int GetRobotMotionDone(ref byte state);

8.16. Länge der Roboter-Bewegungswarteschlange abrufen

1/**
2* @brief Gibt die Länge der Roboter-Bewegungswarteschlange zurück.
3* @param [out] len Länge der Warteschlange.
4* @return Fehlercode.
5*/
6int GetMotionQueueLength(ref int len);

8.17. Roboter-Not-Halt-Status abrufen

1/**
2* @brief Gibt den Roboter-Not-Halt-Status zurück.
3* @param [out] state Not-Halt-Status, 0-nicht aktiv, 1-aktiv.
4* @return Fehlercode.
5*/
6int GetRobotEmergencyStopState(ref byte state);

8.18. Kommunikationsstatus zwischen SDK und Roboter abrufen

1/**
2* @brief Gibt den Kommunikationsstatus zwischen SDK und Roboter zurück.
3* @param [out] state Kommunikationsstatus, 0-normal, 1-gestört.
4*/
5int GetSDKComState(ref int state);

8.19. Sicherheitsstopp-Signale abrufen

1/**
2* @brief Gibt die Sicherheitsstopp-Signale zurück.
3* @param [out] si0_state Sicherheitsstopp-Signal SI0, 0-inaktiv, 1-aktiv.
4* @param [out] si1_state Sicherheitsstopp-Signal SI1, 0-inaktiv, 1-aktiv.
5*/
6int GetSafetyStopState(ref byte si0_state, ref byte si1_state);

8.20. Temperatur der Roboter-Gelenkantriebe (°C) abrufen

1/**
2* @brief Gibt die Temperatur der Roboter-Gelenkantriebe in °C zurück.
3* @param [out] temperature Array der Gelenktemperaturen.
4* @return Fehlercode.
5*/
6int GetJointDriverTemperature(double[] temperature);

8.21. Drehmoment der Roboter-Gelenkantriebe (Nm) abrufen

1/**
2* @brief Gibt das Drehmoment der Roboter-Gelenkantriebe in Nm zurück.
3* @param [out] torque Array der Gelenkdrehmomente.
4* @return Fehlercode.
5*/
6int GetJointDriverTorque(double[] torque);

8.22. Die neuesten Echtzeit-Roboterstatusdaten abrufen (Interne Mechanismusänderung)

1/**
2* @brief Die neuesten Echtzeit-Roboterstatusdaten abrufen (interner Thread aktualisiert kontinuierlich, diese Schnittstelle gibt direkt zwischengespeicherte Daten zurück)
3* @param [out] pkg Referenzparameter zum Empfangen der Roboterstatusdaten (ROBOT_STATE_PKG-Struktur)
4* @return Gibt bei Erfolg 0 zurück; bei Fehler einen negativen Fehlercode (z. B. Netzwerkkommunikationsfehler)
5*/
6public int GetRobotRealTimeState(ref ROBOT_STATE_PKG pkg)

8.23. Codebeispiel für Roboter-Statusabfragen

 1private void button29_Click(object sender, EventArgs e)
 2{
 3    ROBOT_STATE_PKG pkg = new ROBOT_STATE_PKG();
 4    double yangle = 0, zangle = 0;
 5    robot.GetRobotInstallAngle(ref yangle, ref zangle);
 6    Console.WriteLine($"yangle:{yangle},zangle:{zangle}");
 7
 8    JointPos j_deg = new JointPos(0,0,0,0,0,0);
 9    robot.GetActualJointPosDegree(0, ref j_deg);
10    Console.WriteLine($"joint pos deg:{j_deg.jPos[0]},{j_deg.jPos[1]},{j_deg.jPos[2]},{j_deg.jPos[3]},{j_deg.jPos[4]},{j_deg.jPos[5]}");
11
12    double[] jointSpeed = new double[6];
13    robot.GetActualJointSpeedsDegree(0, ref jointSpeed);
14    Console.WriteLine($"joint speeds deg:{jointSpeed[0]},{jointSpeed[1]},{jointSpeed[2]},{jointSpeed[3]},{jointSpeed[4]},{jointSpeed[5]}");
15
16    double[] jointAcc = new double[6];
17    robot.GetActualJointAccDegree(0, ref jointAcc);
18    Console.WriteLine($"joint acc deg:{jointAcc[0]},{jointAcc[1]},{jointAcc[2]},{jointAcc[3]},{jointAcc[4]},{jointAcc[5]}");
19
20    double tcp_speed = 0, ori_speed = 0;
21    robot.GetTargetTCPCompositeSpeed(0, ref tcp_speed, ref ori_speed);
22    Console.WriteLine($"GetTargetTCPCompositeSpeed tcp {tcp_speed}; ori {ori_speed}");
23
24    robot.GetActualTCPCompositeSpeed(0, ref tcp_speed, ref ori_speed);
25    Console.WriteLine($"GetActualTCPCompositeSpeed tcp {tcp_speed}; ori {ori_speed}");
26
27    double[] targetSpeed = new double[6];
28    robot.GetTargetTCPSpeed(0,ref targetSpeed);
29    Console.WriteLine($"GetTargetTCPSpeed {targetSpeed[0]},{targetSpeed[1]},{targetSpeed[2]},{targetSpeed[3]},{targetSpeed[4]},{targetSpeed[5]}");
30
31    double[] actualSpeed = new double[6];
32    robot.GetActualTCPSpeed(0, ref actualSpeed);
33    Console.WriteLine($"GetTargetTCPSpeed {actualSpeed[0]},{actualSpeed[1]},{actualSpeed[2]},{actualSpeed[3]},{actualSpeed[4]},{actualSpeed[5]}");
34
35    DescPose tcp = new DescPose(0, 0, 0, 0, 0, 0);
36    robot.GetActualTCPPose(0, ref tcp);
37    Console.WriteLine($"tcp pose:{tcp.tran.x},{tcp.tran.y},{tcp.tran.z},{tcp.rpy.rx},{tcp.rpy.ry},{tcp.rpy.rz}");
38
39    DescPose flange = new DescPose(0, 0, 0, 0, 0, 0);
40    robot.GetActualToolFlangePose(0, ref flange);
41    Console.WriteLine($"flange pose:{flange.tran.x},{flange.tran.y},{flange.tran.z},{flange.rpy.rx},{flange.rpy.ry},{flange.rpy.rz}");
42
43    int id = 0;
44    robot.GetActualTCPNum(0, ref id);
45    Console.WriteLine($"tcp num:{id}");
46
47    robot.GetActualWObjNum(0, ref id);
48    Console.WriteLine($"wobj num:{id}");
49
50    double[] jtorque = new double[6];
51    robot.GetJointTorques(0, jtorque);
52    Console.WriteLine($"torques:{jtorque[0]},{jtorque[1]},{jtorque[2]},{jtorque[3]},{jtorque[4]},{jtorque[5]}");
53
54    double t_ms = 0;
55    robot.GetSystemClock(ref t_ms);
56    Console.WriteLine($"system clock:{t_ms}");
57
58    int config = 0;
59    robot.GetRobotCurJointsConfig(ref config);
60    Console.WriteLine($"joint config:{config}");
61
62    byte motionDone = 0;
63    robot.GetRobotMotionDone(ref motionDone);
64    Console.WriteLine($"GetRobotMotionDone :{motionDone}");
65
66    int len = 0;
67    robot.GetMotionQueueLength(ref len);
68    Console.WriteLine($"GetMotionQueueLength :{len}");
69
70    byte emergState = 0;
71    robot.GetRobotEmergencyStopState(ref emergState);
72    Console.WriteLine($"GetRobotEmergencyStopState :{emergState}");
73
74    int comstate = 0;
75    robot.GetSDKComState(ref comstate);
76    Console.WriteLine($"GetSDKComState :{comstate}");
77
78    byte si0_state = 0, si1_state = 0;
79    robot.GetSafetyStopState(ref si0_state, ref si1_state);
80    Console.WriteLine($"GetSafetyStopState :{si0_state} {si1_state}");
81
82    double[] temp = new double[6];
83    robot.GetJointDriverTemperature(temp);
84    Console.WriteLine($"Temperature:{temp[0]},{temp[1]},{temp[2]},{temp[3]},{temp[4]},{temp[5]}");
85
86    double[] torque = new double[6];
87    robot.GetJointDriverTorque(torque);
88    Console.WriteLine($"torque:{torque[0]},{torque[1]},{torque[2]},{torque[3]},{torque[4]},{torque[5]}");
89
90    robot.GetRobotRealTimeState(ref pkg);
91}

8.24. Inverse Kinematik berechnen

1/**
2* @brief  Berechnet die inverse Kinematik.
3* @param  [in] type 0-absolute Pose (Basiskoordinatensystem), 1-inkrementelle Pose (Basiskoordinatensystem), 2-inkrementelle Pose (Werkzeugkoordinatensystem).
4* @param  [in] desc_pos Kartesische Pose.
5* @param  [in] config Gelenkraumkonfiguration, [-1]-basierend auf aktueller Gelenkposition berechnen, [0~7]-basierend auf spezifischer Konfiguration lösen.
6* @param  [out] joint_pos Gelenkposition.
7* @return  Fehlercode.
8*/
9int GetInverseKin(int type, DescPose desc_pos, int config, ref JointPos joint_pos);

8.25. Inverse Kinematik berechnen (mit Referenzposition)

1/**
2* @brief  Berechnet die inverse Kinematik unter Verwendung einer Referenz-Gelenkposition, um die Lösbarkeit zu prüfen.
3* @param  [in] type 0-absolute Pose (Basiskoordinatensystem), 1-inkrementelle Pose (Basiskoordinatensystem), 2-inkrementelle Pose (Werkzeugkoordinatensystem).
4* @param  [in] desc_pos Kartesische Pose.
5* @param  [in] joint_pos_ref Referenz-Gelenkposition.
6* @param  [out] joint_pos Berechnete Gelenkposition (falls lösbar).
7* @return  Fehlercode.
8*/
9int GetInverseKinRef(int posMode, DescPose desc_pos, JointPos joint_pos_ref, ref JointPos joint_pos);

8.26. Inverse Kinematik (mit Erweiterungsachsenposition) berechnen

 1/**
 2* @brief Berechnet die inverse Kinematik, einschließlich der Erweiterungsachsenposition im kartesischen Raum.
 3* @param [in] type 0-absolute Pose (Basiskoordinatensystem), 1-inkrementelle Pose (Basiskoordinatensystem), 2-inkrementelle Pose (Werkzeugkoordinatensystem).
 4* @param [in] desc_pos Kartesische Pose.
 5* @param [in] exaxis Position der Erweiterungsachse.
 6* @param [in] tool Werkzeugnummer.
 7* @param [in] workPiece Werkstücknummer.
 8* @param [out] joint_pos Gelenkposition.
 9* @return Fehlercode.
10*/
11public int GetInverseKinExaxis(int type, DescPose desc_pos, ExaxisPos exaxis, int tool, int workPiece, ref JointPos joint_pos);

8.27. Codebeispiel für inverse Kinematik mit Erweiterungsachsen

 1public void TestInverseKinExaxis()
 2{
 3    ROBOT_STATE_PKG pkg = new ROBOT_STATE_PKG();
 4
 5
 6    DescPose desc = new DescPose(99.957f, -0.002f, 29.994f, -176.569f, -6.757f, -167.462f);
 7    ExaxisPos exaxis = new ExaxisPos(100.0f, 0.0f, 0.0f, 0.0f);
 8    JointPos jointPos = new JointPos(0,0,0,0,0,0);
 9    DescPose offsetPos = new DescPose(0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f);
10    int rtn;
11    robot.GetRobotRealTimeState(ref pkg);
12    int toolnum = pkg.tool;
13    int workPcsNum = pkg.user;
14
15    robot.GetInverseKinExaxis(0, desc, exaxis, toolnum, workPcsNum, ref jointPos);
16    Console.WriteLine($"GetInverseKinExaxis joint is {jointPos.jPos[0]}, {jointPos.jPos[1]}, {jointPos.jPos[2]}, {jointPos.jPos[3]}, {jointPos.jPos[4]}, {jointPos.jPos[5]}");
17
18    robot.ExtAxisMove(exaxis, 100, -1);
19
20    int blendMode = 0;
21    int velAccMode = 0;
22    float oacc = 100.0f;
23    byte flag = 0;
24    robot.MoveJ(jointPos, desc, toolnum, workPcsNum, (float)100.0, (float)100.0, (float)100.0, exaxis, -1, 0, offsetPos);
25}

8.28. Lösbarkeit der inversen Kinematik prüfen

1/**
2* @brief Prüft, ob die inverse Kinematik für eine gegebene Referenz-Gelenkposition lösbar ist.
3* @param [in] posMode 0 absolute Pose, 1 relative Pose - Basiskoordinatensystem, 2 relative Pose - Werkzeugkoordinatensystem.
4* @param [in] desc_pos Kartesische Pose.
5* @param [in] joint_pos_ref Referenz-Gelenkposition.
6* @param [out] hasResult 0-keine Lösung, 1-Lösung vorhanden.
7* @return Fehlercode.
8*/
9int GetInverseKinHasSolution(int posMode, DescPose desc_pos, JointPos joint_pos_ref, ref bool hasResult);

8.29. Vorwärtskinematik berechnen

1/**
2* @brief  Berechnet die Vorwärtskinematik.
3* @param  [in] joint_pos Gelenkposition.
4* @param  [out] desc_pos Kartesische Pose.
5* @return  Fehlercode.
6*/
7int GetForwardKin(JointPos joint_pos, ref DescPose desc_pos);

8.30. Codebeispiel für Roboter-Vorwärts-/Inverskinematik

 1private void button30_Click(object sender, EventArgs e)
 2{
 3    JointPos j1 = new JointPos(-11.904f, -99.669f, 117.473f, -108.616f, -91.726f, 74.256f);
 4    DescPose desc_pos1 = new DescPose(-419.524f, -13.000f, 351.569f, -178.118f, 0.314f, 3.833f);
 5
 6    JointPos inverseRtn = new JointPos(0, 0, 0, 0, 0, 0);
 7
 8    robot.GetInverseKin(0, desc_pos1, -1, ref inverseRtn);
 9    Console.WriteLine($"dcs1 GetInverseKin rtn is {inverseRtn.jPos[0]} {inverseRtn.jPos[1]} {inverseRtn.jPos[2]} {inverseRtn.jPos[3]} {inverseRtn.jPos[4]} {inverseRtn.jPos[5]}");
10    robot.GetInverseKinRef(0,  desc_pos1, j1, ref inverseRtn);
11    Console.WriteLine($"dcs1 GetInverseKinRef rtn is {inverseRtn.jPos[0]} {inverseRtn.jPos[1]} {inverseRtn.jPos[2]} {inverseRtn.jPos[3]} {inverseRtn.jPos[4]} {inverseRtn.jPos[5]}");
12
13    bool hasResut = false;
14    robot.GetInverseKinHasSolution(0,  desc_pos1,  j1, ref hasResut);
15    Console.WriteLine($"dcs1 GetInverseKinRef result {hasResut}");
16
17    DescPose forwordResult = new DescPose(0, 0, 0, 0, 0, 0);
18    robot.GetForwardKin(j1, ref forwordResult);
19    Console.WriteLine($"jpos1 forwordResult rtn is {forwordResult.tran.x} {forwordResult.tran.y} {forwordResult.tran.z} {forwordResult.rpy.rx} {forwordResult.rpy.ry} {forwordResult.rpy.rz}");
20}

8.31. Teachpunkt-Daten abrufen

1/**
2* @brief Gibt die Daten eines Robot-Teachpunkts zurück.
3* @param [in] name Punktname.
4* @param [out] data Punktdaten double[20] {x, y, z, rx, ry, rz, j1, j2, j3, j4, j5, j6, tool, wobj, speed, acc, e1, e2, e3, e4}.
5* @return Fehlercode.
6*/
7int GetRobotTeachingPoint(string name, ref double[] data);

8.32. DH-Parameter-Kompensationswerte abrufen

1/**
2* @brief Gibt die Kompensationswerte der Roboter-DH-Parameter zurück.
3* @param [out] dhCompensation DH-Parameter-Kompensationswerte in mm [cmpstD1, cmpstA2, cmpstA3, cmpstD4, cmpstD5, cmpstD6].
4* @return Fehlercode.
5*/
6int GetDHCompensation(ref double[] dhCompensation);

8.33. SN-Code des Steuerschranks abrufen

1/**
2* @brief Gibt den SN-Code des Steuerschranks zurück.
3* @param [out] SNCode SN-Code des Steuerschranks.
4* @return Fehlercode.
5*/
6int GetRobotSN(ref string SNCode);

8.34. Codebeispiel für das Abrufen von Teachpunkt-Daten

 1private void button31_Click(object sender, EventArgs e)
 2{
 3    string name = "A0";
 4    double[] data = new double[20];
 5    int rtn = robot.GetRobotTeachingPoint(name, ref data);
 6    Console.WriteLine(" {0} name is: {1} \n", rtn, name);
 7    for (int i = 0; i < 20; i++)
 8    {
 9        Console.WriteLine("data is: {0} \n", data[i]);
10    }
11
12    int que_len = 0;
13    rtn = robot.GetMotionQueueLength(ref que_len);
14    Console.WriteLine("GetMotionQueueLength rtn is: {0}, queue length is: {1} \n", rtn, que_len);
15
16    double[] dh = { 0, 0, 0, 0, 0, 0 };
17    int retval = 0;
18    retval = robot.GetDHCompensation(ref dh);
19    Console.WriteLine($"retval is  {retval}");
20    Console.WriteLine($"dh is {dh[0]}, {dh[1]}, {dh[2]}, {dh[3]}, {dh[4]}, {dh[5]}");
21    string SN = "";
22    robot.GetRobotSN(ref SN);
23    Console.WriteLine($"robot SN is  {SN}");
24}

8.35. Werkzeugkoordinatensystem anhand der ID abrufen

Neu in Version C#SDK-V1.1.8: Web-3.8.6

1/**
2* @brief Gibt das Werkzeugkoordinatensystem anhand der ID zurück.
3* @param [in] id Werkzeugkoordinatensystem-ID.
4* @param [out] coord Koordinatenwerte.
5* @return Fehlercode.
6*/
7int GetToolCoordWithID(int id, ref DescPose coord);

8.36. Werkstückkoordinatensystem anhand der ID abrufen

Neu in Version C#SDK-V1.1.8: Web-3.8.6

1/**
2* @brief Gibt das Werkstückkoordinatensystem anhand der ID zurück.
3* @param [in] id Werkstückkoordinatensystem-ID.
4* @param [out] coord Koordinatenwerte.
5* @return Fehlercode.
6*/
7public int GetWObjCoordWithID(int id, ref DescPose coord);

8.37. Externes Werkzeugkoordinatensystem anhand der ID abrufen

Neu in Version C#SDK-V1.1.8: Web-3.8.6

1/**
2* @brief Gibt das externe Werkzeugkoordinatensystem anhand der ID zurück.
3* @param [in] id Externe Werkzeugkoordinatensystem-ID.
4* @param [out] coord Koordinatenwerte.
5* @return Fehlercode.
6*/
7public int GetExToolCoordWithID(int id, ref DescPose coord);

8.38. Erweiterungsachsen-Koordinatensystem anhand der ID abrufen

Neu in Version C#SDK-V1.1.8: Web-3.8.6

1/**
2* @brief Gibt das Erweiterungsachsen-Koordinatensystem anhand der ID zurück.
3* @param [in] id Erweiterungsachsen-Koordinatensystem-ID.
4* @param [out] coord Koordinatenwerte.
5* @return Fehlercode.
6*/
7public int GetExAxisCoordWithID(int id, ref DescPose coord);

8.39. Aktuelles Werkzeugkoordinatensystem abrufen

Neu in Version C#SDK-V1.1.8: Web-3.8.6

1/**
2 * @brief Gibt das aktuelle Werkzeugkoordinatensystem zurück.
3 * @param [out] coord Koordinatenwerte.
4 * @return Fehlercode.
5 */
6public int GetCurToolCoord(ref DescPose coord);

8.40. Aktuelles Werkstückkoordinatensystem abrufen

Neu in Version C#SDK-V1.1.8: Web-3.8.6

1/**
2 * @brief Gibt das aktuelle Werkstückkoordinatensystem zurück.
3 * @param [out] coord Koordinatenwerte.
4 * @return Fehlercode.
5 */
6public int GetCurWObjCoord(ref DescPose coord);

8.41. Aktuelles externes Werkzeugkoordinatensystem abrufen

Neu in Version C#SDK-V1.1.8: Web-3.8.6

1/**
2 * @brief Gibt das aktuelle externe Werkzeugkoordinatensystem zurück.
3 * @param [out] coord Koordinatenwerte.
4 * @return Fehlercode.
5 */
6public int GetCurExToolCoord(ref DescPose coord);

8.42. Aktuelles Erweiterungsachsen-Koordinatensystem abrufen

Neu in Version C#SDK-V1.1.8: Web-3.8.6

1/**
2 * @brief Gibt das aktuelle Erweiterungsachsen-Koordinatensystem zurück.
3 * @param [out] coord Koordinatenwerte.
4 * @return Fehlercode.
5 */
6public int GetCurExAxisCoord(ref DescPose coord);

8.43. Codebeispiel für Roboter-Koordinatensysteme und Nutzlast

Neu in Version C#SDK-V1.1.8: Web-3.8.6

 1public void TestCoordMain()
 2{
 3    DescPose t_coord = new DescPose(0, 0, 0, 0, 0, 0);
 4    t_coord.tran.x = 1.0;
 5    t_coord.tran.y = 2.0;
 6    t_coord.tran.z = 300.0;
 7    t_coord.rpy.rx = 4.0;
 8    t_coord.rpy.ry = 5.0;
 9    t_coord.rpy.rz = 6.0;
10    int id = 1;
11    DescPose toolCoord = new DescPose();
12    robot.GetToolCoordWithID(id, ref toolCoord);
13    Console.WriteLine($"GetToolCoordWithID {id}, {toolCoord.tran.x} {toolCoord.tran.y} {toolCoord.tran.z} {toolCoord.rpy.rx} {toolCoord.rpy.ry} {toolCoord.rpy.rz}");
14    DescPose wobjCoord = new DescPose();
15    robot.GetWObjCoordWithID(id, ref wobjCoord);
16    Console.WriteLine($"GetWObjCoordWithID {id}, {wobjCoord.tran.x} {wobjCoord.tran.y} {wobjCoord.tran.z} {wobjCoord.rpy.rx} {wobjCoord.rpy.ry} {wobjCoord.rpy.rz}");
17    DescPose extoolCoord = new DescPose();
18    robot.GetExToolCoordWithID(id, ref extoolCoord);
19    Console.WriteLine($"GetExToolCoordWithID {id}, {extoolCoord.tran.x} {extoolCoord.tran.y} {extoolCoord.tran.z} {extoolCoord.rpy.rx} {extoolCoord.rpy.ry} {extoolCoord.rpy.rz}");
20    DescPose exAxisCoord = new DescPose();
21    robot.GetExAxisCoordWithID(id, ref exAxisCoord);
22    Console.WriteLine($"GetExAxisCoordWithID {id}, {exAxisCoord.tran.x} {exAxisCoord.tran.y} {exAxisCoord.tran.z} {exAxisCoord.rpy.rx} {exAxisCoord.rpy.ry} {exAxisCoord.rpy.rz}");
23    double weight = 0.0;
24    DescTran cog = new DescTran();
25    robot.GetTargetPayloadWithID(id, ref weight, ref cog);
26    Console.WriteLine($"GetTargetPayloadWithID {id}, {weight} {cog.x} {cog.y} {cog.z}");
27    robot.GetCurToolCoord(ref toolCoord);
28    Console.WriteLine($"GetCurToolCoord {toolCoord.tran.x} {toolCoord.tran.y} {toolCoord.tran.z} {toolCoord.rpy.rx} {toolCoord.rpy.ry} {toolCoord.rpy.rz}");
29
30    robot.GetCurWObjCoord(ref wobjCoord);
31    Console.WriteLine($"GetCurWObjCoord {wobjCoord.tran.x} {wobjCoord.tran.y} {wobjCoord.tran.z} {wobjCoord.rpy.rx} {wobjCoord.rpy.ry} {wobjCoord.rpy.rz}");
32    robot.GetCurExToolCoord(ref extoolCoord);
33    Console.WriteLine($"GetExToolCoordWithID {extoolCoord.tran.x} {extoolCoord.tran.y} {extoolCoord.tran.z} {extoolCoord.rpy.rx} {extoolCoord.rpy.ry} {extoolCoord.rpy.rz}");
34    robot.GetCurExAxisCoord(ref exAxisCoord);
35    Console.WriteLine($"GetCurExAxisCoord {exAxisCoord.tran.x} {exAxisCoord.tran.y} {exAxisCoord.tran.z} {exAxisCoord.rpy.rx} {exAxisCoord.rpy.ry} {exAxisCoord.rpy.rz}");
36    double weightT = 0.0f;
37    DescTran cogT = new DescTran();
38    robot.GetTargetPayload(0, ref weightT);
39    robot.GetTargetPayloadCog(0, ref cogT);
40    Console.WriteLine($"GetTargetPayload {weightT} {cogT.x} {cogT.y} {cogT.z}");
41    DescPose coordSet = new DescPose(0, 10, 2, 3, 4, 5);
42    robot.SetToolCoord(2, coordSet, 0, 0, 1, 0);
43    DescPose Coordset0 = new DescPose(0, 0, 0, 0, 0, 0);
44    DescPose Coordset = new DescPose(1, 2, 3, 4, 5, 6);
45    DescPose etcp = new DescPose(10, 20, 30, 40, 50, 60);
46    DescPose etctool = new DescPose(0.1, 0.2, 0.3, 0.4, 0.5, 0.6);
47    robot.SetToolCoord(id, Coordset, 0, 0, 1, 0);
48    Thread.Sleep(100);
49    robot.SetWObjCoord(id, Coordset, 0);
50    Thread.Sleep(100);
51    robot.ExtAxisActiveECoordSys(id, 1, Coordset, 0);
52    Thread.Sleep(100);
53    robot.SetExToolCoord(id, etcp, etctool);
54    Thread.Sleep(100);
55    robot.SetLoadWeight(id, (float)1.5);
56    //Thread.Sleep(500);
57    robot.SetLoadCoord(id, cog);
58    Thread.Sleep(100);
59}