RoboDK API - Documentation
robodk_api.cpp
1#include "robodk_api.h"
2#include <QtNetwork/QTcpSocket>
3#include <QtCore/QProcess>
4#include <cmath>
5#include <algorithm>
6#include <QFile>
7
8
9#ifdef _WIN32
10// Default path on Windows:
11#define ROBODK_DEFAULT_PATH_BIN "C:/RoboDK/bin/RoboDK.exe"
12
13#elif __APPLE__
14// Default Install Path on Mac
15#define ROBODK_DEFAULT_PATH_BIN "~/RoboDK/Applications/RoboDK.app/Contents/MacOS/RoboDK"
16
17#else
18
19// Default Install Path on Linux:
20#define ROBODK_DEFAULT_PATH_BIN "~/RoboDK/bin/RoboDK"
21
22#endif
23
24#define ROBODK_DEFAULT_PORT 20500
25
26#define ROBODK_API_TIMEOUT 1000 // communication timeout. Raise this value for slow computers
27#define ROBODK_API_START_STRING "CMD_START"
28#define ROBODK_API_READY_STRING "READY"
29#define ROBODK_API_LF "\n"
30
31
32
33#define M_PI 3.14159265358979323846264338327950288
34
35
36#ifndef RDK_SKIP_NAMESPACE
37namespace RoboDK_API {
38#endif
39
40
41//----------------------------------- Joints class ------------------------
43 _nDOFs = qMin(ndofs, RDK_SIZE_JOINTS_MAX);
44 for (int i=0; i<_nDOFs; i++){
45 _Values[i] = 0.0;
46 }
47}
49 SetValues(copy._Values, copy._nDOFs);
50}
51tJoints::tJoints(const double *joints, int ndofs){
52 SetValues(joints, ndofs);
53}
54tJoints::tJoints(const float *joints, int ndofs){
55 int ndofs_ok = qMin(ndofs, RDK_SIZE_JOINTS_MAX);
56 double jnts[RDK_SIZE_JOINTS_MAX];
57 for (int i=0; i<ndofs_ok; i++){
58 jnts[i] = joints[i];
59 }
60 SetValues(jnts, ndofs_ok);
61}
62tJoints::tJoints(const tMatrix2D *mat2d, int column, int ndofs){
63 int ncols = Matrix2D_Size(mat2d, 2);
64 if (column >= ncols){
65 _nDOFs = 0;
66 qDebug()<<"Warning: tMatrix2D column outside range when creating joints";
67 }
68 if (ndofs < 0){
69 ndofs = Matrix2D_Size(mat2d, 1);
70 }
71 _nDOFs = qMin(ndofs, RDK_SIZE_JOINTS_MAX);
72 double *ptr = Matrix2D_Get_col(mat2d, column);
73 SetValues(ptr, _nDOFs);
74}
75tJoints::tJoints(const QString &str){
76 _nDOFs = 0;
77 FromString(str);
78}
79
80const double* tJoints::ValuesD() const{
81 return _Values;
82}
83const float* tJoints::ValuesF() const{
84 for (int i=0; i<RDK_SIZE_JOINTS_MAX; i++){
85 ((float*)_ValuesF)[i] = _Values[i];
86 }
87 return _ValuesF;
88}
89#ifdef ROBODK_API_FLOATS
90const float* tJoints::Values() const{
91 return ValuesF();
92}
93#else
94const double* tJoints::Values() const{
95 return _Values;
96}
97#endif
98
99double* tJoints::Data(){
100 return _Values;
101}
102
103
104void tJoints::SetValues(const double *values, int ndofs){
105 if (ndofs >= 0){
106 _nDOFs = qMin(ndofs, RDK_SIZE_JOINTS_MAX);
107 }
108 for (int i=0; i<_nDOFs; i++){
109 _Values[i] = values[i];
110 }
111}
112
113void tJoints::SetValues(const float *values, int ndofs){
114 if (ndofs >= 0){
115 _nDOFs = qMin(ndofs, RDK_SIZE_JOINTS_MAX);
116 }
117 for (int i=0; i<_nDOFs; i++){
118 _Values[i] = values[i];
119 }
120}
121int tJoints::GetValues(double *values){
122 for (int i=0; i<_nDOFs; i++){
123 values[i] = _Values[i];
124 }
125 return _nDOFs;
126}
127QString tJoints::ToString(const QString &separator, int precision) const {
128 if (!Valid()){
129 return "tJoints(Invalid)";
130 }
131 QString values("tJoints({");
132 if (_nDOFs <= 0){
133 return values;
134 }
135 values.append(QString::number(_Values[0],'f',precision));
136 for (int i=1; i<_nDOFs; i++){
137 values.append(separator);
138 values.append(QString::number(_Values[i],'f',precision));
139 }
140 values.append("} , " + QString::number(_nDOFs) + ")");
141 return values;
142}
143bool tJoints::FromString(const QString &str){
144 QStringList jnts_list = QString(str).replace(";",",").replace("\t",",").split(",", QString::SkipEmptyParts);
145 _nDOFs = qMin(jnts_list.length(), RDK_SIZE_JOINTS_MAX);
146 for (int i=0; i<_nDOFs; i++){
147 QString stri(jnts_list.at(i));
148 _Values[i] = stri.trimmed().toDouble();
149 }
150 return true;
151}
152
153int tJoints::Length() const {
154 return _nDOFs;
155}
156
157void tJoints::setLength(int new_length) {
158 if (new_length >= 0 && new_length < _nDOFs){
159 _nDOFs = new_length;
160 }
161}
162
163bool tJoints::Valid() const {
164 return _nDOFs > 0;
165}
166//---------------------------------------------------------------------
167
168
169
170
171
172
173Mat transl(double x, double y, double z){
174 return Mat::transl(x,y,z);
175}
176
177Mat rotx(double rx){
178 return Mat::rotx(rx);
179}
180
181Mat roty(double ry){
182 return Mat::roty(ry);
183}
184
185Mat rotz(double rz){
186 return Mat::rotz(rz);
187}
188
189Mat::Mat() : QMatrix4x4() {
190 _valid = true;
191 setToIdentity();
192}
193Mat::Mat(bool valid) : QMatrix4x4() {
194 _valid = valid;
195 setToIdentity();
196}
197
198Mat::Mat(const QMatrix4x4 &matrix) : QMatrix4x4(matrix) {
199 // just copy
200 _valid = true;
201}
202Mat::Mat(const Mat &matrix) : QMatrix4x4(matrix) {
203 // just copy
204 _valid = matrix._valid;
205}
206
207Mat::Mat(double nx, double ox, double ax, double tx, double ny, double oy, double ay, double ty, double nz, double oz, double az, double tz) :
208 QMatrix4x4(nx, ox, ax, tx, ny, oy, ay, ty, nz, oz, az, tz, 0,0,0,1)
209{
210 _valid = true;
211}
212Mat::Mat(const double v[16]) :
213 QMatrix4x4(v[0], v[4], v[8], v[12], v[1], v[5], v[9], v[13], v[2], v[6], v[10], v[14], v[3], v[7], v[11], v[15])
214{
215 _valid = true;
216}
217Mat::Mat(const float v[16]) :
218 QMatrix4x4(v[0], v[4], v[8], v[12], v[1], v[5], v[9], v[13], v[2], v[6], v[10], v[14], v[3], v[7], v[11], v[15])
219{
220 _valid = true;
221}
222
223
224
225Mat::~Mat(){
226
227}
228
229
230void Mat::VX(tXYZ xyz) const {
231 xyz[0] = Get(0, 0);
232 xyz[1] = Get(1, 0);
233 xyz[2] = Get(2, 0);
234}
235void Mat::VY(tXYZ xyz) const {
236 xyz[0] = Get(0, 1);
237 xyz[1] = Get(1, 1);
238 xyz[2] = Get(2, 1);
239}
240void Mat::VZ(tXYZ xyz) const {
241 xyz[0] = Get(0, 2);
242 xyz[1] = Get(1, 2);
243 xyz[2] = Get(2, 2);
244}
245void Mat::Pos(tXYZ xyz) const {
246 xyz[0] = Get(0, 3);
247 xyz[1] = Get(1, 3);
248 xyz[2] = Get(2, 3);
249}
250void Mat::setVX(double x, double y, double z){
251 Set(0,0, x);
252 Set(1,0, y);
253 Set(2,0, z);
254}
255void Mat::setVY(double x, double y, double z){
256 Set(0,1, x);
257 Set(1,1, y);
258 Set(2,1, z);
259}
260
261void Mat::setVZ(double x, double y, double z){
262 Set(0,2, x);
263 Set(1,2, y);
264 Set(2,2, z);
265}
266
267void Mat::setPos(double x, double y, double z){
268 Set(0,3, x);
269 Set(1,3, y);
270 Set(2,3, z);
271}
272void Mat::setVX(double xyz[3]){
273 Set(0,0, xyz[0]);
274 Set(1,0, xyz[1]);
275 Set(2,0, xyz[2]);
276}
277void Mat::setVY(double xyz[3]){
278 Set(0,1, xyz[0]);
279 Set(1,1, xyz[1]);
280 Set(2,1, xyz[2]);
281}
282void Mat::setVZ(double xyz[3]){
283 Set(0,2, xyz[0]);
284 Set(1,2, xyz[1]);
285 Set(2,2, xyz[2]);
286}
287void Mat::setPos(double xyz[3]){
288 Set(0,3, xyz[0]);
289 Set(1,3, xyz[1]);
290 Set(2,3, xyz[2]);
291}
292
293void Mat::Set(int i, int j, double value){
294 QVector4D rw(this->row(i));
295 rw[j] = value;
296 setRow(i, rw);
297 // the following should not crash!!
298 //float **dt_ok = (float**) data();
299 //dt_ok[i][j] = value;
300}
301
302double Mat::Get(int i, int j) const{
303 return row(i)[j];
304 // the following hsould be allowed!!
305 //return ((const float**)data())[i][j];
306}
307
308
309Mat Mat::inv() const{
310 return this->inverted();
311}
312
313bool Mat::isHomogeneous() const {
314 const bool debug_info = false;
315 tXYZ vx, vy, vz;
316 const double tol = 1e-7;
317 VX(vx);
318 VY(vy);
319 VZ(vz);
320 if (fabs((double) DOT(vx,vy)) > tol){
321 if (debug_info){
322 qDebug() << "Vector X and Y are not perpendicular!";
323 }
324 return false;
325 } else if (fabs((double) DOT(vx,vz)) > tol){
326 if (debug_info){
327 qDebug() << "Vector X and Z are not perpendicular!";
328 }
329 return false;
330 } else if (fabs((double) DOT(vy,vz)) > tol){
331 if (debug_info){
332 qDebug() << "Vector Y and Z are not perpendicular!";
333 }
334 return false;
335 } else if (fabs((double) (NORM(vx)-1.0)) > tol){
336 if (debug_info){
337 qDebug() << "Vector X is not unitary! " << NORM(vx);
338 }
339 return false;
340 } else if (fabs((double) (NORM(vy)-1.0)) > tol){
341 if (debug_info){
342 qDebug() << "Vector Y is not unitary! " << NORM(vy);
343 }
344 return false;
345 } else if (fabs((double) (NORM(vz)-1.0)) > tol){
346 if (debug_info){
347 qDebug() << "Vector Z is not unitary! " << NORM(vz);
348 }
349 return false;
350 }
351 return true;
352}
353
355 tXYZ vx, vy, vz;
356 VX(vx);
357 VY(vy);
358 VZ(vz);
359 bool is_homogeneous = isHomogeneous();
360 //if (is_homogeneous){
361 // return false;
362 //}
363
364 NORMALIZE(vx);
365 CROSS(vz, vx, vy);
366 NORMALIZE(vz);
367 CROSS(vy, vz, vx);
368 NORMALIZE(vy);
369 setVX(vx);
370 setVY(vy);
371 setVZ(vz);
372 Set(3,0, 0.0);
373 Set(3,1, 0.0);
374 Set(3,2, 0.0);
375 Set(3,3, 1.0);
376 return !is_homogeneous;
377}
378
379
380//----------------------------------------------------
381
382void Mat::ToXYZRPW(tXYZWPR xyzwpr) const{
383 double x = Get(0,3);
384 double y = Get(1,3);
385 double z = Get(2,3);
386 double w, p, r;
387 if (Get(2,0) > (1.0 - 1e-6)){
388 p = -M_PI*0.5;
389 r = 0;
390 w = atan2(-Get(1,2), Get(1,1));
391 } else if (Get(2,0) < -1.0 + 1e-6){
392 p = 0.5*M_PI;
393 r = 0;
394 w = atan2(Get(1,2),Get(1,1));
395 } else {
396 p = atan2(-Get(2, 0), sqrt(Get(0, 0) * Get(0, 0) + Get(1, 0) * Get(1, 0)));
397 w = atan2(Get(1, 0), Get(0, 0));
398 r = atan2(Get(2, 1), Get(2, 2));
399 }
400 xyzwpr[0] = x;
401 xyzwpr[1] = y;
402 xyzwpr[2] = z;
403 xyzwpr[3] = r*180.0/M_PI;
404 xyzwpr[4] = p*180.0/M_PI;
405 xyzwpr[5] = w*180.0/M_PI;
406}
407
408QString Mat::ToString(const QString &separator, int precision, bool xyzwpr_only) const {
409 if (!Valid()){
410 return "Mat(Invalid)";
411 }
412 QString str;
413 if (!isHomogeneous()){
414 str.append("Warning!! Pose is not homogeneous! Use Mat::MakeHomogeneous() to make this matrix homogeneous\n");
415 }
416 str.append("Mat(XYZRPW_2_Mat(");
417
418 tXYZWPR xyzwpr;
419 ToXYZRPW(xyzwpr);
420 str.append(QString::number(xyzwpr[0],'f',precision));
421 for (int i=1; i<6; i++){
422 str.append(separator);
423 str.append(QString::number(xyzwpr[i],'f',precision));
424 }
425 str.append("))");
426
427 if (xyzwpr_only){
428 return str;
429 }
430 str.append("\n");
431 for (int i=0; i<4; i++){
432 str.append("[");
433 for (int j=0; j<4; j++){
434 str.append(QString::number(row(i)[j], 'f', precision));
435 if (j < 3){
436 str.append(separator);
437 }
438 }
439 str.append("];\n");
440 }
441 return str;
442}
443
444bool Mat::FromString(const QString &pose_str){
445 QStringList values_list = QString(pose_str).replace(";",",").replace("\t",",").split(",", QString::SkipEmptyParts);
446 int nvalues = qMin(values_list.length(), 6);
447 tXYZWPR xyzwpr;
448 for (int i=0; i<6; i++){
449 xyzwpr[i] = 0.0;
450 }
451 if (nvalues < 6){
452 FromXYZRPW(xyzwpr);
453 return false;
454 }
455 for (int i=0; i<nvalues; i++){
456 QString stri(values_list.at(i));
457 xyzwpr[i] = stri.trimmed().toDouble();
458 }
459 FromXYZRPW(xyzwpr);
460 return true;
461}
462
463
464Mat Mat::XYZRPW_2_Mat(double x, double y, double z, double r, double p, double w){
465 double a = r * M_PI / 180.0;
466 double b = p * M_PI / 180.0;
467 double c = w * M_PI / 180.0;
468 double ca = cos(a);
469 double sa = sin(a);
470 double cb = cos(b);
471 double sb = sin(b);
472 double cc = cos(c);
473 double sc = sin(c);
474 return Mat(cb * cc, cc * sa * sb - ca * sc, sa * sc + ca * cc * sb, x, cb * sc, ca * cc + sa * sb * sc, ca * sb * sc - cc * sa, y, -sb, cb * sa, ca * cb, z);
475}
477 return XYZRPW_2_Mat(xyzwpr[0], xyzwpr[1], xyzwpr[2], xyzwpr[3], xyzwpr[4], xyzwpr[5]);
478}
479
481 Mat newmat = Mat::XYZRPW_2_Mat(xyzwpr[0], xyzwpr[1], xyzwpr[2], xyzwpr[3], xyzwpr[4], xyzwpr[5]);
482 for (int i=0; i<4; i++){
483 for (int j=0; j<4; j++){
484 this->Set(i,j, newmat.Get(i,j));
485 }
486 }
487}
488
489const double* Mat::ValuesD() const {
490 double* _ddata16_non_const = (double*) _ddata16;
491 for(int i=0; i<16; ++i){
492 _ddata16_non_const[i] = constData()[i];
493 }
494 return _ddata16;
495}
496const float* Mat::ValuesF() const {
497 return constData();
498}
499
500#ifdef ROBODK_API_FLOATS
501const float* Mat::Values() const {
502 return constData();
503}
504#else
505const double* Mat::Values() const {
506 return ValuesD();
507}
508
509#endif
510
511
512
513void Mat::Values(double data[16]) const{
514 for(int i=0; i<16; ++i){
515 data[i] = constData()[i];
516 }
517}
518void Mat::Values(float data[16]) const{
519 for(int i=0; i<16; ++i){
520 data[i] = constData()[i];
521 }
522}
523bool Mat::Valid() const{
524 return _valid;
525}
526
527Mat Mat::transl(double x, double y, double z){
528 Mat mat;
529 mat.setToIdentity();
530 mat.setPos(x, y, z);
531 return mat;
532}
533
534Mat Mat::rotx(double rx){
535 double cx = cos(rx);
536 double sx = sin(rx);
537 return Mat(1, 0, 0, 0, 0, cx, -sx, 0, 0, sx, cx, 0);
538}
539
540Mat Mat::roty(double ry){
541 double cy = cos(ry);
542 double sy = sin(ry);
543 return Mat(cy, 0, sy, 0, 0, 1, 0, 0, -sy, 0, cy, 0);
544}
545
546Mat Mat::rotz(double rz){
547 double cz = cos(rz);
548 double sz = sin(rz);
549 return Mat(cz, -sz, 0, 0, sz, cz, 0, 0, 0, 0, 1, 0);
550}
551
552
553
554
555//---------------------------------------------------------------------------------------------------
556//---------------------------------------------------------------------------------------------------
557//---------------------------------------------------------------------------------------------------
558//---------------------------------------------------------------------------------------------------
560Item::Item(RoboDK *rdk, quint64 ptr, qint32 type) {
561 _RDK = rdk;
562 _PTR = ptr;
563 _TYPE = type;
564}
565Item::Item(const Item &other) {
566 _RDK = other._RDK;
567 _PTR = other._PTR;
568 _TYPE = other._TYPE;
569}
570Item::~Item(){
571
572}
573
574QString Item::ToString() const {
575 if (this->Valid()){
576 return QString("Item(&RDK, %1, %2); // %3").arg(_PTR).arg(_TYPE).arg(Name());
577 }
578 return "Item(Invalid)";
579}
580
581
587 return _RDK;
588}
589
594 _RDK = new RoboDK();
595}
596
602int Item::Type() const{
603 _RDK->_check_connection();
604 _RDK->_send_Line("G_Item_Type");
605 _RDK->_send_Item(this);
606 int itemtype = _RDK->_recv_Int();
607 _RDK->_check_status();
608 return itemtype;
609}
610
612
617void Item::Save(const QString &filename){
618 _RDK->Save(filename, this);
619}
620
625 _RDK->_check_connection();
626 _RDK->_send_Line("Remove");
627 _RDK->_send_Item(this);
628 _RDK->_check_status();
629 _PTR = 0;
630 _TYPE = -1;
631}
632
637bool Item::Valid(bool check_deleted) const {
638 if (check_deleted){
639 return Type() > 0;
640 }
641 return _PTR != 0;
642}
648 _RDK->_check_connection();
649 _RDK->_send_Line("S_Parent");
650 _RDK->_send_Item(this);
651 _RDK->_send_Item(parent);
652 _RDK->_check_status();
653}
654
661 _RDK->_check_connection();
662 _RDK->_send_Line("S_Parent_Static");
663 _RDK->_send_Item(this);
664 _RDK->_send_Item(parent);
665 _RDK->_check_status();
666}
667
673 _RDK->_check_connection();
674 _RDK->_send_Line("Attach_Closest");
675 _RDK->_send_Item(this);
676 Item item_attached = _RDK->_recv_Item();
677 _RDK->_check_status();
678 return item_attached;
679}
680
686 _RDK->_check_connection();
687 _RDK->_send_Line("Detach_Closest");
688 _RDK->_send_Item(this);
689 _RDK->_send_Item(parent);
690 Item item_detached = _RDK->_recv_Item();
691 _RDK->_check_status();
692 return item_detached;
693}
694
698void Item::DetachAll(Item parent) {
699 _RDK->_check_connection();
700 _RDK->_send_Line("Detach_All");
701 _RDK->_send_Item(this);
702 _RDK->_send_Item(parent);
703 _RDK->_check_status();
704}
705
706
712 _RDK->_check_connection();
713 _RDK->_send_Line("G_Parent");
714 _RDK->_send_Item(this);
715 Item itm_parent = _RDK->_recv_Item();
716 _RDK->_check_status();
717 return itm_parent;
718}
719
720
726QList<Item> Item::Childs() const {
727 _RDK->_check_connection();
728 _RDK->_send_Line("G_Childs");
729 _RDK->_send_Item(this);
730 int nitems = _RDK->_recv_Int();
731 QList<Item> itemlist;
732 for (int i = 0; i < nitems; i++)
733 {
734 itemlist.append(_RDK->_recv_Item());
735 }
736 _RDK->_check_status();
737 return itemlist;
738}
739
744bool Item::Visible() const {
745 _RDK->_check_connection();
746 _RDK->_send_Line("G_Visible");
747 _RDK->_send_Item(this);
748 int visible = _RDK->_recv_Int();
749 _RDK->_check_status();
750 return (visible != 0);
751}
757void Item::setVisible(bool visible, int visible_frame){
758 if (visible_frame < 0)
759 {
760 visible_frame = visible ? 1 : 0;
761 }
762 _RDK->_check_connection();
763 _RDK->_send_Line("S_Visible");
764 _RDK->_send_Item(this);
765 _RDK->_send_Int(visible ? 1 : 0);
766 _RDK->_send_Int(visible_frame);
767 _RDK->_check_status();
768}
769
774QString Item::Name() const {
775 _RDK->_check_connection();
776 _RDK->_send_Line("G_Name");
777 _RDK->_send_Item(this);
778 QString name = _RDK->_recv_Line();
779 _RDK->_check_status();
780 return name;
781}
782
787void Item::setName(const QString &name){
788 _RDK->_check_connection();
789 _RDK->_send_Line("S_Name");
790 _RDK->_send_Item(this);
791 _RDK->_send_Line(name);
792 _RDK->_check_status();
793}
794
795// add more methods
796
802void Item::setPose(const Mat pose){
803 _RDK->_check_connection();
804 _RDK->_send_Line("S_Hlocal");
805 _RDK->_send_Item(this);
806 _RDK->_send_Pose(pose);
807 _RDK->_check_status();
808}
809
816 _RDK->_check_connection();
817 _RDK->_send_Line("G_Hlocal");
818 _RDK->_send_Item(this);
819 Mat pose = _RDK->_recv_Pose();
820 _RDK->_check_status();
821 return pose;
822}
823
828void Item::setGeometryPose(const Mat pose){
829 _RDK->_check_connection();
830 _RDK->_send_Line("S_Hgeom");
831 _RDK->_send_Item(this);
832 _RDK->_send_Pose(pose);
833 _RDK->_check_status();
834}
835
841 _RDK->_check_connection();
842 _RDK->_send_Line("G_Hgeom");
843 _RDK->_send_Item(this);
844 Mat pose = _RDK->_recv_Pose();
845 _RDK->_check_status();
846 return pose;
847}
848/*
853void Item::setHtool(Mat pose){
854 _RDK->_check_connection();
855 _RDK->_send_Line("S_Htool");
856 _RDK->_send_Item(this);
857 _RDK->_send_Pose(pose);
858 _RDK->_check_status();
859}
860
866Mat Item::Htool(){
867 _RDK->_check_connection();
868 _RDK->_send_Line("G_Htool");
869 _RDK->_send_Item(this);
870 Mat pose = _RDK->_recv_Pose();
871 _RDK->_check_status();
872 return pose;
873}
874*/
880 _RDK->_check_connection();
881 _RDK->_send_Line("G_Tool");
882 _RDK->_send_Item(this);
883 Mat pose = _RDK->_recv_Pose();
884 _RDK->_check_status();
885 return pose;
886}
887
893 _RDK->_check_connection();
894 _RDK->_send_Line("G_Frame");
895 _RDK->_send_Item(this);
896 Mat pose = _RDK->_recv_Pose();
897 _RDK->_check_status();
898 return pose;
899}
900
906void Item::setPoseFrame(const Mat frame_pose){
907 _RDK->_check_connection();
908 _RDK->_send_Line("S_Frame");
909 _RDK->_send_Pose(frame_pose);
910 _RDK->_send_Item(this);
911 _RDK->_check_status();
912}
913
919void Item::setPoseFrame(const Item frame_item){
920 _RDK->_check_connection();
921 _RDK->_send_Line("S_Frame_ptr");
922 _RDK->_send_Item(frame_item);
923 _RDK->_send_Item(this);
924 _RDK->_check_status();
925}
926
932void Item::setPoseTool(const Mat tool_pose){
933 _RDK->_check_connection();
934 _RDK->_send_Line("S_Tool");
935 _RDK->_send_Pose(tool_pose);
936 _RDK->_send_Item(this);
937 _RDK->_check_status();
938}
939
945void Item::setPoseTool(const Item tool_item){
946 _RDK->_check_connection();
947 _RDK->_send_Line("S_Tool_ptr");
948 _RDK->_send_Item(tool_item);
949 _RDK->_send_Item(this);
950 _RDK->_check_status();
951}
952
957void Item::setPoseAbs(const Mat pose){
958 _RDK->_check_connection();
959 _RDK->_send_Line("S_Hlocal_Abs");
960 _RDK->_send_Item(this);
961 _RDK->_send_Pose(pose);
962 _RDK->_check_status();
963
964}
965
971 _RDK->_check_connection();
972 _RDK->_send_Line("G_Hlocal_Abs");
973 _RDK->_send_Item(this);
974 Mat pose = _RDK->_recv_Pose();
975 _RDK->_check_status();
976 return pose;
977}
978
983void Item::setColor(double colorRGBA[4]){
984 _RDK->_check_connection();
985 _RDK->_send_Line("S_Color");
986 _RDK->_send_Item(this);
987 _RDK->_send_Array(colorRGBA, 4);
988 _RDK->_check_status();
989
990}
991
996
997
1003void Item::Scale(double scale){
1004 double scale_xyz[3];
1005 scale_xyz[0] = scale;
1006 scale_xyz[1] = scale;
1007 scale_xyz[2] = scale;
1008 Scale(scale_xyz);
1009}
1010
1016void Item::Scale(double scale_xyz[3]){
1017 _RDK->_check_connection();
1018 _RDK->_send_Line("Scale");
1019 _RDK->_send_Item(this);
1020 _RDK->_send_Array(scale_xyz, 3);
1021 _RDK->_check_status();
1022}
1023
1024
1025
1026
1036Item Item::setMachiningParameters(QString ncfile, Item part_obj, QString options)
1037{
1038 _RDK->_check_connection();
1039 _RDK->_send_Line("S_MachiningParams");
1040 _RDK->_send_Item(this);
1041 _RDK->_send_Line(ncfile);
1042 _RDK->_send_Item(part_obj);
1043 _RDK->_send_Line("NO_UPDATE " + options);
1044 _RDK->_TIMEOUT = 3600 * 1000;
1045 Item program = _RDK->_recv_Item();
1046 _RDK->_TIMEOUT = ROBODK_API_TIMEOUT;
1047 double status = _RDK->_recv_Int() / 1000.0;
1048 _RDK->_check_status();
1049 return program;
1050}
1051
1056 _RDK->_check_connection();
1057 _RDK->_send_Line("S_Target_As_RT");
1058 _RDK->_send_Item(this);
1059 _RDK->_check_status();
1060}
1061
1066 _RDK->_check_connection();
1067 _RDK->_send_Line("S_Target_As_JT");
1068 _RDK->_send_Item(this);
1069 _RDK->_check_status();
1070}
1071
1076 _RDK->_check_connection();
1077 _RDK->_send_Line("Target_Is_JT");
1078 _RDK->_send_Item(this);
1079 int is_jt = _RDK->_recv_Int();
1080 _RDK->_check_status();
1081 return is_jt > 0;
1082}
1083
1084//#####Robot item calls####
1085
1091 tJoints jnts;
1092 _RDK->_check_connection();
1093 _RDK->_send_Line("G_Thetas");
1094 _RDK->_send_Item(this);
1095 _RDK->_recv_Array(&jnts);
1096 _RDK->_check_status();
1097 return jnts;
1098}
1099
1100// add more methods
1101
1107 tJoints jnts;
1108 _RDK->_check_connection();
1109 _RDK->_send_Line("G_Home");
1110 _RDK->_send_Item(this);
1111 _RDK->_recv_Array(&jnts);
1112 _RDK->_check_status();
1113 return jnts;
1114}
1115
1116
1122 _RDK->_check_connection();
1123 _RDK->_send_Line("S_Home");
1124 _RDK->_send_Array(&jnts);
1125 _RDK->_send_Item(this);
1126 _RDK->_check_status();
1127}
1128
1135 _RDK->_check_connection();
1136 _RDK->_send_Line("G_LinkObjId");
1137 _RDK->_send_Item(this);
1138 _RDK->_send_Int(link_id);
1139 Item item = _RDK->_recv_Item();
1140 _RDK->_check_status();
1141 return item;
1142}
1143
1149Item Item::getLink(int type_linked){
1150 _RDK->_check_connection();
1151 _RDK->_send_Line("G_LinkType");
1152 _RDK->_send_Item(this);
1153 _RDK->_send_Int(type_linked);
1154 Item item = _RDK->_recv_Item();
1155 _RDK->_check_status();
1156 return item;
1157}
1158
1159
1164void Item::setJoints(const tJoints &jnts){
1165 _RDK->_check_connection();
1166 _RDK->_send_Line("S_Thetas");
1167 _RDK->_send_Array(&jnts);
1168 _RDK->_send_Item(this);
1169 _RDK->_check_status();
1170}
1171
1177void Item::JointLimits(tJoints *lower_limits, tJoints *upper_limits){
1178 _RDK->_check_connection();
1179 _RDK->_send_Line("G_RobLimits");
1180 _RDK->_send_Item(this);
1181 _RDK->_recv_Array(lower_limits);
1182 _RDK->_recv_Array(upper_limits);
1183 double joints_type = _RDK->_recv_Int() / 1000.0;
1184 _RDK->_check_status();
1185}
1186
1192void Item::setJointLimits(const tJoints &lower_limits, const tJoints &upper_limits){
1193 _RDK->_check_connection();
1194 _RDK->_send_Line("S_RobLimits");
1195 _RDK->_send_Item(this);
1196 _RDK->_send_Array(&lower_limits);
1197 _RDK->_send_Array(&upper_limits);
1198 //double joints_type = _RDK->_recv_Int() / 1000.0;
1199 _RDK->_check_status();
1200}
1201
1207void Item::setRobot(const Item &robot){
1208 _RDK->_check_connection();
1209 _RDK->_send_Line("S_Robot");
1210 _RDK->_send_Item(this);
1211 _RDK->_send_Item(robot);
1212 _RDK->_check_status();
1213}
1214
1215
1222Item Item::AddTool(const Mat &tool_pose, const QString &tool_name){
1223 _RDK->_check_connection();
1224 _RDK->_send_Line("AddToolEmpty");
1225 _RDK->_send_Item(this);
1226 _RDK->_send_Pose(tool_pose);
1227 _RDK->_send_Line(tool_name);
1228 Item newtool = _RDK->_recv_Item();
1229 _RDK->_check_status();
1230 return newtool;
1231}
1232
1238Mat Item::SolveFK(const tJoints &joints, const Mat *tool, const Mat *ref){
1239 _RDK->_check_connection();
1240 _RDK->_send_Line("G_FK");
1241 _RDK->_send_Array(&joints);
1242 _RDK->_send_Item(this);
1243 Mat pose = _RDK->_recv_Pose();
1244 Mat base2flange(pose);
1245 if (tool != nullptr){
1246 base2flange = pose*(*tool);
1247 }
1248 if (ref != nullptr){
1249 base2flange = ref->inv() * base2flange;
1250 }
1251 _RDK->_check_status();
1252 return base2flange;
1253}
1254
1260void Item::JointsConfig(const tJoints &joints, tConfig config){
1261 _RDK->_check_connection();
1262 _RDK->_send_Line("G_Thetas_Config");
1263 _RDK->_send_Array(&joints);
1264 _RDK->_send_Item(this);
1265 int sz = RDK_SIZE_MAX_CONFIG;
1266 _RDK->_recv_Array(config, &sz);
1267 _RDK->_check_status();
1268 //return config;
1269}
1270
1278tJoints Item::SolveIK(const Mat &pose, const Mat *tool, const Mat *ref){
1279 tJoints jnts;
1280 Mat base2flange(pose);
1281 if (tool != nullptr){
1282 base2flange = pose*tool->inv();
1283 }
1284 if (ref != nullptr){
1285 base2flange = (*ref) * base2flange;
1286 }
1287 _RDK->_check_connection();
1288 _RDK->_send_Line("G_IK");
1289 _RDK->_send_Pose(base2flange);
1290 _RDK->_send_Item(this);
1291 _RDK->_recv_Array(&jnts);
1292 _RDK->_check_status();
1293 return jnts;
1294}
1295
1296
1297
1306tJoints Item::SolveIK(const Mat pose, tJoints joints_approx, const Mat *tool, const Mat *ref){
1307 Mat base2flange(pose);
1308 if (tool != nullptr){
1309 base2flange = pose*tool->inv();
1310 }
1311 if (ref != nullptr){
1312 base2flange = (*ref) * base2flange;
1313 }
1314 _RDK->_check_connection();
1315 _RDK->_send_Line("G_IK_jnts");
1316 _RDK->_send_Pose(base2flange);
1317 _RDK->_send_Array(&joints_approx);
1318 _RDK->_send_Item(this);
1319 tJoints jnts;
1320 _RDK->_recv_Array(&jnts);
1321 _RDK->_check_status();
1322 return jnts;
1323}
1324
1325
1331tMatrix2D* Item::SolveIK_All_Mat2D(const Mat &pose, const Mat *tool, const Mat *ref){
1332 tMatrix2D *mat2d = nullptr;
1333 Mat base2flange(pose);
1334 if (tool != nullptr){
1335 base2flange = pose*tool->inv();
1336 }
1337 if (ref != nullptr){
1338 base2flange = (*ref) * base2flange;
1339 }
1340 _RDK->_check_connection();
1341 _RDK->_send_Line("G_IK_cmpl");
1342 _RDK->_send_Pose(base2flange);
1343 _RDK->_send_Item(this);
1344 _RDK->_recv_Matrix2D(&mat2d);
1345 _RDK->_check_status();
1346 return mat2d;
1347}
1348QList<tJoints> Item::SolveIK_All(const Mat &pose, const Mat *tool, const Mat *ref){
1349 tMatrix2D *mat2d = SolveIK_All_Mat2D(pose, tool, ref);
1350 QList<tJoints> jnts_list;
1351 int ndofs = Matrix2D_Size(mat2d, 1) - 2;
1352 int nsol = Matrix2D_Size(mat2d, 2);
1353 for (int i=0; i<nsol; i++){
1354 tJoints jnts = tJoints(mat2d, i);
1355 jnts.setLength(jnts.Length() - 2);
1356 jnts_list.append(jnts);
1357 }
1358 return jnts_list;
1359}
1360
1366bool Item::Connect(const QString &robot_ip){
1367 _RDK->_check_connection();
1368 _RDK->_send_Line("Connect");
1369 _RDK->_send_Item(this);
1370 _RDK->_send_Line(robot_ip);
1371 int status = _RDK->_recv_Int();
1372 _RDK->_check_status();
1373 return status != 0;
1374}
1375
1381 _RDK->_check_connection();
1382 _RDK->_send_Line("Disconnect");
1383 _RDK->_send_Item(this);
1384 int status = _RDK->_recv_Int();
1385 _RDK->_check_status();
1386 return status != 0;
1387}
1388
1394void Item::MoveJ(const Item &itemtarget, bool blocking){
1396 _RDK->_check_connection();
1397 _RDK->_send_Line("Add_INSMOVE");
1398 _RDK->_send_Item(itemtarget);
1399 _RDK->_send_Item(this);
1400 _RDK->_send_Int(1);
1401 _RDK->_check_status();
1402 } else {
1403 _RDK->_moveX(&itemtarget, nullptr, nullptr, this, 1, blocking);
1404 }
1405}
1406
1412void Item::MoveJ(const tJoints &joints, bool blocking){
1413 _RDK->_moveX(nullptr, &joints, nullptr, this, 1, blocking);
1414}
1415
1421void Item::MoveJ(const Mat &target, bool blocking){
1422 _RDK->_moveX(nullptr, nullptr, &target, this, 1, blocking);
1423}
1424
1430void Item::MoveL(const Item &itemtarget, bool blocking){
1432 _RDK->_check_connection();
1433 _RDK->_send_Line("Add_INSMOVE");
1434 _RDK->_send_Item(itemtarget);
1435 _RDK->_send_Item(this);
1436 _RDK->_send_Int(2);
1437 _RDK->_check_status();
1438 } else {
1439 _RDK->_moveX(&itemtarget, nullptr, nullptr, this, 2, blocking);
1440 }
1441}
1442
1448void Item::MoveL(const tJoints &joints, bool blocking){
1449 _RDK->_moveX(nullptr, &joints, nullptr, this, 2, blocking);
1450}
1451
1457void Item::MoveL(const Mat &target, bool blocking){
1458 _RDK->_moveX(nullptr, nullptr, &target, this, 2, blocking);
1459}
1460
1467void Item::MoveC(const Item &itemtarget1, const Item &itemtarget2, bool blocking){
1468 _RDK->_moveC(&itemtarget1, nullptr, nullptr, &itemtarget2, nullptr, nullptr, this, blocking);
1469}
1470
1477void Item::MoveC(const tJoints &joints1, const tJoints &joints2, bool blocking){
1478 _RDK->_moveC(nullptr, &joints1, nullptr, nullptr, &joints2, nullptr, this, blocking);
1479}
1480
1487void Item::MoveC(const Mat &target1, const Mat &target2, bool blocking){
1488 _RDK->_moveC(nullptr, nullptr, &target1, nullptr, nullptr, &target2, this, blocking);
1489}
1490
1498int Item::MoveJ_Test(const tJoints &j1, const tJoints &j2, double minstep_deg){
1499 _RDK->_check_connection();
1500 _RDK->_send_Line("CollisionMove");
1501 _RDK->_send_Item(this);
1502 _RDK->_send_Array(&j1);
1503 _RDK->_send_Array(&j2);
1504 _RDK->_send_Int((int)(minstep_deg * 1000.0));
1505 _RDK->_TIMEOUT = 3600 * 1000;
1506 int collision = _RDK->_recv_Int();
1507 _RDK->_TIMEOUT = ROBODK_API_TIMEOUT;
1508 _RDK->_check_status();
1509 return collision;
1510}
1511
1519int Item::MoveL_Test(const tJoints &j1, const Mat &pose2, double minstep_deg){
1520 _RDK->_check_connection();
1521 _RDK->_send_Line("CollisionMoveL");
1522 _RDK->_send_Item(this);
1523 _RDK->_send_Array(&j1);
1524 _RDK->_send_Pose(pose2);
1525 _RDK->_send_Int((int)(minstep_deg * 1000.0));
1526 _RDK->_TIMEOUT = 3600 * 1000;
1527 int collision = _RDK->_recv_Int();
1528 _RDK->_TIMEOUT = ROBODK_API_TIMEOUT;
1529 _RDK->_check_status();
1530 return collision;
1531}
1532
1533
1541void Item::setSpeed(double speed_linear, double speed_joints, double accel_linear, double accel_joints){
1542 _RDK->_check_connection();
1543 _RDK->_send_Line("S_Speed4");
1544 _RDK->_send_Item(this);
1545 double speed_accel[4];
1546 speed_accel[0] = speed_linear;
1547 speed_accel[1] = speed_joints;
1548 speed_accel[2] = accel_linear;
1549 speed_accel[3] = accel_joints;
1550 _RDK->_send_Array(speed_accel, 4);
1551 _RDK->_check_status();
1552}
1553
1558void Item::setRounding(double zonedata){
1559 _RDK->_check_connection();
1560 _RDK->_send_Line("S_ZoneData");
1561 _RDK->_send_Int((int)(zonedata * 1000.0));
1562 _RDK->_send_Item(this);
1563 _RDK->_check_status();
1564}
1565
1571 _RDK->_check_connection();
1572 _RDK->_send_Line("Show_Seq");
1573 _RDK->_send_Matrix2D(sequence);
1574 _RDK->_send_Item(this);
1575 _RDK->_check_status();
1576}
1577
1578
1584 _RDK->_check_connection();
1585 _RDK->_send_Line("IsBusy");
1586 _RDK->_send_Item(this);
1587 int busy = _RDK->_recv_Int();
1588 _RDK->_check_status();
1589 return (busy > 0);
1590}
1591
1597 _RDK->_check_connection();
1598 _RDK->_send_Line("Stop");
1599 _RDK->_send_Item(this);
1600 _RDK->_check_status();
1601}
1602
1607void Item::WaitMove(double timeout_sec) const{
1608 _RDK->_check_connection();
1609 _RDK->_send_Line("WaitMove");
1610 _RDK->_send_Item(this);
1611 _RDK->_check_status();
1612 _RDK->_TIMEOUT = (int)(timeout_sec * 1000.0);
1613 _RDK->_check_status();//will wait here;
1614 _RDK->_TIMEOUT = ROBODK_API_TIMEOUT;
1615 //int isbusy = _RDK->Busy(this);
1616 //while (isbusy)
1617 //{
1618 // busy = _RDK->Busy(item);
1619 //}
1620}
1621
1622
1627void Item::setAccuracyActive(int accurate){
1628 _RDK->_check_connection();
1629 _RDK->_send_Line("S_AbsAccOn");
1630 _RDK->_send_Item(this);
1631 _RDK->_send_Int(accurate);
1632 _RDK->_check_status();
1633}
1634
1636
1637
1638// ---- Program item calls -----
1639
1645bool Item::MakeProgram(const QString &filename){
1646 _RDK->_check_connection();
1647 _RDK->_send_Line("MakeProg");
1648 _RDK->_send_Item(this);
1649 _RDK->_send_Line(filename);
1650 int prog_status = _RDK->_recv_Int();
1651 QString prog_log_str = _RDK->_recv_Line();
1652 _RDK->_check_status();
1653 bool success = false;
1654 if (prog_status > 1) {
1655 success = true;
1656 }
1657 return success; // prog_log_str
1658}
1659
1665void Item::setRunType(int program_run_type){
1666 _RDK->_check_connection();
1667 _RDK->_send_Line("S_ProgRunType");
1668 _RDK->_send_Item(this);
1669 _RDK->_send_Int(program_run_type);
1670 _RDK->_check_status();
1671}
1672
1683 _RDK->_check_connection();
1684 _RDK->_send_Line("RunProg");
1685 _RDK->_send_Item(this);
1686 int prog_status = _RDK->_recv_Int();
1687 _RDK->_check_status();
1688 return prog_status;
1689}
1690
1691
1701int Item::RunCode(const QString &parameters){
1702 _RDK->_check_connection();
1703 if (parameters.isEmpty()){
1704 _RDK->_send_Line("RunProg");
1705 _RDK->_send_Item(this);
1706 } else {
1707 _RDK->_send_Line("RunProgParam");
1708 _RDK->_send_Item(this);
1709 _RDK->_send_Line(parameters);
1710 }
1711 int progstatus = _RDK->_recv_Int();
1712 _RDK->_check_status();
1713 return progstatus;
1714}
1715
1721int Item::RunInstruction(const QString &code, int run_type){
1722 _RDK->_check_connection();
1723 _RDK->_send_Line("RunCode2");
1724 _RDK->_send_Item(this);
1725 _RDK->_send_Line(QString(code).replace("\n\n", "<br>").replace("\n", "<br>"));
1726 _RDK->_send_Int(run_type);
1727 int progstatus = _RDK->_recv_Int();
1728 _RDK->_check_status();
1729 return progstatus;
1730}
1731
1736void Item::Pause(double time_ms){
1737 _RDK->_check_connection();
1738 _RDK->_send_Line("RunPause");
1739 _RDK->_send_Item(this);
1740 _RDK->_send_Int((int)(time_ms * 1000.0));
1741 _RDK->_check_status();
1742}
1743
1744
1750void Item::setDO(const QString &io_var, const QString &io_value){
1751 _RDK->_check_connection();
1752 _RDK->_send_Line("setDO");
1753 _RDK->_send_Item(this);
1754 _RDK->_send_Line(io_var);
1755 _RDK->_send_Line(io_value);
1756 _RDK->_check_status();
1757}
1763void Item::setAO(const QString &io_var, const QString &io_value){
1764 _RDK->_check_connection();
1765 _RDK->_send_Line("setAO");
1766 _RDK->_send_Item(this);
1767 _RDK->_send_Line(io_var);
1768 _RDK->_send_Line(io_value);
1769 _RDK->_check_status();
1770}
1771
1776QString Item::getDI(const QString &io_var){
1777 _RDK->_check_connection();
1778 _RDK->_send_Line("getDI");
1779 _RDK->_send_Item(this);
1780 _RDK->_send_Line(io_var);
1781 QString io_value(_RDK->_recv_Line());
1782 _RDK->_check_status();
1783 return io_value;
1784}
1785
1790QString Item::getAI(const QString &io_var){
1791 _RDK->_check_connection();
1792 _RDK->_send_Line("getAI");
1793 _RDK->_send_Item(this);
1794 _RDK->_send_Line(io_var);
1795 QString di_value(_RDK->_recv_Line());
1796 _RDK->_check_status();
1797 return di_value;
1798}
1799
1806void Item::waitDI(const QString &io_var, const QString &io_value, double timeout_ms){
1807 _RDK->_check_connection();
1808 _RDK->_send_Line("waitDI");
1809 _RDK->_send_Item(this);
1810 _RDK->_send_Line(io_var);
1811 _RDK->_send_Line(io_value);
1812 _RDK->_send_Int((int)(timeout_ms * 1000.0));
1813 _RDK->_check_status();
1814}
1815
1816
1826void Item::customInstruction(const QString &name, const QString &path_run, const QString &path_icon, bool blocking, const QString &cmd_run_on_robot){
1827 _RDK->_check_connection();
1828 _RDK->_send_Line("InsCustom2");
1829 _RDK->_send_Item(this);
1830 _RDK->_send_Line(name);
1831 _RDK->_send_Line(path_run);
1832 _RDK->_send_Line(path_icon);
1833 _RDK->_send_Line(cmd_run_on_robot);
1834 _RDK->_send_Int(blocking ? 1 : 0);
1835 _RDK->_check_status();
1836}
1837
1838/*
1844void Item::addMoveJ(const Item &itemtarget){
1845 _RDK->_check_connection();
1846 _RDK->_send_Line("Add_INSMOVE");
1847 _RDK->_send_Item(itemtarget);
1848 _RDK->_send_Item(this);
1849 _RDK->_send_Int(1);
1850 _RDK->_check_status();
1851}
1852
1857void Item::addMoveL(const Item &itemtarget){
1858 _RDK->_check_connection();
1859 _RDK->_send_Line("Add_INSMOVE");
1860 _RDK->_send_Item(itemtarget);
1861 _RDK->_send_Item(this);
1862 _RDK->_send_Int(2);
1863 _RDK->_check_status();
1864}
1865*/
1866
1871void Item::ShowInstructions(bool visible){
1872 _RDK->_check_connection();
1873 _RDK->_send_Line("Prog_ShowIns");
1874 _RDK->_send_Item(this);
1875 _RDK->_send_Int(visible ? 1 : 0);
1876 _RDK->_check_status();
1877}
1878
1883void Item::ShowTargets(bool visible){
1884 _RDK->_check_connection();
1885 _RDK->_send_Line("Prog_ShowTargets");
1886 _RDK->_send_Item(this);
1887 _RDK->_send_Int(visible ? 1 : 0);
1888 _RDK->_check_status();
1889}
1890
1891
1898 _RDK->_check_connection();
1899 _RDK->_send_Line("Prog_Nins");
1900 _RDK->_send_Item(this);
1901 int nins = _RDK->_recv_Int();
1902 _RDK->_check_status();
1903 return nins;
1904}
1905
1916void Item::Instruction(int ins_id, QString &name, int &instype, int &movetype, bool &isjointtarget, Mat &target, tJoints &joints){
1917 _RDK->_check_connection();
1918 _RDK->_send_Line("Prog_GIns");
1919 _RDK->_send_Item(this);
1920 _RDK->_send_Int(ins_id);
1921 name = _RDK->_recv_Line();
1922 instype = _RDK->_recv_Int();
1923 movetype = 0;
1924 isjointtarget = false;
1925 //target = null;
1926 //joints = null;
1927 if (instype == RoboDK::INS_TYPE_MOVE) {
1928 movetype = _RDK->_recv_Int();
1929 isjointtarget = _RDK->_recv_Int() > 0 ? true : false;
1930 target = _RDK->_recv_Pose();
1931 _RDK->_recv_Array(&joints);
1932 }
1933 _RDK->_check_status();
1934}
1935
1946void Item::setInstruction(int ins_id, const QString &name, int instype, int movetype, bool isjointtarget, const Mat &target, const tJoints &joints){
1947 _RDK->_check_connection();
1948 _RDK->_send_Line("Prog_SIns");
1949 _RDK->_send_Item(this);
1950 _RDK->_send_Int(ins_id);
1951 _RDK->_send_Line(name);
1952 _RDK->_send_Int(instype);
1953 if (instype == RoboDK::INS_TYPE_MOVE)
1954 {
1955 _RDK->_send_Int(movetype);
1956 _RDK->_send_Int(isjointtarget ? 1 : 0);
1957 _RDK->_send_Pose(target);
1958 _RDK->_send_Array(&joints);
1959 }
1960 _RDK->_check_status();
1961}
1962
1963
1970 _RDK->_check_connection();
1971 _RDK->_send_Line("G_ProgInsList");
1972 _RDK->_send_Item(this);
1973 _RDK->_recv_Matrix2D(&instructions);
1974 int errors = _RDK->_recv_Int();
1975 _RDK->_check_status();
1976 return errors;
1977}
1978
1979
1980
1991double Item::Update(int collision_check, int timeout_sec, double *out_nins_time_dist, double mm_step, double deg_step){
1992 _RDK->_check_connection();
1993 _RDK->_send_Line("Update2");
1994 _RDK->_send_Item(this);
1995 double values[5];
1996 values[0] = collision_check;
1997 values[1] = mm_step;
1998 values[2] = deg_step;
1999 _RDK->_send_Array(values, 3);
2000 _RDK->_TIMEOUT = timeout_sec * 1000;
2001 double return_values[10];
2002 int nvalues = 10;
2003 _RDK->_recv_Array(return_values, &nvalues);
2004 _RDK->_TIMEOUT = ROBODK_API_TIMEOUT;
2005 QString readable_msg = _RDK->_recv_Line();
2006 _RDK->_check_status();
2007 double ratio_ok = return_values[3];
2008 if (out_nins_time_dist != nullptr)
2009 {
2010 out_nins_time_dist[0] = return_values[0]; // number of correct instructions
2011 out_nins_time_dist[1] = return_values[1]; // estimated time to complete the program (cycle time)
2012 out_nins_time_dist[2] = return_values[2]; // estimated travel distance
2013 }
2014 return ratio_ok;
2015}
2016
2017
2030int Item::InstructionListJoints(QString &error_msg, tMatrix2D **joint_list, double mm_step, double deg_step, const QString &save_to_file, bool collision_check, int result_flag, double time_step_s){
2031 _RDK->_check_connection();
2032 _RDK->_send_Line("G_ProgJointList");
2033 _RDK->_send_Item(this);
2034 double step_mm_deg[5] = { mm_step, deg_step, collision_check ? 1.0 : 0.0, (double) result_flag, time_step_s };
2035 _RDK->_send_Array(step_mm_deg, 5);
2036 _RDK->_TIMEOUT = 3600 * 1000;
2037 //joint_list = save_to_file;
2038 if (save_to_file.isEmpty()) {
2039 _RDK->_send_Line("");
2040 _RDK->_recv_Matrix2D(joint_list);
2041 } else {
2042 _RDK->_send_Line(save_to_file);
2043 joint_list = nullptr;
2044 }
2045 int error_code = _RDK->_recv_Int();
2046 _RDK->_TIMEOUT = ROBODK_API_TIMEOUT;
2047 error_msg = _RDK->_recv_Line();
2048 _RDK->_check_status();
2049 return error_code;
2050}
2051
2060QString Item::setParam(const QString &param, const QString &value){
2061 _RDK->_check_connection();
2062 _RDK->_send_Line("ICMD");
2063 _RDK->_send_Item(this);
2064 _RDK->_send_Line(param);
2065 _RDK->_send_Line(value);
2066 QString result =_RDK->_recv_Line();
2067 _RDK->_check_status();
2068 return result;
2069}
2070
2076 _RDK->Finish();
2077 return true;
2078}
2079
2080quint64 Item::GetID(){
2081 return _PTR;
2082}
2083
2084//---------------------------------------- add more
2085
2086
2087
2088
2089
2090
2091
2092
2093
2094
2095
2096
2097//---------------------------------------------------------------------------------------------------
2098//---------------------------------------------------------------------------------------------------
2099//---------------------------------------------------------------------------------------------------
2100//---------------------------------------------------------------------------------------------------
2102RoboDK::RoboDK(const QString &robodk_ip, int com_port, const QString &args, const QString &path) {
2103 _COM = nullptr;
2104 _IP = robodk_ip;
2105 _TIMEOUT = ROBODK_API_TIMEOUT;
2106 _PROCESS = 0;
2107 _PORT = com_port;
2108 _ROBODK_BIN = path;
2109 if (_PORT < 0){
2110 _PORT = ROBODK_DEFAULT_PORT;
2111 }
2112 if (_ROBODK_BIN.isEmpty()){
2113 _ROBODK_BIN = ROBODK_DEFAULT_PATH_BIN;
2114 }
2115 _ARGUMENTS = args;
2116 if (com_port > 0){
2117 _ARGUMENTS.append(" /PORT=" + QString::number(com_port));
2118 }
2119 _connect_smart();
2120}
2121
2122RoboDK::~RoboDK(){
2123 _disconnect();
2124}
2125
2126quint64 RoboDK::ProcessID(){
2127 if (_PROCESS == 0) {
2128 QString response = Command("MainProcess_ID");
2129 _PROCESS = response.toULongLong();
2130 }
2131 return _PROCESS;
2132}
2133
2134quint64 RoboDK::WindowID(){
2135 qint64 window_id;
2136 QString response = Command("MainWindow_ID");
2137 window_id = response.toULongLong();
2138 return window_id;
2139}
2140
2141bool RoboDK::Connected(){
2142 return _connected();
2143}
2144
2145bool RoboDK::Connect(){
2146 return _connect();
2147}
2153 _disconnect();
2154}
2160 Disconnect();
2161}
2162
2163// %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
2164// public methods
2171Item RoboDK::getItem(QString name, int itemtype){
2172 _check_connection();
2173 if (itemtype < 0){
2174 _send_Line("G_Item");
2175 _send_Line(name);
2176 } else {
2177 _send_Line("G_Item2");
2178 _send_Line(name);
2179 _send_Int(itemtype);
2180 }
2181 Item item = _recv_Item();
2182 _check_status();
2183 return item;
2184}
2185
2192QStringList RoboDK::getItemListNames(int filter){
2193 _check_connection();
2194 if (filter < 0) {
2195 _send_Line("G_List_Items");
2196 } else {
2197 _send_Line("G_List_Items_Type");
2198 _send_Int(filter);
2199 }
2200 qint32 numitems = _recv_Int();
2201 QStringList listnames;
2202 for (int i = 0; i < numitems; i++) {
2203 listnames.append(_recv_Line());
2204 }
2205 _check_status();
2206 return listnames;
2207}
2208
2215QList<Item> RoboDK::getItemList(int filter) {
2216 _check_connection();
2217 if (filter < 0) {
2218 _send_Line("G_List_Items_ptr");
2219 } else {
2220 _send_Line("G_List_Items_Type_ptr");
2221 _send_Int(filter);
2222 }
2223 int numitems = _recv_Int();
2224 QList<Item> listitems;
2225 for (int i = 0; i < numitems; i++) {
2226 listitems.append(_recv_Item());
2227 }
2228 _check_status();
2229 return listitems;
2230}
2231
2233
2241Item RoboDK::ItemUserPick(const QString &message, int itemtype) {
2242 _check_connection();
2243 _send_Line("PickItem");
2244 _send_Line(message);
2245 _send_Int(itemtype);
2246 _TIMEOUT = 3600 * 1000;
2247 Item item = _recv_Item();//item);
2248 _TIMEOUT = ROBODK_API_TIMEOUT;
2249 _check_status();
2250 return item;
2251}
2252
2257 _check_connection();
2258 _send_Line("RAISE");
2259 _check_status();
2260}
2261
2266 _check_connection();
2267 _send_Line("HIDE");
2268 _check_status();
2269}
2270
2275 _check_connection();
2276 _send_Line("QUIT");
2277 _check_status();
2278 _disconnect();
2279 _PROCESS = 0;
2280}
2281
2283{
2284 _check_connection();
2285 _send_Line("Version");
2286 QString appName = _recv_Line();
2287 int bitArch = _recv_Int();
2288 QString ver4 = _recv_Line();
2289 QString dateBuild = _recv_Line();
2290 _check_status();
2291 return ver4;
2292
2293}
2294
2295
2300void RoboDK::setWindowState(int windowstate){
2301 _check_connection();
2302 _send_Line("S_WindowState");
2303 _send_Int(windowstate);
2304 _check_status();
2305}
2306
2307
2313 _check_connection();
2314 _send_Line("S_RoboDK_Rights");
2315 _send_Int(flags);
2316 _check_status();
2317}
2318
2324void RoboDK::setFlagsItem(Item item, int flags){
2325 _check_connection();
2326 _send_Line("S_Item_Rights");
2327 _send_Item(item);
2328 _send_Int(flags);
2329 _check_status();
2330}
2331
2338 _check_connection();
2339 _send_Line("S_Item_Rights");
2340 _send_Item(item);
2341 int flags = _recv_Int();
2342 _check_status();
2343 return flags;
2344}
2345
2351void RoboDK::ShowMessage(const QString &message, bool popup){
2352 _check_connection();
2353 if (popup)
2354 {
2355 _send_Line("ShowMessage");
2356 _send_Line(message);
2357 _TIMEOUT = 3600 * 1000;
2358 _check_status();
2359 _TIMEOUT = ROBODK_API_TIMEOUT;
2360 }
2361 else
2362 {
2363 _send_Line("ShowMessageStatus");
2364 _send_Line(message);
2365 _check_status();
2366 }
2367
2368}
2369
2374void RoboDK::Copy(const Item &tocopy){
2375 _check_connection();
2376 _send_Line("Copy");
2377 _send_Item(tocopy);
2378 _check_status();
2379}
2380
2386Item RoboDK::Paste(const Item *paste_to){
2387 _check_connection();
2388 _send_Line("Paste");
2389 _send_Item(paste_to);
2390 Item newitem = _recv_Item();
2391 _check_status();
2392 return newitem;
2393}
2394
2401Item RoboDK::AddFile(const QString &filename, const Item *parent){
2402 _check_connection();
2403 _send_Line("Add");
2404 _send_Line(filename);
2405 _send_Item(parent);
2406 _TIMEOUT = 3600 * 1000;
2407 Item newitem = _recv_Item();
2408 _TIMEOUT = ROBODK_API_TIMEOUT;
2409 _check_status();
2410 return newitem;
2411}
2412
2418void RoboDK::Save(const QString &filename, const Item *itemsave){
2419 _check_connection();
2420 _send_Line("Save");
2421 _send_Line(filename);
2422 _send_Item(itemsave);
2423 _check_status();
2424}
2425
2438Item RoboDK::AddShape(tMatrix2D *trianglePoints, Item *addTo, bool shapeOverride, Color *color)
2439{
2440 double colorArray[4] = {0.6,0.6,0.8,1.0};
2441 if (color != nullptr){
2442 colorArray[0] = color->r;
2443 colorArray[1] = color->g;
2444 colorArray[2] = color->b;
2445 colorArray[3] = color->a;
2446 }
2447 _check_connection();
2448 _send_Line("AddShape3");
2449 _send_Matrix2D(trianglePoints);
2450 _send_Item(addTo);
2451 _send_Int(shapeOverride? 1 : 0);
2452 _send_Array(colorArray,4);
2453 Item newitem = _recv_Item();
2454 _check_status();
2455 return newitem;
2456}
2457
2474Item RoboDK::AddCurve(tMatrix2D *curvePoints, Item *referenceObject, bool addToRef, int ProjectionType)
2475{
2476 _check_connection();
2477 _send_Line("AddWire");
2478 _send_Matrix2D(curvePoints);
2479 _send_Item(referenceObject);
2480 _send_Int(addToRef ? 1:0);
2481 _send_Int(ProjectionType);
2482 Item newitem = _recv_Item();
2483 _check_status();
2484 return newitem;
2485}
2486
2495Item RoboDK::AddPoints(tMatrix2D *points, Item *referenceObject, bool addToRef, int ProjectionType)
2496{
2497 _check_connection();
2498 _send_Line("AddPoints");
2499 _send_Matrix2D(points);
2500 _send_Item(referenceObject);
2501 _send_Int(addToRef? 1 : 0);
2502 _send_Int(ProjectionType);Item newitem = _recv_Item();
2503 _check_status();
2504 return newitem;
2505}
2506
2507void RoboDK::ProjectPoints(tMatrix2D *points, tMatrix2D **projected, Item objectProject, int ProjectionType)
2508{
2509 _check_connection();
2510 _send_Line("ProjectPoints");
2511 _send_Matrix2D(points);
2512 _send_Item(objectProject);
2513 _send_Int(ProjectionType);
2514 _recv_Matrix2D(projected);
2515 _check_status();
2516}
2517
2523Item RoboDK::AddStation(const QString &name)
2524{
2525 _check_connection();
2526 _send_Line("NewStation");
2527 _send_Line(name);
2528 Item newitem = _recv_Item();
2529 _check_status();
2530 return newitem;
2531}
2532
2533
2534
2535
2540 _check_connection();
2541 _send_Line("RemoveStn");
2542 _check_status();
2543}
2544
2552Item RoboDK::AddTarget(const QString &name, Item *itemparent, Item *itemrobot){
2553 _check_connection();
2554 _send_Line("Add_TARGET");
2555 _send_Line(name);
2556 _send_Item(itemparent);
2557 _send_Item(itemrobot);
2558 Item newitem = _recv_Item();
2559 _check_status();
2560 return newitem;
2561}
2562
2569Item RoboDK::AddFrame(const QString &name, Item *itemparent){
2570 _check_connection();
2571 _send_Line("Add_FRAME");
2572 _send_Line(name);
2573 _send_Item(itemparent);
2574 Item newitem = _recv_Item();
2575 _check_status();
2576 return newitem;
2577}
2578
2585Item RoboDK::AddProgram(const QString &name, Item *itemrobot){
2586 _check_connection();
2587 _send_Line("Add_PROG");
2588 _send_Line(name);
2589 _send_Item(itemrobot);
2590 Item newitem = _recv_Item();
2591 _check_status();
2592 return newitem;
2593}
2594
2603Item RoboDK::AddMachiningProject(const QString &name, Item *itemrobot)
2604{
2605 _check_connection();
2606 _send_Line("Add_MACHINING");
2607 _send_Line(name);
2608 _send_Item(itemrobot);
2609 Item newitem = _recv_Item();
2610 _check_status();
2611 return newitem;
2612}
2613
2614
2615
2617{
2618 _check_connection();
2619 _send_Line("G_AllStn");
2620 int nstn = _recv_Int();
2621 QList<Item> *listStn = new QList<Item>();
2622 for (int i = 0;i < nstn;i++){
2623 Item station = _recv_Item();
2624 listStn->append(station);
2625 }
2626 _check_status();
2627 return *listStn;
2628}
2629
2630
2636 _check_connection();
2637 _send_Line("G_ActiveStn");
2638 Item station = _recv_Item();
2639 _check_status();
2640 return station;
2641}
2642
2648 _check_connection();
2649 _send_Line("S_ActiveStn");
2650 _send_Item(station);
2651 _check_status();
2652}
2653
2654
2655//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
2661int RoboDK::RunProgram(const QString &function_w_params){
2662 return RunCode(function_w_params, true);
2663}
2664
2671int RoboDK::RunCode(const QString &code, bool code_is_fcn_call){
2672 _check_connection();
2673 _send_Line("RunCode");
2674 _send_Int(code_is_fcn_call ? 1 : 0);
2675 _send_Line(code);
2676 int prog_status = _recv_Int();
2677 _check_status();
2678 return prog_status;
2679}
2680
2686void RoboDK::RunMessage(const QString &message, bool message_is_comment){
2687 _check_connection();
2688 _send_Line("RunMessage");
2689 _send_Int(message_is_comment ? 1 : 0);
2690 _send_Line(message);
2691 _check_status();
2692}
2693
2698void RoboDK::Render(bool always_render){
2699 bool auto_render = !always_render;
2700 _check_connection();
2701 _send_Line("Render");
2702 _send_Int(auto_render ? 1 : 0);
2703 _check_status();
2704}
2705
2711{
2712 _check_connection();
2713 _send_Line("Refresh");
2714 _send_Int(0);
2715 _check_status();
2716}
2717
2724bool RoboDK::IsInside(Item object_inside, Item object_parent){
2725 _check_connection();
2726 _send_Line("IsInside");
2727 _send_Item(object_inside);
2728 _send_Item(object_parent);
2729 int inside = _recv_Int();
2730 _check_status();
2731 return inside > 0;
2732}
2733
2739int RoboDK::setCollisionActive(int check_state){
2740 _check_connection();
2741 _send_Line("Collision_SetState");
2742 _send_Int(check_state);
2743 int ncollisions = _recv_Int();
2744 _check_status();
2745 return ncollisions;
2746}
2747
2758bool RoboDK::setCollisionActivePair(int check_state, Item item1, Item item2, int id1, int id2){
2759 _check_connection();
2760 _send_Line("Collision_SetPair");
2761 _send_Item(item1);
2762 _send_Item(item2);
2763 _send_Int(id1);
2764 _send_Int(id2);
2765 _send_Int(check_state);
2766 int success = _recv_Int();
2767 _check_status();
2768 return success > 0;
2769}
2770
2776 _check_connection();
2777 _send_Line("Collisions");
2778 int ncollisions = _recv_Int();
2779 _check_status();
2780 return ncollisions;
2781}
2782
2789int RoboDK::Collision(Item item1, Item item2){
2790 _check_connection();
2791 _send_Line("Collided");
2792 _send_Item(item1);
2793 _send_Item(item2);
2794 int ncollisions = _recv_Int();
2795 _check_status();
2796 return ncollisions;
2797}
2798
2799QList<Item> RoboDK::getCollisionItems(QList<int> link_id_list)
2800{
2801 _check_connection();
2802 _send_Line("Collision Items");
2803 int nitems = _recv_Int();
2804 QList<Item> itemList = QList<Item>();
2805 if (!link_id_list.isEmpty()){
2806 link_id_list.clear();
2807 }
2808 for (int i = 0; i < nitems; i++){
2809 itemList.append(_recv_Item());
2810 int linkId = _recv_Int();
2811 if (!link_id_list.isEmpty()){
2812 link_id_list.append(linkId);
2813 }
2814 int collisionTimes = _recv_Int();
2815 }
2816 _check_status();
2817 return itemList;
2818}
2819
2825 _check_connection();
2826 _send_Line("SimulateSpeed");
2827 _send_Int((int)(speed * 1000.0));
2828 _check_status();
2829}
2830
2836 _check_connection();
2837 _send_Line("GetSimulateSpeed");
2838 double speed = ((double)_recv_Int()) / 1000.0;
2839 _check_status();
2840 return speed;
2841}
2852void RoboDK::setRunMode(int run_mode){
2853 _check_connection();
2854 _send_Line("S_RunMode");
2855 _send_Int(run_mode);
2856 _check_status();
2857}
2858
2868 _check_connection();
2869 _send_Line("G_RunMode");
2870 int runmode = _recv_Int();
2871 _check_status();
2872 return runmode;
2873}
2880QList<QPair<QString,QString>> RoboDK::getParams(){
2881 _check_connection();
2882 _send_Line("G_Params");
2883 QList<QPair<QString,QString>> paramlist;
2884 int nparam = _recv_Int();
2885 for (int i = 0; i < nparam; i++) {
2886 QString param = _recv_Line();
2887 QString value = _recv_Line();
2888 paramlist.append(qMakePair(param, value));
2889 }
2890 _check_status();
2891 return paramlist;
2892}
2893
2905QString RoboDK::getParam(const QString &param){
2906 _check_connection();
2907 _send_Line("G_Param");
2908 _send_Line(param);
2909 QString value = _recv_Line();
2910 if (value.startsWith("UNKNOWN ")) {
2911 value = "";
2912 }
2913 _check_status();
2914 return value;
2915}
2916
2924void RoboDK::setParam(const QString &param, const QString &value){
2925 _check_connection();
2926 _send_Line("S_Param");
2927 _send_Line(param);
2928 _send_Line(value);
2929 _check_status();
2930}
2931
2938QString RoboDK::Command(const QString &cmd, const QString &value){
2939 _check_connection();
2940 _send_Line("SCMD");
2941 _send_Line(cmd);
2942 _send_Line(value);
2943 QString answer = _recv_Line();
2944 _check_status();
2945 return answer;
2946}
2947
2948bool RoboDK::LaserTrackerMeasure(tXYZ xyz, tXYZ estimate, bool search)
2949{
2950 _check_connection();
2951 _send_Line("MeasLT");
2952 _send_XYZ(estimate);
2953 _send_Int(search ? 1 : 0);
2954 _recv_XYZ(xyz);
2955 _check_status();
2956 if (xyz[0]*xyz[0] + xyz[1]*xyz[1] + xyz[2]*xyz[2] < 0.0001){
2957 return false;
2958 }
2959
2960 return true;
2961}
2962
2963void RoboDK::ShowAsCollided(QList<Item> itemList, QList<bool> collidedList, QList<int> *robot_link_id)
2964{
2965 int nitems = qMin(itemList.length(),collidedList.length());
2966 if (robot_link_id != nullptr){
2967 nitems = qMin(nitems, robot_link_id->length());
2968 }
2969 _check_connection();
2970 _send_Line("ShowAsCollidedList");
2971 _send_Int(nitems);
2972 for (int i = 0; i < nitems; i++){
2973 _send_Item(itemList[i]);
2974 _send_Int(collidedList[i] ? 1 : 0);
2975 int link_id = 0;
2976 if (robot_link_id != nullptr){
2977 link_id = robot_link_id->at(i);
2978 }
2979 _send_Int(link_id);
2980 }
2981 _check_status();
2982}
2983
2984//---------------------------------------------- ADD MORE (getParams, setParams, calibrate TCP, calibrate ref...)
2985
2986
2997void RoboDK::CalibrateTool(tMatrix2D *poses_joints, tXYZ tcp_xyz, int format, int algorithm, Item *robot, double *error_stats){
2998 _check_connection();
2999 _send_Line("CalibTCP2");
3000 _send_Matrix2D(poses_joints);
3001 _send_Int(format);
3002 _send_Int(algorithm);
3003 _send_Item(robot);
3004 int nxyz = 3;
3005 _recv_Array(tcp_xyz, &nxyz);
3006 if (error_stats != nullptr){
3007 _recv_Array(error_stats);
3008 } else {
3009 double errors_ignored[20];
3010 _recv_Array(errors_ignored);
3011 }
3012 tMatrix2D *error_graph = Matrix2D_Create();
3013 _recv_Matrix2D(&error_graph);
3014 Matrix2D_Delete(&error_graph);
3015 _check_status();
3016}
3017
3026Mat RoboDK::CalibrateReference(tMatrix2D *poses_joints, int method, bool use_joints, Item *robot){
3027 _check_connection();
3028 _send_Line("CalibFrame");
3029 _send_Matrix2D(poses_joints);
3030 _send_Int(use_joints ? -1 : 0);
3031 _send_Int(method);
3032 _send_Item(robot);
3033 Mat reference_pose = _recv_Pose();
3034 double error_stats[20];
3035 _recv_Array(error_stats);
3036 _check_status();
3037 return reference_pose;
3038}
3039
3040
3041int RoboDK::ProgramStart(const QString &progname, const QString &defaultfolder, const QString &postprocessor, Item *robot){
3042 _check_connection();
3043 _send_Line("ProgramStart");
3044 _send_Line(progname);
3045 _send_Line(defaultfolder);
3046 _send_Line(postprocessor);
3047 _send_Item(robot);
3048 int errors = _recv_Int();
3049 _check_status();
3050 return errors;
3051}
3052
3057void RoboDK::setViewPose(const Mat &pose){
3058 _check_connection();
3059 _send_Line("S_ViewPose");
3060 _send_Pose(pose);
3061 _check_status();
3062}
3063
3069 _check_connection();
3070 _send_Line("G_ViewPose");
3071 Mat pose = _recv_Pose();
3072 _check_status();
3073 return pose;
3074}
3075
3076//INCOMPLETE function!
3077/*bool RoboDK::SetRobotParams(Item *robot, tMatrix2D dhm, Mat poseBase, Mat poseTool)
3078{
3079 _check_connection();
3080 _send_Line("S_AbsAccParam");
3081 _send_Item(robot);
3082 Mat r2b;
3083 r2b.setToIdentity();
3084 _send_Pose(r2b);
3085 _send_Pose(poseBase);
3086 _send_Pose(poseTool);
3087 int *ndofs = dhm.size;
3088 _send_Int(*ndofs);
3089 for (int i = 0; i < *ndofs; i++){
3090 _send_Array(dhm);
3091 }
3092
3093 _send_Pose(poseBase);
3094 _send_Pose(poseTool);
3095 _send_Int(*ndofs);
3096 for (int i = 0; i < *ndofs; i++){
3097 _send_Array(dhm[i]);
3098 }
3099
3100 _send_Array(nullptr);
3101 _send_Array(nullptr);
3102 _check_status();
3103 return true;
3104}*/
3105
3106Item RoboDK::Cam2D_Add(const Item &item_object, const QString &cam_params, const Item *cam_item){
3107 _check_connection();
3108 _send_Line("Cam2D_PtrAdd");
3109 _send_Item(item_object);
3110 _send_Item(cam_item);
3111 _send_Line(cam_params);
3112 Item cam_item_return = _recv_Item();
3113 _check_status();
3114 return cam_item_return;
3115}
3116int RoboDK::Cam2D_Snapshot(const QString &file_save_img, const Item &cam_item, const QString &params){
3117 _check_connection();
3118 _send_Line("Cam2D_PtrSnapshot");
3119 _send_Item(cam_item);
3120 _send_Line(file_save_img);
3121 _send_Line(params);
3122 _TIMEOUT = 3600 * 1000;
3123 int status = _recv_Int();
3124 _TIMEOUT = ROBODK_API_TIMEOUT;
3125 _check_status();
3126 return status;
3127}
3128
3129int RoboDK::Cam2D_SetParams(const QString &params, const Item &cam_item){
3130 _check_connection();
3131 _send_Line("Cam2D_PtrSetParams");
3132 _send_Item(cam_item);
3133 _send_Line(params);
3134 int status = _recv_Int();
3135 _check_status();
3136 return status;
3137}
3138
3139Item RoboDK::getCursorXYZ(int x, int y, tXYZ xyzStation)
3140{
3141 _check_connection();
3142 _send_Line("Proj2d3d");
3143 _send_Int(x);
3144 _send_Int(y);
3145 int selection = _recv_Int();
3146 Item selectedItem = _recv_Item();
3147 tXYZ xyz;
3148 _recv_XYZ(xyz);
3149 if (xyzStation != nullptr){
3150 xyzStation[0] = xyz[0];
3151 xyzStation[1] = xyz[1];
3152 xyzStation[2] = xyz[2];
3153 }
3154 _check_status();
3155 return selectedItem;
3156}
3157
3158
3160
3161
3167 _check_connection();
3168 _send_Line("G_License");
3169 QString license = _recv_Line();
3170 _check_status();
3171 return license;
3172}
3173
3178QList<Item> RoboDK::Selection(){
3179 _check_connection();
3180 _send_Line("G_Selection");
3181 int nitems = _recv_Int();
3182 QList<Item> list_items;
3183 for (int i = 0; i < nitems; i++) {
3184 list_items.append(_recv_Item());
3185 }
3186 _check_status();
3187 return list_items;
3188}
3189
3194void RoboDK::setSelection(QList<Item> list_items){
3195 _check_connection();
3196 _send_Line("S_Selection");
3197 _send_Int(list_items.length());
3198 for (int i = 0; i < list_items.length(); i++) {
3199 _send_Item(list_items[i]);
3200 }
3201 _check_status();
3202}
3203
3204
3208void RoboDK::PluginLoad(const QString &pluginName, int load){
3209 _check_connection();
3210 _send_Line("PluginLoad");
3211 _send_Line(pluginName);
3212 _send_Int(load);
3213 _check_status();
3214}
3215
3219QString RoboDK::PluginCommand(const QString &pluginName, const QString &pluginCommand, const QString &pluginValue){
3220 _check_connection();
3221 _send_Line("PluginCommand");
3222 _send_Line(pluginName);
3223 _send_Line(pluginCommand);
3224 _send_Line(pluginValue);
3225 QString result = _recv_Line();
3226 _check_status();
3227 return result;
3228}
3229
3230
3235Item RoboDK::Popup_ISO9283_CubeProgram(Item *robot, tXYZ center, double side, bool blocking){
3236 //_require_build(5177);
3237 Item iso_program;
3238 _check_connection();
3239 if (center == nullptr){
3240 _send_Line("Popup_ProgISO9283");
3241 _send_Item(robot);
3242 _TIMEOUT = 3600 * 1000;
3243 iso_program = _recv_Item();
3244 _TIMEOUT = ROBODK_API_TIMEOUT;
3245 _check_status();
3246 } else {
3247 _send_Line("Popup_ProgISO9283_Param");
3248 _send_Item(robot);
3249 double values[5];
3250 values[0] = center[0];
3251 values[1] = center[1];
3252 values[2] = center[2];
3253 values[3] = side;
3254 values[4] = blocking ? 1 : 0;
3255 _send_Array(values, 4);
3256 if (blocking){
3257 _TIMEOUT = 3600 * 1000;
3258 iso_program = _recv_Item();
3259 _TIMEOUT = ROBODK_API_TIMEOUT;
3260 _check_status();
3261 }
3262 }
3263 return iso_program;
3264}
3265
3266
3267
3268
3269bool RoboDK::FileSet(const QString &path_file_local, const QString &file_remote, bool load_file, Item *attach_to){
3270 if (!_check_connection()){ return false; }
3271 if (!_send_Line("FileRecvBin")){ return false; }
3272 QFile file(path_file_local);
3273 if (!_send_Line(file_remote)){ return false; }
3274 int nbytes = file.size();
3275 if (!_send_Int(nbytes)){ return false; }
3276 if (!_send_Item(attach_to)){ return false; }
3277 if (!_send_Int(load_file ? 1 : 0)){ return false; }
3278 if (!_check_status()){ return false; }
3279 int sz_sent = 0;
3280 if (!file.open(QFile::ReadOnly)){
3281 return false;
3282 }
3283 while (true){
3284 QByteArray buffer(file.read(1024));
3285 if (buffer.size() == 0){
3286 break;
3287 }
3288 // warning! Nothing guarantees that all bytes are sent
3289 sz_sent += _COM->write(buffer);
3290 qDebug() << "Sending file " << path_file_local << 100*sz_sent/nbytes;
3291 }
3292 file.close();
3293 return true;
3294}
3295
3296bool RoboDK::FileGet(const QString &path_file_local, Item *station, const QString path_file_remote){
3297 if (!_check_connection()){ return false; }
3298 if (!_send_Line("FileSendBin")){ return false; }
3299 if (!_send_Item(station)){ return false; }
3300 if (!_send_Line(path_file_remote)){ return false; }
3301 int nbytes = _recv_Int();
3302 int remaining = nbytes;
3303 QFile file(path_file_local);
3304 if (!file.open(QFile::WriteOnly)){
3305 qDebug() << "Can not open file for writting " << path_file_local;
3306 return false;
3307 }
3308 while (remaining > 0){
3309 QByteArray buffer(_COM->read(qMin(remaining, 1024)));
3310 remaining -= buffer.size();
3311 file.write(buffer);
3312 }
3313 file.close();
3314 if (!_check_status()){ return false;}
3315 return true;
3316}
3317
3318
3319bool RoboDK::EmbedWindow(QString window_name, QString docked_name, int size_w, int size_h, quint64 pid, int area_add, int area_allowed, int timeout)
3320{
3321 if (!_check_connection()){ return false; }
3322 if (docked_name == "") {
3323 docked_name = window_name;
3324 }
3325 _check_connection();
3326 _send_Line("WinProcDock");
3327 _send_Line(docked_name);
3328 _send_Line(window_name);
3329 double sizeArray[2] = {(double)size_w, (double)size_h};
3330 _send_Array(sizeArray,2);
3331 _send_Line(QString::number(pid));
3332 _send_Int(area_allowed);
3333 _send_Int(area_add);
3334 _send_Int(timeout);
3335 int result = _recv_Int();
3336 _check_status();
3337 return result > 0;
3338}
3339
3340
3341bool RoboDK::EventsListen()
3342{
3343 _COM_EVT = new QTcpSocket();
3344 if (_IP.isEmpty()){
3345 _COM_EVT->connectToHost("127.0.0.1", _PORT); //QHostAddress::LocalHost, _PORT);
3346 } else {
3347 _COM_EVT->connectToHost(_IP, _PORT);
3348 }
3349 qDebug() << _COM_EVT->state();
3350 _COM_EVT->waitForConnected(_TIMEOUT);
3351 qDebug() << _COM_EVT->state();
3352 _send_Line("RDK_EVT", _COM_EVT);
3353 _send_Int(0, _COM_EVT);
3354 QString response = _recv_Line(_COM_EVT);
3355 qDebug() << response;
3356 int ver_evt = _recv_Int(_COM_EVT);
3357 int status = _recv_Int(_COM_EVT);
3358 if (response != "RDK_EVT" || status != 0)
3359 {
3360 return false;
3361 }
3362 //_COM_EVT.ReceiveTimeout = 3600 * 1000;
3363 //return EventsLoop();
3364 return true;
3365}
3366
3367bool RoboDK::WaitForEvent(int &evt, Item &itm)
3368{
3369 evt = _recv_Int(_COM_EVT);
3370 itm = _recv_Item(_COM_EVT);
3371 return true;
3372}
3373
3374//Receives 24 doubles of data from the event loop
3375bool RoboDK::Event_Receive_3D_POS(double *data, int *valueCount) {
3376 return _recv_Array(data,valueCount,_COM_EVT);
3377}
3378
3379//Receives the 3 bytes of mouse data
3380bool RoboDK::Event_Receive_Mouse_data(int *data) {
3381 data[0] = _recv_Int(_COM_EVT);
3382 data[1] = _recv_Int(_COM_EVT);
3383 data[2] = _recv_Int(_COM_EVT);
3384
3385 return true;
3386}
3387
3388bool RoboDK::Event_Receive_Event_Moved(Mat *pose_rel_out) {
3389 int nvalues = _recv_Int(_COM_EVT);
3390 Mat pose_rel = _recv_Pose(_COM_EVT);
3391 *pose_rel_out = pose_rel;
3392 if (nvalues > 16)
3393 {
3394 return false;
3395 // future compatibility
3396 }
3397
3398 return true;
3399}
3400
3401bool RoboDK::Event_Connected()
3402{
3403 return _COM_EVT != nullptr && _COM_EVT->state() == QTcpSocket::ConnectedState;
3404}
3405
3406//-------------------------- private ---------------------------------------
3407
3408bool RoboDK::_connected(){
3409 return _COM != nullptr && _COM->state() == QTcpSocket::ConnectedState;
3410}
3411
3412
3413bool RoboDK::_check_connection(){
3414 if (_connected()){
3415 return true;
3416 }
3417 bool connection_ok = _connect_smart();
3418 //if (!connection_ok){
3419 // throw -1;
3420 //}
3421 return connection_ok;
3422}
3423
3424bool RoboDK::_check_status(){
3425 qint32 status = _recv_Int();
3426 if (status == 0) {
3427 // everything is OK
3428 //status = status
3429 } else if (status > 0 && status < 10) {
3430 QString strproblems("Unknown error");
3431 if (status == 1) {
3432 strproblems = "Invalid item provided: The item identifier provided is not valid or it does not exist.";
3433 } else if (status == 2) { //output warning only
3434 strproblems = _recv_Line();
3435 qDebug() << "RoboDK API WARNING: " << strproblems;
3436 return 0;
3437 } else if (status == 3){ // output error
3438 strproblems = _recv_Line();
3439 qDebug() << "RoboDK API ERROR: " << strproblems;
3440 } else if (status == 9) {
3441 qDebug() << "Invalid RoboDK License";
3442 }
3443 //print(strproblems);
3444 //throw new RDKException(strproblems); //raise Exception(strproblems)
3445 } else if (status < 100){
3446 QString strproblems = _recv_Line();
3447 qDebug() << "RoboDK API ERROR: " << strproblems;
3448 } else {
3449 //throw new RDKException("Communication problems with the RoboDK API"); //raise Exception('Problems running function');
3450 qDebug() << "Communication problems with the RoboDK API";
3451 }
3452 return status;
3453}
3454
3455
3456
3457void RoboDK::_disconnect(){
3458 if (_COM != nullptr){
3459 _COM->deleteLater();
3460 _COM = nullptr;
3461 }
3462}
3463
3464// attempt a simple connection to RoboDK and start RoboDK if it is not running
3465bool RoboDK::_connect_smart(){
3466 //Establishes a connection with robodk. robodk must be running, otherwise, it will attempt to start it
3467 if (_connect()){
3468 qDebug() << "The RoboDK API is connected";
3469 return true;
3470 }
3471
3472 qDebug() << "...Trying to start RoboDK: " << _ROBODK_BIN << " " << _ARGUMENTS;
3473 // Start RoboDK
3474 QProcess *p = new QProcess();
3475 //_ARGUMENTS = "/DEBUG";
3476 p->start(_ROBODK_BIN, _ARGUMENTS.split(" ", QString::SkipEmptyParts));
3477 p->setReadChannel(QProcess::StandardOutput);
3478 //p->waitForReadyRead(10000);
3479 _PROCESS = p->processId();
3480 while (p->canReadLine() || p->waitForReadyRead(5000)){
3481 QString line = QString::fromUtf8(p->readLine().trimmed());
3482 //qDebug() << "RoboDK process: " << line;
3483 if (line.contains("Running", Qt::CaseInsensitive)){
3484 qDebug() << "RoboDK is Running... Connecting API";
3485 bool is_connected = _connect();
3486 if (is_connected){
3487 qDebug() << "The RoboDK API is connected";
3488 } else {
3489 qDebug() << "The RoboDK API is NOT connected!";
3490 }
3491 return is_connected;
3492 }
3493 }
3494 qDebug() << "Could not start RoboDK!";
3495 return false;
3496}
3497
3498// attempt a simple connection to RoboDK
3499bool RoboDK::_connect(){
3500 _disconnect();
3501 _COM = new QTcpSocket();
3502 if (_IP.isEmpty()){
3503 _COM->connectToHost("127.0.0.1", _PORT); //QHostAddress::LocalHost, _PORT);
3504 } else {
3505 _COM->connectToHost(_IP, _PORT);
3506 }
3507 // usually, 5 msec should be enough for localhost
3508 if (!_COM->waitForConnected(_TIMEOUT)){
3509 _COM->deleteLater();
3510 _COM = nullptr;
3511 return false;
3512 }
3513
3514 // RoboDK protocol to check that we are connected to the right port
3515 _COM->write(ROBODK_API_START_STRING); _COM->write(ROBODK_API_LF, 1);
3516 _COM->write("1 0"); _COM->write(ROBODK_API_LF, 1);
3517
3518 // 5 msec should be enough for localhost
3519 /*if (!_COM->waitForBytesWritten(_TIMEOUT)){
3520 _COM->deleteLater();
3521 _COM = nullptr;
3522 return false;
3523 }*/
3524 // 10 msec should be enough for localhost
3525 if (!_COM->canReadLine() && !_COM->waitForReadyRead(_TIMEOUT)){
3526 _COM->deleteLater();
3527 _COM = nullptr;
3528 return false;
3529 }
3530 QString read(_COM->readAll());
3531 // make sure we receive the OK from RoboDK
3532 if (!read.startsWith(ROBODK_API_READY_STRING)){
3533 _COM->deleteLater();
3534 _COM = nullptr;
3535 return false;
3536 }
3537 return true;
3538}
3539
3540
3542bool RoboDK::_waitline(QTcpSocket *com){
3543 if (com == nullptr) {
3544 com = _COM;
3545 }
3546 if (com == nullptr){ return false; }
3547 while (!com->canReadLine()){
3548 if (!com->waitForReadyRead(_TIMEOUT)){
3549 return false;
3550 }
3551 }
3552 return true;
3553}
3554QString RoboDK::_recv_Line(QTcpSocket *com){//QString &string){
3555 if (com == nullptr) {
3556 com = _COM;
3557 }
3558 QString string;
3559 if (!_waitline(com)){
3560 if (com != nullptr){
3561 //if this happens it means that there are problems: delete buffer
3562 com->readAll();
3563 }
3564 return string;
3565 }
3566 QByteArray line = _COM->readLine().trimmed();//remove last character \n //.trimmed();
3567 string.append(QString::fromUtf8(line));
3568 return string;
3569}
3570bool RoboDK::_send_Line(const QString& string,QTcpSocket *com){
3571 if (com == nullptr) {
3572 com = _COM;
3573 }
3574 if (com == nullptr || !com->isOpen()){ return false; }
3575 com->write(string.toUtf8());
3576 com->write(ROBODK_API_LF, 1);
3577 return true;
3578}
3579
3580int RoboDK::_recv_Int(QTcpSocket *com){//qint32 &value){
3581 if (com == nullptr){
3582 com = _COM;
3583 }
3584 qint32 value; // do not change type
3585 if (com == nullptr){ return false; }
3586 if (com->bytesAvailable() < sizeof(qint32)){
3587 com->waitForReadyRead(_TIMEOUT);
3588 if (com->bytesAvailable() < sizeof(qint32)){
3589 return -1;
3590 }
3591 }
3592 QDataStream ds(com);
3593 ds >> value;
3594 return value;
3595}
3596bool RoboDK::_send_Int(qint32 value,QTcpSocket *com){
3597 if (com == nullptr) {
3598 com = _COM;
3599 }
3600 if (com == nullptr || !com->isOpen()){ return false; }
3601 QDataStream ds(com);
3602 ds << value;
3603 return true;
3604}
3605
3606Item RoboDK::_recv_Item(QTcpSocket *com){//Item *item){
3607 if (com == nullptr) {
3608 com = _COM;
3609 }
3610 Item item(this);
3611 if (com == nullptr){ return item; }
3612 item._PTR = 0;
3613 item._TYPE = -1;
3614 if (com->bytesAvailable() < sizeof(quint64)){
3615 com->waitForReadyRead(_TIMEOUT);
3616 if (com->bytesAvailable() < sizeof(quint64)){
3617 return item;
3618 }
3619 }
3620 QDataStream ds(com);
3621 ds >> item._PTR;
3622 ds >> item._TYPE;
3623 return item;
3624}
3625bool RoboDK::_send_Item(const Item *item){
3626 if (_COM == nullptr || !_COM->isOpen()){ return false; }
3627 QDataStream ds(_COM);
3628 quint64 ptr = 0;
3629 if (item != nullptr){
3630 ptr = item->_PTR;
3631 }
3632 ds << ptr;
3633 return true;
3634}
3635bool RoboDK::_send_Item(const Item &item){
3636 return _send_Item(&item);
3637}
3638
3639Mat RoboDK::_recv_Pose(QTcpSocket *com){//Mat &pose){
3640 if (com == nullptr) {
3641 com = _COM;
3642 }
3643
3644 Mat pose;
3645 if (com == nullptr){ return pose; }
3646 int size = 16*sizeof(double);
3647 if (com->bytesAvailable() < size){
3648 com->waitForReadyRead(_TIMEOUT);
3649 if (com->bytesAvailable() < size){
3650 return pose;
3651 }
3652 }
3653 QDataStream ds(com);
3654 ds.setFloatingPointPrecision(QDataStream::DoublePrecision);
3655 //ds.setByteOrder(QDataStream::LittleEndian);
3656 double valuei;
3657 for (int j=0; j<4; j++){
3658 for (int i=0; i<4; i++){
3659 ds >> valuei;
3660 pose.Set(i,j,valuei);
3661 //pose.data()[i][j] = valuei;
3662 }
3663 }
3664 return pose;
3665}
3666bool RoboDK::_send_Pose(const Mat &pose){
3667 if (_COM == nullptr || !_COM->isOpen()){ return false; }
3668 QDataStream ds(_COM);
3669 ds.setFloatingPointPrecision(QDataStream::DoublePrecision);
3670 //ds.setByteOrder(QDataStream::LittleEndian);
3671 double valuei;
3672 for (int j=0; j<4; j++){
3673 for (int i=0; i<4; i++){
3674 valuei = pose.Get(i,j);
3675 ds << valuei;
3676 }
3677 }
3678 return true;
3679}
3680bool RoboDK::_recv_XYZ(tXYZ pos){
3681 if (_COM == nullptr){ return false; }
3682 int size = 3*sizeof(double);
3683 if (_COM->bytesAvailable() < size){
3684 _COM->waitForReadyRead(_TIMEOUT);
3685 if (_COM->bytesAvailable() < size){
3686 return false;
3687 }
3688 }
3689 QDataStream ds(_COM);
3690 ds.setFloatingPointPrecision(QDataStream::DoublePrecision);
3691 //ds.setByteOrder(QDataStream::LittleEndian);
3692 double valuei;
3693 for (int i=0; i<3; i++){
3694 ds >> valuei;
3695 pos[i] = valuei;
3696 }
3697 return true;
3698}
3699bool RoboDK::_send_XYZ(const tXYZ pos){
3700 if (_COM == nullptr || !_COM->isOpen()){ return false; }
3701 QDataStream ds(_COM);
3702 ds.setFloatingPointPrecision(QDataStream::DoublePrecision);
3703 //ds.setByteOrder(QDataStream::LittleEndian);
3704 double valuei;
3705 for (int i=0; i<3; i++){
3706 valuei = pos[i];
3707 ds << valuei;
3708 }
3709 return true;
3710}
3711bool RoboDK::_recv_Array(tJoints *jnts){
3712 return _recv_Array(jnts->_Values, &(jnts->_nDOFs));
3713}
3714bool RoboDK::_send_Array(const tJoints *jnts){
3715 if (jnts == nullptr){
3716 return _send_Int(0);
3717 }
3718 return _send_Array(jnts->_Values, jnts->_nDOFs);
3719}
3720bool RoboDK::_send_Array(const Mat *mat){
3721 if (mat == nullptr){
3722 return _send_Int(0);
3723 }
3724 double m44[16];
3725 for (int c=0; c<4; c++){
3726 for (int r=0; r<4; r++){
3727 m44[c*4+r] = mat->Get(r,c);
3728 }
3729 }
3730 return _send_Array(m44, 16);
3731}
3732bool RoboDK::_recv_Array(double *values, int *psize, QTcpSocket *com){
3733 if (com == nullptr) {
3734 com = _COM;
3735 }
3736 int nvalues = _recv_Int();
3737 if (com == nullptr || nvalues < 0) {return false;}
3738 if (psize != nullptr){
3739 *psize = nvalues;
3740 }
3741 if (nvalues < 0 || nvalues > 50){return false;} //check if the value is not too big
3742 int size = nvalues*sizeof(double);
3743 if (com->bytesAvailable() < size){
3744 com->waitForReadyRead(_TIMEOUT);
3745 if (com->bytesAvailable() < size){
3746 return false;
3747 }
3748 }
3749 QDataStream ds(com);
3750 ds.setFloatingPointPrecision(QDataStream::DoublePrecision);
3751 //ds.setByteOrder(QDataStream::LittleEndian);
3752 double valuei;
3753 for (int i=0; i<nvalues; i++){
3754 ds >> valuei;
3755 values[i] = valuei;
3756 }
3757 return true;
3758}
3759
3760bool RoboDK::_send_Array(const double *values, int nvalues){
3761 if (_COM == nullptr || !_COM->isOpen()){ return false; }
3762 if (!_send_Int((qint32)nvalues)){ return false; }
3763 QDataStream ds(_COM);
3764 ds.setFloatingPointPrecision(QDataStream::DoublePrecision);
3765 //ds.setByteOrder(QDataStream::LittleEndian);
3766 double valuei;
3767 for (int i=0; i<nvalues; i++){
3768 valuei = values[i];
3769 ds << valuei;
3770 }
3771 return true;
3772}
3773
3774bool RoboDK::_recv_Matrix2D(tMatrix2D **mat){ // needs to delete after!
3775 qint32 dim1 = _recv_Int();
3776 qint32 dim2 = _recv_Int();
3777 *mat = Matrix2D_Create();
3778 //emxInit_real_T(mat, 2);
3779 if (dim1 < 0 || dim2 < 0){ return false; }
3780 Matrix2D_Set_Size(*mat, dim1, dim2);
3781 if (dim1*dim2 <= 0){
3782 return true;
3783 }
3784 QByteArray buffer;
3785 int count = 0;
3786 double value;
3787 while (true){
3788 int remaining = dim1*dim2 - count;
3789 if (remaining <= 0){ return true; }
3790 if (_COM->bytesAvailable() <= 0 && !_COM->waitForReadyRead(_TIMEOUT)){
3791 Matrix2D_Delete(mat);
3792 return false;
3793 }
3794 buffer.append(_COM->read(remaining * sizeof(double) - buffer.size()));
3795 int np = buffer.size() / sizeof(double);
3796 QDataStream indata(buffer);
3797 indata.setFloatingPointPrecision(QDataStream::DoublePrecision);
3798 for (int i=0; i<np; i++){
3799 indata >> value;
3800 (*mat)->data[count] = value;
3801 count = count + 1;
3802 }
3803 buffer = buffer.mid(np * sizeof(double));
3804 }
3805 return false;// we should never arrive here...
3806}
3807bool RoboDK::_send_Matrix2D(tMatrix2D *mat){
3808 if (_COM == nullptr || !_COM->isOpen()){ return false; }
3809 QDataStream ds(_COM);
3810 ds.setFloatingPointPrecision(QDataStream::DoublePrecision);
3811 //ds.setByteOrder(QDataStream::LittleEndian);
3812 qint32 dim1 = Matrix2D_Size(mat, 1);
3813 qint32 dim2 = Matrix2D_Size(mat, 2);
3814 bool ok1 = _send_Int(dim1);
3815 bool ok2 = _send_Int(dim2);
3816 if (!ok1 || !ok2) {return false; }
3817 double valuei;
3818 for (int j=0; j<dim2; j++){
3819 for (int i=0; i<dim1; i++){
3820 valuei = Matrix2D_Get_ij(mat, i, j);
3821 ds << valuei;
3822 }
3823 }
3824 return true;
3825}
3826// private move type, to be used by public methods (MoveJ and MoveL)
3827void RoboDK::_moveX(const Item *target, const tJoints *joints, const Mat *mat_target, const Item *itemrobot, int movetype, bool blocking){
3828 itemrobot->WaitMove();
3829 _send_Line("MoveX");
3830 _send_Int(movetype);
3831 if (target != nullptr){
3832 _send_Int(3);
3833 _send_Array((tJoints*)nullptr);
3834 _send_Item(target);
3835 } else if (joints != nullptr){
3836 _send_Int(1);
3837 _send_Array(joints);
3838 _send_Item(nullptr);
3839 } else if (mat_target != nullptr){// && mat_target.IsHomogeneous()) {
3840 _send_Int(2);
3841 _send_Array(mat_target); // keep it as array!
3842 _send_Item(nullptr);
3843 } else {
3844 //throw new RDKException("Invalid target type"); //raise Exception('Problems running function');
3845 throw 0;
3846 }
3847 _send_Item(itemrobot);
3848 _check_status();
3849 if (blocking){
3850 itemrobot->WaitMove();
3851 }
3852}
3853// private move type, to be used by public methods (MoveJ and MoveL)
3854void RoboDK::_moveC(const Item *target1, const tJoints *joints1, const Mat *mat_target1, const Item *target2, const tJoints *joints2, const Mat *mat_target2, const Item *itemrobot, bool blocking){
3855 itemrobot->WaitMove();
3856 _send_Line("MoveC");
3857 _send_Int(3);
3858 if (target1 != nullptr){
3859 _send_Int(3);
3860 _send_Array((tJoints*)nullptr);
3861 _send_Item(target1);
3862 } else if (joints1 != nullptr) {
3863 _send_Int(1);
3864 _send_Array(joints1);
3865 _send_Item(nullptr);
3866 } else if (mat_target1 != nullptr){// && mat_target1.IsHomogeneous()) {
3867 _send_Int(2);
3868 _send_Array(mat_target1);
3869 _send_Item(nullptr);
3870 } else {
3871 throw 0;
3872 //throw new RDKException("Invalid type of target 1");
3873 }
3875 if (target2 != nullptr) {
3876 _send_Int(3);
3877 _send_Array((tJoints*)nullptr);
3878 _send_Item(target2);
3879 } else if (joints2 != nullptr) {
3880 _send_Int(1);
3881 _send_Array(joints2);
3882 _send_Item(nullptr);
3883 } else if (mat_target2 != nullptr){// && mat_target2.IsHomogeneous()) {
3884 _send_Int(2);
3885 _send_Array(mat_target2);
3886 _send_Item(nullptr);
3887 } else {
3888 throw 0;
3889 //throw new RDKException("Invalid type of target 2");
3890 }
3892 _send_Item(itemrobot);
3893 _check_status();
3894 if (blocking){
3895 itemrobot->WaitMove();
3896 }
3897}
3898
3899
3900
3901
3902
3903
3904
3905
3906
3907
3908
3909
3910
3911//---------------------------------------------------------------------------------------------------
3912//---------------------------------------------------------------------------------------------------
3913//---------------------------------------------------------------------------------------------------
3914//---------------------------------------------------------------------------------------------------
3915//---------------------------------------------------------------------------------------------------
3916//---------------------------------------------------------------------------------------------------
3918// 2D matrix functions
3920void emxInit_real_T(tMatrix2D **pEmxArray, int numDimensions)
3921{
3922 tMatrix2D *emxArray;
3923 int i;
3924 *pEmxArray = (tMatrix2D *)malloc(sizeof(tMatrix2D));
3925 emxArray = *pEmxArray;
3926 emxArray->data = (double *)NULL;
3927 emxArray->numDimensions = numDimensions;
3928 emxArray->size = (int *)malloc((unsigned int)(sizeof(int) * numDimensions));
3929 emxArray->allocatedSize = 0;
3930 emxArray->canFreeData = true;
3931 for (i = 0; i < numDimensions; i++) {
3932 emxArray->size[i] = 0;
3933 }
3934}
3937 tMatrix2D *matrix;
3938 emxInit_real_T((tMatrix2D**)(&matrix), 2);
3939 return matrix;
3940}
3941
3942
3943void emxFree_real_T(tMatrix2D **pEmxArray){
3944 if (*pEmxArray != (tMatrix2D *)NULL) {
3945 if (((*pEmxArray)->data != (double *)NULL) && (*pEmxArray)->canFreeData) {
3946 free((void *)(*pEmxArray)->data);
3947 }
3948 free((void *)(*pEmxArray)->size);
3949 free((void *)*pEmxArray);
3950 *pEmxArray = (tMatrix2D *)NULL;
3951 }
3952}
3953
3955 emxFree_real_T((tMatrix2D**)(mat));
3956}
3957
3958
3959
3960void emxEnsureCapacity(tMatrix2D *emxArray, int oldNumel, unsigned int elementSize){
3961 int newNumel;
3962 int i;
3963 double *newData;
3964 if (oldNumel < 0) {
3965 oldNumel = 0;
3966 }
3967 newNumel = 1;
3968 for (i = 0; i < emxArray->numDimensions; i++) {
3969 newNumel *= emxArray->size[i];
3970 }
3971 if (newNumel > emxArray->allocatedSize) {
3972 i = emxArray->allocatedSize;
3973 if (i < 16) {
3974 i = 16;
3975 }
3976 while (i < newNumel) {
3977 if (i > 1073741823) {
3978 i =(2147483647);//MAX_int32_T;
3979 } else {
3980 i <<= 1;
3981 }
3982 }
3983 newData = (double*) calloc((unsigned int)i, elementSize);
3984 if (emxArray->data != NULL) {
3985 memcpy(newData, emxArray->data, elementSize * oldNumel);
3986 if (emxArray->canFreeData) {
3987 free(emxArray->data);
3988 }
3989 }
3990 emxArray->data = newData;
3991 emxArray->allocatedSize = i;
3992 emxArray->canFreeData = true;
3993 }
3994}
3995
3996void Matrix2D_Set_Size(tMatrix2D *mat, int rows, int cols) {
3997 int old_numel;
3998 int numbel;
3999 old_numel = mat->size[0] * mat->size[1];
4000 mat->size[0] = rows;
4001 mat->size[1] = cols;
4002 numbel = rows*cols;
4003 emxEnsureCapacity(mat, old_numel, sizeof(double));
4004 /*for (i=0; i<numbel; i++){
4005 mat->data[i] = 0.0;
4006 }*/
4007}
4008
4009int Matrix2D_Size(const tMatrix2D *var, int dim) { // ONE BASED!!
4010 if (var->numDimensions >= dim) {
4011 return var->size[dim - 1];
4012 }
4013 else {
4014 return 0;
4015 }
4016}
4018 return Matrix2D_Size(var, 2);
4019}
4021 return Matrix2D_Size(var, 1);
4022}
4023double Matrix2D_Get_ij(const tMatrix2D *var, int i, int j) { // ZERO BASED!!
4024 return var->data[var->size[0] * j + i];
4025}
4026void Matrix2D_SET_ij(const tMatrix2D *var, int i, int j, double value) { // ZERO BASED!!
4027 var->data[var->size[0] * j + i] = value;
4028}
4029
4030double *Matrix2D_Get_col(const tMatrix2D *var, int col) { // ZERO BASED!!
4031 return (var->data + var->size[0] * col);
4032}
4033
4034
4035void Matrix2D_Add(tMatrix2D *var, const double *array, int numel){
4036 int oldnumel;
4037 int size1 = var->size[0];
4038 int size2 = var->size[1];
4039 oldnumel = size1*size2;
4040 var->size[1] = size2 + 1;
4041 emxEnsureCapacity(var, oldnumel, (int)sizeof(double));
4042 numel = qMin(numel, size1);
4043 for (int i=0; i<numel; i++){
4044 var->data[size1*size2 + i] = array[i];
4045 }
4046}
4047
4048void Matrix2D_Add(tMatrix2D *var, const tMatrix2D *varadd){
4049 int oldnumel;
4050 int size1 = var->size[0];
4051 int size2 = var->size[1];
4052 int size1_ap = varadd->size[0];
4053 int size2_ap = varadd->size[1];
4054 int numel = size1_ap*size2_ap;
4055 if (size1 != size1_ap){
4056 return;
4057 }
4058 oldnumel = size1*size2;
4059 var->size[1] = size2 + size2_ap;
4060 emxEnsureCapacity(var, oldnumel, (int)sizeof(double));
4061 for (int i=0; i<numel; i++){
4062 var->data[size1*size2 + i] = varadd->data[i];
4063 }
4064}
4065
4066void Debug_Array(const double *array, int arraysize) {
4067 int i;
4068 for (i = 0; i < arraysize; i++) {
4069 //char chararray[500]; // You had better have room for what you are sprintf()ing!
4070 //sprintf(chararray, "%.3f", array[i]);
4071 //std::cout << chararray;
4072 printf("%.3f", array[i]);
4073 if (i < arraysize - 1) {
4074 //std::cout << " , ";
4075 printf(" , ");
4076 }
4077 }
4078}
4079
4080void Debug_Matrix2D(const tMatrix2D *emx) {
4081 int size1;
4082 int size2;
4083 int j;
4084 double *column;
4085 size1 = Matrix2D_Get_nrows(emx);
4086 size2 = Matrix2D_Get_ncols(emx);
4087 printf("Matrix size = [%i, %i]\n", size1, size2);
4088 //std::out << "Matrix size = [%i, %i]" << size1 << " " << size2 << "]\n";
4089 for (j = 0; j<size2; j++) {
4090 column = Matrix2D_Get_col(emx, j);
4091 Debug_Array(column, size1);
4092 printf("\n");
4093 //std::cout << "\n";
4094 }
4095}
4096/*
4097void Debug_Mat(Mat pose, char show_full_pose) {
4098 tMatrix4x4 pose_tr;
4099 double xyzwpr[6];
4100 int j;
4101 if (show_full_pose > 0) {
4102 POSE_TR(pose_tr, pose);
4103 printf("Pose size = [4x4]\n");
4104 //std::cout << "Pose size = [4x4]\n";
4105 for (j = 0; j < 4; j++) {
4106 Debug_Array(pose_tr + j * 4, 4);
4107 printf("\n");
4108 //std::cout << "\n";
4109 }
4110 }
4111 else {
4112 POSE_2_XYZWPR(xyzwpr, pose);
4113 //std::cout << "XYZWPR = [ ";
4114 printf("XYZWPR = [ ");
4115 Debug_Array(xyzwpr, 6);
4116 printf(" ]\n");
4117 //std::cout << " ]\n";
4118 }
4119}
4120*/
4121
4122
4123
4124
4125#ifndef RDK_SKIP_NAMESPACE
4126}
4127#endif
The Item class represents an item in RoboDK station. An item can be a robot, a frame,...
Definition: robodk_api.h:1749
Item ObjectLink(int link_id=0)
Returns an item pointer to the geometry of a robot link. This is useful to show/hide certain robot li...
int RunInstruction(const QString &code, int run_type=RoboDK::INSTRUCTION_CALL_PROGRAM)
Adds a program call, code, message or comment inside a program.
RoboDK * RDK()
Returns the RoboDK link Robolink().
Definition: robodk_api.cpp:586
Mat GeometryPose()
Returns the position (pose) the object geometry with respect to its own reference frame....
Definition: robodk_api.cpp:840
Item getLink(int type_linked=RoboDK::ITEM_TYPE_ROBOT)
Returns an item linked to a robot, object, tool, program or robot machining project....
Item setMachiningParameters(QString ncfile="", Item part_obj=nullptr, QString options="")
Update the robot milling path input and parameters. Parameter input can be an NC file (G-code or APT ...
void Stop()
Stops a program or a robot
void MoveC(const Item &itemtarget1, const Item &itemtarget2, bool blocking=true)
Moves a robot to a specific target ("Move Circular" mode). By default, this function blocks until the...
tMatrix2D * SolveIK_All_Mat2D(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr)
Computes the inverse kinematics for the specified robot and pose. The function returns all available ...
void setRunType(int program_run_type)
Sets if the program will be run in simulation mode or on the real robot. Use: "PROGRAM_RUN_ON_SIMULAT...
void setSpeed(double speed_linear, double accel_linear=-1, double speed_joints=-1, double accel_joints=-1)
Sets the speed and/or the acceleration of a robot.
int InstructionList(tMatrix2D *instructions)
Returns the list of program instructions as an MxN matrix, where N is the number of instructions and ...
void NewLink()
Create a new communication link for RoboDK. Use this for robots if you use a multithread application ...
Definition: robodk_api.cpp:593
Mat SolveFK(const tJoints &joints, const Mat *tool=nullptr, const Mat *ref=nullptr)
Computes the forward kinematics of the robot for the provided joints. The tool and the reference fram...
bool Connect(const QString &robot_ip="")
Connect to a real robot using the corresponding robot driver.
void setPoseTool(const Mat tool_pose)
Sets the tool of a robot or a tool object (Tool Center Point, or TCP). The tool pose can be either an...
Definition: robodk_api.cpp:932
void setJoints(const tJoints &jnts)
Set robot joints or the joints of a target
bool Valid(bool check_pointer=false) const
Check if an item is valid (not null and available in the open station)
Definition: robodk_api.cpp:637
void Instruction(int ins_id, QString &name, int &instype, int &movetype, bool &isjointtarget, Mat &target, tJoints &joints)
Returns the program instruction at position id
qint32 _TYPE
Item type.
Definition: robodk_api.h:2488
void setAccuracyActive(int accurate=1)
Sets the accuracy of the robot active or inactive. A robot must have been calibrated to properly use ...
Mat Pose() const
Returns the local position (pose) of an object, target or reference frame. For example,...
Definition: robodk_api.cpp:815
void setColor(double colorRGBA[4])
Changes the color of a robot/object/tool. A color must must in the format COLOR=[R,...
Definition: robodk_api.cpp:983
int Type() const
Item type (object, robot, tool, reference, robot machining project, ...)
Definition: robodk_api.cpp:602
void customInstruction(const QString &name, const QString &path_run, const QString &path_icon="", bool blocking=true, const QString &cmd_run_on_robot="")
Add a custom instruction. This instruction will execute a Python file or an executable file.
void setDO(const QString &io_var, const QString &io_value)
Sets a variable (output) to a given value. This can also be used to set any variables to a desired va...
void setPose(const Mat pose)
Sets the local position (pose) of an object, target or reference frame. For example,...
Definition: robodk_api.cpp:802
void setGeometryPose(const Mat pose)
Sets the position (pose) the object geometry with respect to its own reference frame....
Definition: robodk_api.cpp:828
bool Busy()
Checks if a robot or program is currently running (busy or moving)
void setAsJointTarget()
Sets a target as a joint target. A joint target moves to a joints position without regarding the cart...
int RunCode(const QString &parameters)
Runs a program. It returns the number of instructions that can be executed successfully (a quick prog...
Mat PoseTool()
Returns the tool pose of an item. If a robot is provided it will get the tool pose of the active tool...
Definition: robodk_api.cpp:879
bool Disconnect()
Disconnect from a real robot (when the robot driver is used)
void setRobot(const Item &robot)
Sets the robot of a program or a target. You must set the robot linked to a program or a target every...
void setPoseAbs(const Mat pose)
Sets the global position (pose) of an item. For example, the position of an object/frame/target with ...
Definition: robodk_api.cpp:957
void setJointsHome(const tJoints &jnts)
Set robot joints for the home position
void setParent(Item parent)
Attaches the item to a new parent while maintaining the relative position with its parent....
Definition: robodk_api.cpp:647
void setPoseFrame(const Mat frame_pose)
Sets the reference frame of a robot(user frame). The frame can be either an item or a pose....
Definition: robodk_api.cpp:906
void setRounding(double zonedata)
Sets the robot movement smoothing accuracy (also known as zone data value).
void JointsConfig(const tJoints &joints, tConfig config)
Returns the robot configuration state for a set of robot joints.
void setParentStatic(Item parent)
Attaches the item to another parent while maintaining the current absolute position in the station....
Definition: robodk_api.cpp:660
int InstructionListJoints(QString &error_msg, tMatrix2D **joint_list, double mm_step=10.0, double deg_step=5.0, const QString &save_to_file="", bool collision_check=false, int flags=0, double time_step_s=0.1)
Returns a list of joints an MxN matrix, where M is the number of robot axes plus 4 columns....
void ShowTargets(bool visible=true)
Show or hide targets of a program in the RoboDK tree
tJoints Joints() const
Returns the current joints of a robot or the joints of a target. If the item is a cartesian target,...
void WaitMove(double timeout_sec=300) const
Waits (blocks) until the robot finishes its movement.
Mat PoseFrame()
Returns the reference frame pose of an item. If a robot is provided it will get the tool pose of the ...
Definition: robodk_api.cpp:892
Mat PoseAbs()
Returns the global position (pose) of an item. For example, the position of an object/frame/target wi...
Definition: robodk_api.cpp:970
RoboDK * _RDK
Pointer to RoboDK link object.
Definition: robodk_api.h:2482
QList< tJoints > SolveIK_All(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr)
Computes the inverse kinematics for the specified robot and pose. The function returns all available ...
bool isJointTarget() const
Returns True if a target is a joint target (green icon). Otherwise, the target is a Cartesian target ...
quint64 _PTR
Pointer to the item inside RoboDK.
Definition: robodk_api.h:2485
void MoveJ(const Item &itemtarget, bool blocking=true)
Moves a robot to a specific target ("Move Joint" mode). By default, this function blocks until the ro...
QList< Item > Childs() const
Returns a list of the item childs that are attached to the provided item.
Definition: robodk_api.cpp:726
int InstructionCount()
Returns the number of instructions of a program.
void setName(const QString &name)
Set the name of a RoboDK item.
Definition: robodk_api.cpp:787
double Update(int collision_check=RoboDK::COLLISION_OFF, int timeout_sec=3600, double *out_nins_time_dist=nullptr, double mm_step=-1, double deg_step=-1)
Updates a program and returns the estimated time and the number of valid instructions....
void Save(const QString &filename)
Save a station, a robot, a tool or an object to a file
Definition: robodk_api.cpp:617
void Pause(double time_ms=-1)
Generates a pause instruction for a robot or a program when generating code. Set it to -1 (default) i...
tJoints JointsHome() const
Returns the home joints of a robot. These joints can be manually set in the robot "Parameters" menu,...
Item AttachClosest()
Attach the closest object to the tool. Returns the item that was attached.
Definition: robodk_api.cpp:672
void DetachAll(Item parent)
Detach any object attached to a tool.
Definition: robodk_api.cpp:698
void ShowInstructions(bool visible=true)
Show or hide instruction items of a program in the RoboDK tree
void setAO(const QString &io_var, const QString &io_value)
Set an analog Output
void JointLimits(tJoints *lower_limits, tJoints *upper_limits)
Retrieve the joint limits of a robot
bool Visible() const
Returns 1 if the item is visible, otherwise, returns 0.
Definition: robodk_api.cpp:744
bool MakeProgram(const QString &filename)
Saves a program to a file.
void Delete()
Deletes an item and its childs from the station.
Definition: robodk_api.cpp:624
void waitDI(const QString &io_var, const QString &io_value, double timeout_ms=-1)
Waits for an input io_id to attain a given value io_value. Optionally, a timeout can be provided.
QString getDI(const QString &io_var)
Get a Digital Input (DI). This function is only useful when connected to a real robot using the robot...
void setVisible(bool visible, int visible_frame=-1)
Sets the item visiblity status
Definition: robodk_api.cpp:757
void MoveL(const Item &itemtarget, bool blocking=true)
Moves a robot to a specific target ("Move Linear" mode). By default, this function blocks until the r...
QString setParam(const QString &param, const QString &value)
Set a specific item parameter. Select Tools-Run Script-Show Commands to see all available commands fo...
int RunProgram()
Runs a program. It returns the number of instructions that can be executed successfully (a quick prog...
void setAsCartesianTarget()
Sets a target as a cartesian target. A cartesian target moves to cartesian coordinates.
void ShowSequence(tMatrix2D *sequence)
Displays a sequence of joints
int MoveL_Test(const tJoints &joints1, const Mat &pose2, double minstep_mm=-1)
Checks if a linear movement is free of issues and, optionally, collisions.
QString Name() const
Returns the name of an item. The name of the item is always displayed in the RoboDK station tree
Definition: robodk_api.cpp:774
bool Finish()
Disconnect from the RoboDK API. This flushes any pending program generation.
Item AddTool(const Mat &tool_pose, const QString &tool_name="New TCP")
Adds an empty tool to the robot provided the tool pose (4x4 Matrix) and the tool name.
tJoints SolveIK(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr)
Computes the inverse kinematics for the specified robot and pose. The joints returned are the closest...
quint64 GetID()
Get the item pointer.
void Scale(double scale)
Apply a scale to an object to make it bigger or smaller. The scale can be uniform (if scale is a floa...
int MoveJ_Test(const tJoints &j1, const tJoints &j2, double minstep_deg=-1)
Checks if a joint movement is possible and, optionally, free of collisions.
void setInstruction(int ins_id, const QString &name, int instype, int movetype, bool isjointtarget, const Mat &target, const tJoints &joints)
Sets the program instruction at position id
QString getAI(const QString &io_var)
Get an Analog Input (AI). This function is only useful when connected to a real robot using the robot...
Item DetachClosest(Item parent)
Detach the closest object attached to the tool (see also setParentStatic).
Definition: robodk_api.cpp:685
void setJointLimits(const tJoints &lower_limits, const tJoints &upper_limits)
Set the joint limits of a robot
Item Parent() const
Return the parent item of this item
Definition: robodk_api.cpp:711
The Mat class represents a 4x4 pose matrix. The main purpose of this object is to represent a pose in...
Definition: robodk_api.h:506
Mat()
Create the identity matrix.
Definition: robodk_api.cpp:189
void VX(tXYZ xyz) const
Get the X vector (N vector)
Definition: robodk_api.cpp:230
void setVX(double x, double y, double z)
Set the X vector values (N vector)
Definition: robodk_api.cpp:250
void FromXYZRPW(tXYZWPR xyzwpr)
Calculates the pose from the position and euler angles ([x,y,z,r,p,w] vector) The result is the same ...
Definition: robodk_api.cpp:480
void VY(tXYZ xyz) const
Get the Y vector (O vector)
Definition: robodk_api.cpp:235
static Mat transl(double x, double y, double z)
Return a translation matrix.
Definition: robodk_api.cpp:527
void ToXYZRPW(tXYZWPR xyzwpr) const
Calculates the equivalent position and euler angles ([x,y,z,r,p,w] vector) of the given pose Note: tr...
Definition: robodk_api.cpp:382
void setVZ(double x, double y, double z)
Set the Z vector values (A vector)
Definition: robodk_api.cpp:261
double Get(int r, int c) const
Get a matrix value.
Definition: robodk_api.cpp:302
bool Valid() const
Check if the matrix is valid.
Definition: robodk_api.cpp:523
void setVY(double x, double y, double z)
Set the Y vector values (O vector)
Definition: robodk_api.cpp:255
static Mat roty(double ry)
Return a Y-axis rotation matrix
Definition: robodk_api.cpp:540
const double * Values() const
Get a pointer to the 16-digit array (doubles or floats if ROBODK_API_FLOATS is defined).
Definition: robodk_api.cpp:505
void Pos(tXYZ xyz) const
Get the position (T position), in mm.
Definition: robodk_api.cpp:245
bool MakeHomogeneous()
Forces 4x4 matrix to be homogeneous (vx,vy,vz must be unitary vectors and respect: vx x vy = vz)....
Definition: robodk_api.cpp:354
static Mat rotz(double rz)
Return a Z-axis rotation matrix.
Definition: robodk_api.cpp:546
const double * ValuesD() const
Get a pointer to the 16-digit double array.
Definition: robodk_api.cpp:489
double _ddata16[16]
Copy of the data as a double array.
Definition: robodk_api.h:753
QString ToString(const QString &separator=", ", int precision=3, bool xyzwpr_only=false) const
Retrieve a string representation of the pose.
Definition: robodk_api.cpp:408
bool FromString(const QString &str)
Set the matrix given a XYZRPW string array (6-values)
Definition: robodk_api.cpp:444
Mat inv() const
Invert the pose (homogeneous matrix assumed)
Definition: robodk_api.cpp:309
void setPos(double x, double y, double z)
Set the position (T position) in mm.
Definition: robodk_api.cpp:267
void VZ(tXYZ xyz) const
Get the Z vector (A vector)
Definition: robodk_api.cpp:240
bool isHomogeneous() const
Returns true if the matrix is homogeneous, otherwise it returns false.
Definition: robodk_api.cpp:313
bool _valid
Flags if a matrix is not valid.
Definition: robodk_api.h:748
const float * ValuesF() const
Get a pointer to the 16-digit array as an array of floats.
Definition: robodk_api.cpp:496
void Set(int r, int c, double value)
Set a matrix value.
Definition: robodk_api.cpp:293
static Mat rotx(double rx)
Return the X-axis rotation matrix.
Definition: robodk_api.cpp:534
static Mat XYZRPW_2_Mat(double x, double y, double z, double r, double p, double w)
Calculates the pose from the position and euler angles ([x,y,z,r,p,w] vector) The result is the same ...
Definition: robodk_api.cpp:464
This class is the iterface to the RoboDK API. With the RoboDK API you can automate certain tasks and ...
Definition: robodk_api.h:762
void setViewPose(const Mat &pose)
Set the pose of the wold reference frame with respect to the user view (camera/screen).
void setSimulationSpeed(double speed)
Sets the current simulation speed. Set the speed to 1 for a real-time simulation. The slowest speed a...
@ ITEM_TYPE_PROGRAM
Program item.
Definition: robodk_api.h:1348
Item getItem(QString name, int itemtype=-1)
Returns an item by its name. If there is no exact match it will return the last closest match.
Item Paste(const Item *paste_to=nullptr)
Paste the copied item as a dependency of another item (same as Ctrl+V). Paste should be used after Co...
QList< Item > getCollisionItems(QList< int > link_id_list)
Return the list of items that are in a collision state. This function can be used after calling Colli...
void CloseRoboDK()
Closes RoboDK window and finishes RoboDK execution
QString Command(const QString &cmd, const QString &value="")
Send a special command. These commands are meant to have a specific effect in RoboDK,...
void ShowMessage(const QString &message, bool popup=true)
Show a message in RoboDK (it can be blocking or non blocking in the status bar)
Item AddPoints(tMatrix2D *points, Item *referenceObject=nullptr, bool addToRef=false, int ProjectionType=PROJECTION_ALONG_NORMAL_RECALC)
Adds a list of points to an object. The provided points must be a list of vertices....
int RunCode(const QString &code, bool code_is_fcn_call=false)
Adds code to run in the program output. If the program exists it will also run the program in simulat...
bool LaserTrackerMeasure(tXYZ xyz, tXYZ estimate, bool search=false)
Takes a laser tracker measurement with respect to its own reference frame. If an estimate point is pr...
int Collision(Item item1, Item item2)
Returns 1 if item1 and item2 collided. Otherwise returns 0.
void Save(const QString &filename, const Item *itemsave=nullptr)
Save an item to a file. If no item is provided, the open station is saved.
bool IsInside(Item object_inside, Item object_parent)
Check if an object is fully inside another one.
QString License()
Returns the license as a readable string (same name shown in the RoboDK's title bar,...
void setRunMode(int run_mode=1)
Sets the behavior of the RoboDK API. By default, RoboDK shows the path simulation for movement instru...
void PluginLoad(const QString &pluginName, int load=1)
Load or unload the specified plugin (path to DLL, dylib or SO file). If the plugin is already loaded ...
QString Version()
Return the vesion of RoboDK as a 4 digit string: Major.Minor.Revision.Build
Item AddFile(const QString &filename, const Item *parent=nullptr)
Loads a file and attaches it to parent. It can be any file supported by RoboDK.
Item AddStation(const QString &name)
Add a new empty station. It returns the station item added.
void ShowAsCollided(QList< Item > itemList, QList< bool > collidedList, QList< int > *robot_link_id=nullptr)
Show a list of items as collided.
bool setCollisionActivePair(int check_state, Item item1, Item item2, int id1=0, int id2=0)
Set collision checking ON or OFF (COLLISION_ON/COLLISION_OFF) for a specific pair of objects....
bool FileGet(const QString &path_file_local, Item *station=nullptr, const QString path_file_remote="")
Retrieve a file from the RoboDK running instance.
int RunMode()
Returns the behavior of the RoboDK API. By default, RoboDK shows the path simulation for movement ins...
Item getActiveStation()
Returns the active station item (station currently visible).
QList< QPair< QString, QString > > getParams()
Gets all the user parameters from the open RoboDK station. The parameters can also be modified by rig...
void ShowRoboDK()
Shows or raises the RoboDK window.
void CalibrateTool(tMatrix2D *poses_joints, tXYZ tcp_xyz, int format=EULER_RX_RY_RZ, int algorithm=CALIBRATE_TCP_BY_POINT, Item *robot=nullptr, double *error_stats=nullptr)
Calibrate a tool (TCP) given a number of points or calibration joints. Important: If the robot is cal...
void Disconnect()
Disconnect from the RoboDK API. This flushes any pending program generation.
Item Popup_ISO9283_CubeProgram(Item *robot=nullptr, tXYZ center=nullptr, double side=-1, bool blocking=true)
Show the popup menu to create the ISO9283 path for position accuracy, repeatability and path accuracy...
int setCollisionActive(int check_state=COLLISION_ON)
Turn collision checking ON or OFF (COLLISION_OFF/COLLISION_OFF) according to the collision map....
Item getCursorXYZ(int x=-1, int y=-1, tXYZ xyzStation=nullptr)
Returns the position of the cursor as XYZ coordinates (by default), or the 3D position of a given set...
Mat ViewPose()
Get the pose of the wold reference frame with respect to the user view (camera/screen).
Item ItemUserPick(const QString &message="Pick one item", int itemtype=-1)
Shows a RoboDK popup to select one object from the open RoboDK station. An item type can be specified...
Item AddTarget(const QString &name, Item *itemparent=nullptr, Item *itemrobot=nullptr)
Adds a new target that can be reached with a robot.
void setSelection(QList< Item > list_items)
Sets the selection in the tree (it can be one or more items).
QList< Item > Selection()
Returns the list of items selected (it can be one or more items).
Item AddMachiningProject(const QString &name="Curve follow settings", Item *itemrobot=nullptr)
Add a new robot machining project. Machining projects can also be used for 3D printing,...
Item AddCurve(tMatrix2D *curvePoints, Item *referenceObject=nullptr, bool addToRef=false, int ProjectionType=PROJECTION_ALONG_NORMAL_RECALC)
Adds a curve provided point coordinates. The provided points must be a list of vertices....
Item AddProgram(const QString &name, Item *itemrobot=nullptr)
Adds a new Frame that can be referenced by a robot.
int Cam2D_Snapshot(const QString &file_save_img, const Item &cam_item, const QString &params="")
Take a snapshot of a simulated camera and save it as an image.
QList< Item > getOpenStation()
Returns the list of open stations in RoboDK.
int RunProgram(const QString &function_w_params)
Adds a function call in the program output. RoboDK will handle the syntax when the code is generated ...
int ProgramStart(const QString &progname, const QString &defaultfolder="", const QString &postprocessor="", Item *robot=nullptr)
Defines the name of the program when the program is generated. It is also possible to specify the nam...
QList< Item > getItemList(int filter=-1)
Returns a list of items (list of names or pointers) of all available items in the currently open stat...
int Cam2D_SetParams(const QString &cam_params, const Item &cam_item)
Set the camera parameters.
Mat CalibrateReference(tMatrix2D *poses_joints, int method=CALIBRATE_FRAME_3P_P1_ON_X, bool use_joints=false, Item *robot=nullptr)
Calibrate a Reference Frame given a list of points or joint values. Important: If the robot is calibr...
void RunMessage(const QString &message, bool message_is_comment=false)
Shows a message or a comment in the output robot program.
Item AddFrame(const QString &name, Item *itemparent=nullptr)
Adds a new Frame that can be referenced by a robot.
int getFlagsItem(Item item)
Retrieve current item flags. Item flags allow defining how much access the user has to item-specific ...
void setActiveStation(Item stn)
Set the active station (project currently visible).
Item AddShape(tMatrix2D *trianglePoints, Item *addTo=nullptr, bool shapeOverride=false, Color *color=nullptr)
Adds a shape provided triangle coordinates. Triangles must be provided as a list of vertices....
Item Cam2D_Add(const Item &item_object, const QString &cam_params, const Item *cam_item=nullptr)
Add a simulated 2D or depth camera as an item. Use Delete to delete it.
QStringList getItemListNames(int filter=-1)
Returns a list of items (list of names or Items) of all available items in the currently open station...
void setWindowState(int windowstate=WINDOWSTATE_NORMAL)
Set the state of the RoboDK window
QString PluginCommand(const QString &pluginName, const QString &pluginCommand, const QString &pluginValue="")
Send a specific command to a RoboDK plugin. The command and value (optional) must be handled by your ...
void HideRoboDK()
Hides the RoboDK window. RoboDK will continue running in the background.
@ INS_TYPE_MOVE
Linear or joint movement instruction.
Definition: robodk_api.h:1375
int Collisions()
Returns the number of pairs of objects that are currently in a collision state.
void Copy(const Item &tocopy)
Makes a copy of an item (same as Ctrl+C), which can be pasted (Ctrl+V) using Paste().
void CloseStation()
Close the current station without asking to save.
void setParam(const QString &param, const QString &value)
Sets a global parameter from the RoboDK station. If the parameters exists, it will be modified....
void Update()
Update the screen. This updates the position of all robots and internal links according to previously...
QString getParam(const QString &param)
Gets a global or a user parameter from the open RoboDK station. The parameters can also be modified b...
void ProjectPoints(tMatrix2D *points, tMatrix2D **projected, Item objectProject, int ProjectionType=PROJECTION_ALONG_NORMAL_RECALC)
Projects a point given its coordinates. The provided points must be a list of [XYZ] coordinates....
void setFlagsRoboDK(int flags=FLAG_ROBODK_ALL)
Update the RoboDK flags. RoboDK flags allow defining how much access the user has to certain RoboDK f...
void Finish()
Disconnect from the RoboDK API. This flushes any pending program generation.
void setFlagsItem(Item item, int flags=FLAG_ITEM_ALL)
Update item flags. Item flags allow defining how much access the user has to item-specific features....
void Render(bool always_render=false)
Update the scene.
double SimulationSpeed()
Gets the current simulation speed. Set the speed to 1 for a real-time simulation.
bool FileSet(const QString &file_local, const QString &file_remote="", bool load_file=true, Item *attach_to=nullptr)
Send file from the current location to the RoboDK instance.
The tJoints class represents a joint position of a robot (robot axes).
Definition: robodk_api.h:384
int GetValues(double *joints)
GetValues.
Definition: robodk_api.cpp:121
tJoints(int ndofs=0)
tJoints
Definition: robodk_api.cpp:42
QString ToString(const QString &separator=", ", int precision=3) const
Retrieve a string representation of the joint values.
Definition: robodk_api.cpp:127
bool Valid() const
Check if the joints are valid. For example, when we request the Inverse kinematics and there is no so...
Definition: robodk_api.cpp:163
int Length() const
Number of joint axes of the robot (or degrees of freedom)
Definition: robodk_api.cpp:153
const double * Values() const
Joint values.
Definition: robodk_api.cpp:94
int _nDOFs
number of degrees of freedom
Definition: robodk_api.h:485
const double * ValuesD() const
Joint values.
Definition: robodk_api.cpp:80
double _Values[RDK_SIZE_JOINTS_MAX]
joint values (doubles, used to store the joint values)
Definition: robodk_api.h:488
bool FromString(const QString &str)
Set the joint values given a comma-separated string. Tabs and spaces are also allowed.
Definition: robodk_api.cpp:143
void setLength(int new_length)
Set the length of the array (only shrinking the array is allowed)
Definition: robodk_api.cpp:157
float _ValuesF[RDK_SIZE_JOINTS_MAX]
joint values (floats, used to return a copy as a float pointer)
Definition: robodk_api.h:491
const float * ValuesF() const
Joint values.
Definition: robodk_api.cpp:83
void SetValues(const double *joints, int ndofs=-1)
Set the joint values in deg or mm. You can also important provide the number of degrees of freedom (6...
Definition: robodk_api.cpp:104
All RoboDK API functions are wrapped in the RoboDK_API namespace. If you prefer to forget about the R...
Definition: robodk_api.cpp:37
double * Matrix2D_Get_col(const tMatrix2D *var, int col)
Returns the pointer of a column of a tMatrix2D. A column has Matrix2D_Get_nrows values that can be ac...
tMatrix2D * Matrix2D_Create()
Creates a new 2D matrix tMatrix2D.. Use Matrix2D_Delete to delete the matrix (to free the memory)....
Mat roty(double ry)
Translation matrix class: Mat::roty.
Definition: robodk_api.cpp:181
int Matrix2D_Get_ncols(const tMatrix2D *var)
Returns the number of columns of a tMatrix2D.
double Matrix2D_Get_ij(const tMatrix2D *var, int i, int j)
Returns the value at location [i,j] of a tMatrix2D.
Mat rotz(double rz)
Translation matrix class: Mat::rotz.
Definition: robodk_api.cpp:185
double tConfig[RDK_SIZE_MAX_CONFIG]
The robot configuration defines a specific state of the robot without crossing any singularities....
Definition: robodk_api.h:310
Mat transl(double x, double y, double z)
Translation matrix class: Mat::transl.
Definition: robodk_api.cpp:173
void Matrix2D_Set_Size(tMatrix2D *mat, int rows, int cols)
Sets the size of a tMatrix2D.
int Matrix2D_Size(const tMatrix2D *var, int dim)
Sets the size of a tMatrix2D.
void Debug_Matrix2D(const tMatrix2D *emx)
Display the content of a tMatrix2D through STDOUT. This is only intended for debug purposes.
Mat rotx(double rx)
Translation matrix class: Mat::rotx.
Definition: robodk_api.cpp:177
double tXYZ[3]
tXYZ (mm) represents a position or a vector in mm
Definition: robodk_api.h:299
int Matrix2D_Get_nrows(const tMatrix2D *var)
Returns the number of rows of a tMatrix2D.
void Debug_Array(const double *array, int arraysize)
Show an array through STDOUT Given an array of doubles, it generates a string.
void Matrix2D_Delete(tMatrix2D **mat)
Deletes a tMatrix2D.
double tXYZWPR[6]
Six doubles that represent robot joints (usually in degrees)
Definition: robodk_api.h:296
The Color struct represents an RGBA color (each color component should be in the range [0-1])
Definition: robodk_api.h:336
float r
Red color.
Definition: robodk_api.h:338
float a
Alpha value (0 = transparent; 1 = opaque)
Definition: robodk_api.h:347
float b
Blue color.
Definition: robodk_api.h:344
float g
Green color.
Definition: robodk_api.h:341
The tMatrix2D struct represents a variable size 2d Matrix. Use the Matrix2D_... functions to oeprate ...
Definition: robodk_api.h:361
double * data
Pointer to the data.
Definition: robodk_api.h:363
int * size
Pointer to the size array.
Definition: robodk_api.h:366
int numDimensions
Number of dimensions (usually 2)
Definition: robodk_api.h:372