8. Query Stato Robot
8.1. Ottenere Posizione Articolare Corrente (Gradi)
1/**
2* @brief Ottenere Posizione Articolare Corrente (Gradi)
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] jPos Sei posizioni articolari, unità deg
5* @return Codice errore
6*/
7int GetActualJointPosDegree(byte flag, ref JointPos jPos);
8.2. Ottenere Posizione Articolare Corrente (Radianti)
1/**
2* @brief Ottenere Posizione Articolare Corrente (Radianti)
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] jPos Sei posizioni articolari, unità rad
5* @return Codice errore
6*/
7int GetActualJointPosRadian(byte flag, ref JointPos jPos);
8.3. Ottenere Velocità Feedback Articolare
1/**
2* @brief Ottenere Velocità Feedback Articolare-deg/s
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] speed Sei velocità articolari
5* @return Codice errore
6*/
7int GetActualJointSpeedsDegree(byte flag, ref double[] speed);
8.4. Ottenere Accelerazione Feedback Articolare
1/**
2* @brief Ottenere Accelerazione Feedback Articolare-deg/s^2
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] acc Sei accelerazioni articolari
5* @return Codice errore
6*/
7int GetActualJointAccDegree(byte flag, ref double[] acc);
8.5. Ottenere Velocità Comando TCP - Velocità Totale
1/**
2* @brief Ottenere Velocità Comando TCP - Velocità Totale
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] tcp_speed Velocità lineare
5* @param [out] ori_speed Velocità orientamento
6* @return Codice errore
7*/
8int GetTargetTCPCompositeSpeed(byte flag, ref double tcp_speed, ref double ori_speed);
8.6. Ottenere Velocità Feedback TCP - Velocità Totale
1/**
2* @brief Ottenere Velocità Feedback TCP - Velocità Totale
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] tcp_speed Velocità lineare
5* @param [out] ori_speed Velocità orientamento
6* @return Codice errore
7*/
8int GetActualTCPCompositeSpeed(byte flag, ref double tcp_speed, ref double ori_speed);
8.7. Ottenere Velocità Comando TCP - Velocità Componenti
1/**
2* @brief Ottenere Velocità Comando TCP - Velocità Componenti
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] speed [x,y,z,rx,ry,rz] velocità
5* @return Codice errore
6*/
7int GetTargetTCPSpeed(byte flag, ref double[] speed);
8.8. Ottenere Velocità Feedback TCP - Velocità Componenti
1/**
2* @brief Ottenere Velocità Feedback TCP - Velocità Componenti
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] speed [x,y,z,rx,ry,rz] velocità
5* @return Codice errore
6*/
7int GetActualTCPSpeed(byte flag, ref double[] speed);
8.9. Ottenere Posa Utensile Corrente
1/**
2* @brief Ottenere Posa Utensile Corrente
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] desc_pos Posa utensile
5* @return Codice errore
6*/
7int GetActualTCPPose(byte flag, ref DescPose desc_pos);
8.10. Ottenere Numero Sistema Coordinate Utensile Corrente
1/**
2* @brief Ottenere Numero Sistema Coordinate Utensile Corrente
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] id Numero sistema coordinate utensile
5* @return Codice errore
6*/
7int GetActualTCPNum(byte flag, ref int id);
8.11. Ottenere Numero Sistema Coordinate Pezzo Corrente
1/**
2* @brief Ottenere Numero Sistema Coordinate Pezzo Corrente
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] id Numero sistema coordinate pezzo
5* @return Codice errore
6*/
7int GetActualWObjNum(byte flag, ref int id);
8.12. Ottenere Posa Flangia Estremità Corrente
1/**
2* @brief Ottenere Posa Flangia Estremità Corrente
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] desc_pos Posa flangia
5* @return Codice errore
6*/
7int GetActualToolFlangePose(byte flag, ref DescPose desc_pos);
8.13. Ottenere Coppia Articolare Corrente
1/**
2* @brief Ottenere Coppia Articolare Corrente
3* @param [in] flag 0-bloccante, 1-non bloccante
4* @param [out] torques Coppia articolare
5* @return Codice errore
6*/
7int GetJointTorques(byte flag, float[] torques);
8.14. Ottenere l’Ora di Sistema
1/**
2* @brief Ottenere l'ora di sistema
3* @param [out] t_ms Unità ms, può essere convertita secondo il tempo UTC. Quando il robot è in stato di guasto, GetSystemClock restituisce 0 e restituisce un codice di errore.
4* @return Codice di errore
5*/
6public int GetSystemClock(ref double t_ms)
8.15. Verificare Se Movimento Robot Completato
1/**
2* @brief Verificare Se Movimento Robot Completato
3* @param [out] state 0-non completato, 1-completato
4* @return Codice errore
5*/
6int GetRobotMotionDone(ref byte state);
8.16. Verificare Lunghezza Coda Cache Movimento Robot
1/**
2* @brief Verificare Lunghezza Coda Cache Movimento Robot
3* @param [out] len Lunghezza cache
4* @return Codice errore
5*/
6int GetMotionQueueLength(ref int len);
8.17. Ottenere Stato Arresto Emergenza Robot
1/**
2* @brief Ottenere Stato Arresto Emergenza Robot
3* @param [out] state Stato arresto emergenza, 0-non arresto emergenza, 1-arresto emergenza
4* @return Codice errore
5*/
6int GetRobotEmergencyStopState(ref byte state);
8.18. Ottenere Stato Comunicazione SDK con Robot
1/**
2* @brief Ottenere Stato Comunicazione SDK con Robot
3* @param [out] state Stato comunicazione, 0-comunicazione normale, 1-comunicazione anomala
4*/
5int GetSDKComState(ref int state);
8.19. Ottenere Segnale Arresto Sicurezza
1/**
2* @brief Ottenere Segnale Arresto Sicurezza
3* @param [out] si0_state Segnale arresto sicurezza SI0, 0-non valido, 1-valido
4* @param [out] si1_state Segnale arresto sicurezza SI1, 0-non valido, 1-valido
5*/
6int GetSafetyStopState(ref byte si0_state, ref byte si1_state);
8.20. Ottenere Temperatura Azionamento Articolare Robot (℃)
1/**
2* @brief Ottenere Temperatura Azionamento Articolare Robot (℃)
3* @return Codice errore
4*/
5int GetJointDriverTemperature(double[] temperature);
8.21. Ottenere Coppia Azionamento Articolare Robot (Nm)
1/**
2* @brief Ottenere Coppia Azionamento Articolare Robot (Nm)
3* @return Codice errore
4*/
5int GetJointDriverTorque(double torque[]);
8.22. Ottenere l’Ultimo Frame dei Dati di Stato in Tempo Reale del Robot (Modifica del Meccanismo Interno)
1/**
2* @brief Ottenere l'ultimo frame dei dati di stato in tempo reale del robot (thread interno si aggiorna continuamente, questa interfaccia restituisce direttamente i dati dalla cache)
3* @param [out] pkg Parametro di riferimento per ricevere i dati di stato del robot (struttura ROBOT_STATE_PKG)
4* @return Restituisce 0 in caso di successo; restituisce un codice di errore negativo in caso di fallimento (es. errore di comunicazione di rete)
5*/
6public int GetRobotRealTimeState(ref ROBOT_STATE_PKG pkg)
8.23. Esempio Codice Query Stato Robot
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. Calcolo Cinematica Inversa
1/**
2* @brief Calcolo Cinematica Inversa
3* @param [in] type 0-posa assoluta (sistema base), 1-posa incrementale (sistema base), 2-posa incrementale (sistema utensile)
4* @param [in] desc_pos Posa cartesiana
5* @param [in] config Configurazione spazio articolare, [-1]-calcolo riferimento posizione articolare corrente, [0~7]-soluzione basata configurazione spazio articolare specifica
6* @param [out] joint_pos Posizione articolare
7* @return Codice errore
8*/
9int GetInverseKin(int type, DescPose desc_pos, int config, ref JointPos joint_pos);
8.25. Calcolo Cinematica Inversa (Riferimento Posizione)
1/**
2* @brief Calcolo Cinematica Inversa, riferimento posizione articolare specificata per verificare se soluzione esiste
3* @param [in] type 0-posa assoluta (sistema base), 1-posa incrementale (sistema base), 2-posa incrementale (sistema utensile)
4* @param [in] desc_pos Posa cartesiana
5* @param [in] joint_pos_ref Posizione articolare riferimento
6* @param [out] result 0-nessuna soluzione, 1-soluzione esistente
7* @return Codice errore
8*/
9int GetInverseKinRef(int posMode, DescPose desc_pos, JointPos joint_pos_ref, ref JointPos joint_pos);
8.26. Soluzione Cinematica Inversa, Spazio Cartesiano Include Posizione Asse Esteso
1/**
2* @brief Soluzione cinematica inversa, spazio cartesiano include posizione asse esteso
3* @param [in] type 0-Posa assoluta (sistema coordinate base), 1-Posa incrementale (sistema coordinate base), 2-Posa incrementale (sistema coordinate utensile)
4* @param [in] desc_pos Posa cartesiana
5* @param [in] exaxis Posizione asse esteso
6* @param [in] tool Numero utensile
7* @param [in] workPiece Numero pezzo
8* @param [out] joint_pos Posizione giunto
9* @return Codice errore
10*/
11public int GetInverseKinExaxis(int type, DescPose desc_pos, ExaxisPos exaxis, int tool, int workPiece, ref JointPos joint_pos);
8.27. Esempio di Codice per Soluzione di Cinematica Inversa Inclusa Posizione dell’Asse Esteso
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. Verificare Se Esiste Soluzione Cinematica Inversa
1/**
2* @brief Calcolo Cinematica Inversa, verificare se esiste soluzione per posizione articolare riferimento specificata
3* @param [in] posMode 0 posa assoluta, 1 posa relativa-sistema base, 2 posa relativa-sistema utensile
4* @param [in] desc_pos Posa cartesiana
5* @param [in] joint_pos_ref Posizione articolare riferimento
6* @param [out] hasResult 0-nessuna soluzione, 1-soluzione esistente
7* @return Codice errore
8*/
9int GetInverseKinHasSolution(int posMode, DescPose desc_pos, JointPos joint_pos_ref, ref bool hasResult);
8.29. Calcolo Cinematica Diretta
1/**
2* @brief Calcolo Cinematica Diretta
3* @param [in] joint_pos Posizione articolare
4* @param [out] desc_pos Posa cartesiana
5* @return Codice errore
6*/
7int GetForwardKin(JointPos joint_pos, ref DescPose desc_pos);
8.30. Esempio Codice Calcolo Cinematica Diretta/Inversa Robot
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. Verificare Dati Punti Gestione Insegnamento Robot
1/**
2* @brief Verificare Dati Punti Gestione Insegnamento Robot
3* @param [in] name Nome punto
4* @param [out] data Dati punto double[20]{x,y,z,rx,ry,rz,j1,j2,j3,j4,j5,j6,tool, wobj,speed,acc,e1,e2,e3,e4}
5* @return Codice errore
6*/
7int GetRobotTeachingPoint(string name, ref double[] data);
8.32. Ottenere Valori Compensazione Parametri DH Robot
1/**
2* @brief Ottenere Valori Compensazione Parametri DH Robot
3* @param [out] dhCompensation Valori compensazione parametri DH robot(mm) [cmpstD1,cmpstA2,cmpstA3,cmpstD4,cmpstD5,cmpstD6]
4* @return Codice errore
5*/
6int GetDHCompensation(ref double[] dhCompensation);
8.33. Ottenere Codice SN Quadro Controllo
1/**
2* @brief Ottenere Codice SN Quadro Controllo
3* @param [out] SNCode Codice SN quadro controllo
4* @return Codice errore
5*/
6int GetRobotSN(ref string SNCode);
8.34. Esempio Codice Verifica Dati Punti Gestione Insegnamento Robot
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. Ottenere Sistema Coordinate Utensile in Base al Numero
Nuovo nella versione C#SDK-V1.1.8: Web-3.8.6
1/**
2* @brief Ottenere Sistema Coordinate Utensile in Base al Numero
3* @param [in] id Numero sistema coordinate utensile
4* @param [out] coord Valori coefficienti coordinate
5* @return Codice errore
6*/
7int GetToolCoordWithID(int id,ref DescPose coord)
8.36. Ottenere Sistema Coordinate Pezzo in Base al Numero
Nuovo nella versione C#SDK-V1.1.8: Web-3.8.6
1/**
2* @brief Ottenere Sistema Coordinate Pezzo in Base al Numero
3* @param [in] id Numero sistema coordinate pezzo
4* @param [out] coord Valori coefficienti coordinate
5* @return Codice errore
6*/
7public int GetWObjCoordWithID(int id, ref DescPose coord)
8.37. Ottenere Sistema Coordinate Utensile Esterno in Base al Numero
Nuovo nella versione C#SDK-V1.1.8: Web-3.8.6
1/**
2* @brief Ottenere Sistema Coordinate Utensile Esterno in Base al Numero
3* @param [in] id Numero sistema coordinate utensile esterno
4* @param [out] coord Valori coefficienti coordinate
5* @return Codice errore
6*/
7public int GetExToolCoordWithID(int id, ref DescPose coord)
8.38. Ottenere Sistema Coordinate Asse Esteso in Base al Numero
Nuovo nella versione C#SDK-V1.1.8: Web-3.8.6
1/**
2* @brief Ottenere Sistema Coordinate Asse Esteso in Base al Numero
3* @param [in] id Numero sistema coordinate utensile esterno
4* @param [out] coord Valori coefficienti coordinate
5* @return Codice errore
6*/
7public int GetExAxisCoordWithID(int id, ref DescPose coord)
8.39. Ottenere Sistema Coordinate Utensile Corrente
Nuovo nella versione C#SDK-V1.1.8: Web-3.8.6
1/**
2 * @brief Ottenere Sistema Coordinate Utensile Corrente
3 * @param [out] coord Valori coefficienti coordinate
4 * @return Codice errore
5 */
6public int GetCurToolCoord(ref DescPose coord)
8.40. Ottenere Sistema Coordinate Pezzo Corrente
Nuovo nella versione C#SDK-V1.1.8: Web-3.8.6
1/**
2 * @brief Ottenere Sistema Coordinate Pezzo Corrente
3 * @param [out] coord Valori coefficienti coordinate
4 * @return Codice errore
5 */
6public int GetCurWObjCoord(ref DescPose coord)
8.41. Ottenere Sistema Coordinate Utensile Esterno Corrente
Nuovo nella versione C#SDK-V1.1.8: Web-3.8.6
1/**
2 * @brief Ottenere Sistema Coordinate Utensile Esterno Corrente
3 * @param [out] coord Valori coefficienti coordinate
4 * @return Codice errore
5 */
6public int GetCurExToolCoord(ref DescPose coord)
8.42. Ottenere Sistema Coordinate Asse Esteso Corrente
Nuovo nella versione C#SDK-V1.1.8: Web-3.8.6
1/**
2 * @brief Ottenere Sistema Coordinate Asse Esteso Corrente
3 * @param [out] coord Valori coefficienti coordinate
4 * @return Codice errore
5 */
6public int GetCurExAxisCoord(ref DescPose coord)
8.43. Esempio Codice Ottenimento Sistemi Coordinate e Carico Robot
Nuovo nella versione 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}