RoboDK API - Documentation
robodk_api.h
1// Copyright 2015-2021 - RoboDK Inc. - https://robodk.com/
2// Licensed under the Apache License, Version 2.0 (the "License");
3// you may not use this file except in compliance with the License.
4// You may obtain a copy of the License at
5// http://www.apache.org/licenses/LICENSE-2.0
6// Unless required by applicable law or agreed to in writing, software
7// distributed under the License is distributed on an "AS IS" BASIS,
8// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
9// See the License for the specific language governing permissions and
10// limitations under the License.
11//
12// --------------------------------------------
13// --------------- DESCRIPTION ----------------
14// This file defines the following two classes:
15// Joints : for 1D arrays representing joint values
16// Mat : for pose multiplications
17// RoboDK (Robolink()) : Main interface with RoboDK
18// Item : Represents an item in the RoboDK station
19// These classes are the objects used to interact with RoboDK and create macros.
20// An item is an object in the RoboDK tree (it can be either a robot, an object, a tool, a frame, a program, ...).
21// Items can be retrieved from the RoboDK station using the Robolink() object (such as Robolink.Item() method)
22//
23// In this document: pose = transformation matrix = homogeneous matrix = 4x4 matrix
24//
25// More information about the RoboDK API here:
26// https://robodk.com/doc/en/RoboDK-API.html
27// https://robodk.com/doc/en/PythonAPI/index.html
28//
29// More information about RoboDK post processors here:
30// https://robodk.com/help#PostProcessor
31//
32// Visit the Matrix and Quaternions FAQ for more information about pose/homogeneous transformations
33// http://www.j3d.org/matrix_faq/matrfaq_latest.html
34//
35//---------------------------------------------
36// TIPS:
37// 1- Add #define RDK_SKIP_NAMESPACE
38// to avoid using the RoboDK_API namespace
39// 2- Add #define RDK_WITH_EXPORTS (and RDK_EXPORTS)
40// to generate/import as a DLL
41//---------------------------------------------
42
43
245#ifndef ROBODK_API_H
246#define ROBODK_API_H
247
248
249
250#ifdef RDK_WITH_EXPORTS
251 #ifdef RDK_EXPORTS
252 #define ROBODK __declspec(dllexport)
253 #else
254 #define ROBODK __declspec(dllimport)
255 #endif
256#else
257 #define ROBODK
258#endif
259
260
261#include <QtCore/QString>
262#include <QtGui/QMatrix4x4> // this should not be part of the QtGui! it is just a matrix
263#include <QDebug>
264
265
266class QTcpSocket;
267
268
269#ifndef RDK_SKIP_NAMESPACE
270
272namespace RoboDK_API {
273#endif
274
275
276class Item;
277class RoboDK;
278
279
281#define RDK_SIZE_JOINTS_MAX 12
282// IMPORTANT!! Do not change this value
283
285#define RDK_SIZE_MAX_CONFIG 4
286// IMPORTANT!! Do not change this value
287
289//typedef double tJoints[RDK_SIZE_JOINTS_MAX];
290
291
296typedef double tXYZWPR[6];
297
299typedef double tXYZ[3];
300
301
310typedef double tConfig[RDK_SIZE_MAX_CONFIG];
311
312
314#define DOT(v,q) ((v)[0]*(q)[0] + (v)[1]*(q)[1] + (v)[2]*(q)[2])
315
317#define NORM(v) (sqrt((v)[0]*(v)[0] + (v)[1]*(v)[1] + (v)[2]*(v)[2]))
318
320#define CROSS(out,a,b) \
321 (out)[0] = (a)[1]*(b)[2] - (b)[1]*(a)[2]; \
322 (out)[1] = (a)[2]*(b)[0] - (b)[2]*(a)[0]; \
323 (out)[2] = (a)[0]*(b)[1] - (b)[0]*(a)[1];
324
326#define NORMALIZE(inout){\
327 double norm;\
328 norm = sqrt((inout)[0]*(inout)[0] + (inout)[1]*(inout)[1] + (inout)[2]*(inout)[2]);\
329 (inout)[0] = (inout)[0]/norm;\
330 (inout)[1] = (inout)[1]/norm;\
331 (inout)[2] = (inout)[2]/norm;}
332
333
334
336struct Color{
338 float r;
339
341 float g;
342
344 float b;
345
347 float a;
348};
349
350
351
352
353
354
355//------------------------------------------------------------------------------------------------------------
356
357
358
361struct tMatrix2D {
363 double *data;
364
366 int *size;
367
370
373
374 bool canFreeData;
375};
376
377
378
379
380
381//--------------------- Joints class -----------------------
382
384class ROBODK tJoints {
385
386public:
389 tJoints(int ndofs = 0);
390
394 tJoints(const double *joints, int ndofs = 0);
395
399 tJoints(const float *joints, int ndofs = 0);
400
403 tJoints(const tJoints &jnts);
404
409 tJoints(const tMatrix2D *mat2d, int column=0, int ndofs=-1);
410
413 tJoints(const QString &str);
414
416 operator QString() const { return ToString(); }
417
420 const double *ValuesD() const;
421
424 const float *ValuesF() const;
425
426#ifdef ROBODK_API_FLOATS
429 const float *Values() const;
430#else
433 const double *Values() const;
434#endif
435
436
437
438
439
442 double *Data();
443
446 int Length() const;
447
449 void setLength(int new_length);
450
454 bool Valid() const;
455
459 int GetValues(double *joints);
460
464 void SetValues(const double *joints, int ndofs = -1);
465
469 void SetValues(const float *joints, int ndofs = -1);
470
475 QString ToString(const QString &separator=", ", int precision = 3) const;
476
480 bool FromString(const QString &str);
481
482
483public:
486
488 double _Values[RDK_SIZE_JOINTS_MAX];
489
491 float _ValuesF[RDK_SIZE_JOINTS_MAX];
492};
493
494
495
496
506class ROBODK Mat : public QMatrix4x4 {
507
508public:
509
511 Mat();
512
514 Mat(bool valid);
515
517 Mat(const QMatrix4x4 &matrix);
518
521 Mat(const Mat &matrix);
522
543 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);
544
552 Mat(const double values[16]);
553
562 Mat(const float values[16]);
563
564 ~Mat();
565
567 operator QString() const { return ToString(); }
568
570 void setVX(double x, double y, double z);
571
573 void setVY(double x, double y, double z);
574
576 void setVZ(double x, double y, double z);
577
579 void setPos(double x, double y, double z);
580
582 void setVX(double xyz[3]);
583
585 void setVY(double xyz[3]);
586
588 void setVZ(double xyz[3]);
589
591 void setPos(double xyz[3]);
592
594 void VX(tXYZ xyz) const;
595
597 void VY(tXYZ xyz) const;
598
600 void VZ(tXYZ xyz) const;
601
603 void Pos(tXYZ xyz) const;
604
609 void Set(int r, int c, double value);
610
615 double Get(int r, int c) const;
616
618 Mat inv() const;
619
621 bool isHomogeneous() const;
622
624 bool MakeHomogeneous();
625
626
627
628
629 //------ Pose to xyzrpw and xyzrpw to pose------------
630
637 void ToXYZRPW(tXYZWPR xyzwpr) const;
638
644 QString ToString(const QString &separator=", ", int precision = 3, bool xyzwpr_only = false) const;
645
647 bool FromString(const QString &str);
648
656 void FromXYZRPW(tXYZWPR xyzwpr);
657
665 static Mat XYZRPW_2_Mat(double x, double y, double z, double r, double p, double w);
666 static Mat XYZRPW_2_Mat(tXYZWPR xyzwpr);
667
669 const double* ValuesD() const;
670
672 const float* ValuesF() const;
673
674#ifdef ROBODK_API_FLOATS
676 const float* Values() const;
677#else
679 const double* Values() const;
680#endif
681
683 void Values(double values[16]) const;
684
686 void Values(float values[16]) const;
687
689 bool Valid() const;
690
704 static Mat transl(double x, double y, double z);
705
717 static Mat rotx(double rx);
718
730 static Mat roty(double ry);
731
743 static Mat rotz(double rz);
744
745
746private:
748 bool _valid;
749
750// this is a dummy variable to easily obtain a pointer to a 16-double-array for matrix multiplications
751private:
753 double _ddata16[16];
754
755};
756
762class ROBODK RoboDK {
763 friend class RoboDK_API::Item;
764
765public:
766 RoboDK(const QString &robodk_ip="", int com_port=-1, const QString &args="", const QString &path="");
767 ~RoboDK();
768
769 quint64 ProcessID();
770 quint64 WindowID();
771
772 bool Connected();
773 bool Connect();
774
775 void Disconnect();
776 void Finish();
777
778
785 Item getItem(QString name, int itemtype = -1);
786
793 QStringList getItemListNames(int filter = -1);
794
801 QList<Item> getItemList(int filter = -1);
802
810 Item ItemUserPick(const QString &message = "Pick one item", int itemtype = -1);
811
815 void ShowRoboDK();
816
820 void HideRoboDK();
821
825 void CloseRoboDK();
826
830 QString Version();
831
836 void setWindowState(int windowstate = WINDOWSTATE_NORMAL);
837
842 void setFlagsRoboDK(int flags = FLAG_ROBODK_ALL);
843
849 void setFlagsItem(Item item, int flags = FLAG_ITEM_ALL);
850
856 int getFlagsItem(Item item);
857
863 void ShowMessage(const QString &message, bool popup = true);
864
869 void Copy(const Item &tocopy);
870
876 Item Paste(const Item *paste_to=nullptr);
877
884 Item AddFile(const QString &filename, const Item *parent=nullptr);
885
891 void Save(const QString &filename, const Item *itemsave=nullptr);
892
901 Item AddShape(tMatrix2D *trianglePoints,Item *addTo = nullptr, bool shapeOverride = false, Color *color = nullptr);
902
911 Item AddCurve(tMatrix2D *curvePoints,Item *referenceObject = nullptr,bool addToRef = false,int ProjectionType = PROJECTION_ALONG_NORMAL_RECALC);
912
921 Item AddPoints(tMatrix2D *points, Item *referenceObject = nullptr, bool addToRef = false, int ProjectionType = PROJECTION_ALONG_NORMAL_RECALC);
922
930 void ProjectPoints(tMatrix2D *points, tMatrix2D **projected, Item objectProject, int ProjectionType = PROJECTION_ALONG_NORMAL_RECALC);
931
935 void CloseStation();
936
944 Item AddTarget(const QString &name, Item *itemparent = nullptr, Item *itemrobot = nullptr);
945
952 Item AddFrame(const QString &name, Item *itemparent = nullptr);
953
960 Item AddProgram(const QString &name, Item *itemrobot = nullptr);
961
966 Item AddStation(const QString &name);
967
976 Item AddMachiningProject(const QString &name = "Curve follow settings",Item *itemrobot = nullptr);
977
982 QList<Item> getOpenStation();
983
988 void setActiveStation(Item stn);
989
994 Item getActiveStation();
995
1001 int RunProgram(const QString &function_w_params);
1002
1009 int RunCode(const QString &code, bool code_is_fcn_call = false);
1010
1016 void RunMessage(const QString &message, bool message_is_comment = false);
1017
1022 void Render(bool always_render = false);
1023
1028 void Update();
1029
1036 bool IsInside(Item object_inside, Item object_parent);
1037
1043 int setCollisionActive(int check_state = COLLISION_ON);
1044
1055 bool setCollisionActivePair(int check_state, Item item1, Item item2, int id1 = 0, int id2 = 0);
1056
1061 int Collisions();
1062
1069 int Collision(Item item1, Item item2);
1070
1076 QList<Item> getCollisionItems(QList<int> link_id_list);
1077
1082 void setSimulationSpeed(double speed);
1083
1088 double SimulationSpeed();
1089
1100 void setRunMode(int run_mode = 1);
1101
1110 int RunMode();
1111
1118 QList<QPair<QString, QString> > getParams();
1119
1131 QString getParam(const QString &param);
1132
1140 void setParam(const QString &param, const QString &value);
1141
1148 QString Command(const QString &cmd, const QString &value="");
1149
1150 // --- add calibrate reference, calibrate tool, measure tracker, etc...
1151
1159 bool LaserTrackerMeasure(tXYZ xyz, tXYZ estimate, bool search = false);
1160
1170
1172 void setVisible(QList<Item> itemList, QList<bool> visibleList, QList<int> visibleFrames);
1173
1176 void ShowAsCollided(QList<Item> itemList, QList<bool> collidedList, QList<int> *robot_link_id = nullptr);
1177
1187 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);
1188
1197 Mat CalibrateReference(tMatrix2D *poses_joints, int method = CALIBRATE_FRAME_3P_P1_ON_X, bool use_joints = false, Item *robot = nullptr);
1198
1208 int ProgramStart(const QString &progname, const QString &defaultfolder = "", const QString &postprocessor = "", Item *robot = nullptr);
1209
1214 void setViewPose(const Mat &pose);
1215
1220 Mat ViewPose();
1221
1229 Item Cam2D_Add(const Item &item_object, const QString &cam_params, const Item *cam_item=nullptr);
1230
1238 int Cam2D_Snapshot(const QString &file_save_img, const Item &cam_item, const QString &params="");
1239
1246 int Cam2D_SetParams(const QString &cam_params, const Item &cam_item);
1247
1256 bool setRobotParams(Item *robot,tMatrix2D dhm, Mat poseBase, Mat poseTool);
1257
1267 Item getCursorXYZ(int x = -1, int y = -1, tXYZ xyzStation = nullptr);
1268
1273 QString License();
1274
1279 QList<Item> Selection();
1280
1285 void setSelection(QList<Item> list_items);
1286
1290 void PluginLoad(const QString &pluginName, int load=1);
1291
1295 QString PluginCommand(const QString &pluginName, const QString &pluginCommand, const QString &pluginValue="");
1296
1304 Item Popup_ISO9283_CubeProgram(Item *robot=nullptr, tXYZ center=nullptr, double side=-1, bool blocking=true);
1305
1307 bool FileSet(const QString &file_local, const QString &file_remote="", bool load_file=true, Item *attach_to=nullptr);
1308
1310 bool FileGet(const QString &path_file_local, Item *station=nullptr, const QString path_file_remote="");
1311
1312 bool EmbedWindow(QString window_name, QString docked_name="", int size_w=-1, int size_h=-1, quint64 pid=0, int area_add=1, int area_allowed=15, int timeout=500);
1313
1314 bool EventsListen();
1315 bool WaitForEvent(int &evt,Item &itm);
1316 bool Event_Receive_3D_POS(double *data, int *valueCount);
1317 bool Event_Receive_Mouse_data(int *data);
1318 bool Event_Receive_Event_Moved(Mat *pose_rel_out);
1319 bool Event_Connected();
1320
1321public:
1322
1323
1325 enum {
1327 ITEM_TYPE_ANY = -1,
1328
1330 ITEM_TYPE_STATION = 1,
1331
1333 ITEM_TYPE_ROBOT = 2,
1334
1336 ITEM_TYPE_FRAME = 3,
1337
1339 ITEM_TYPE_TOOL = 4,
1340
1342 ITEM_TYPE_OBJECT = 5,
1343
1345 ITEM_TYPE_TARGET = 6,
1346
1348 ITEM_TYPE_PROGRAM = 8,
1349
1351 ITEM_TYPE_INSTRUCTION = 9,
1352
1354 ITEM_TYPE_PROGRAM_PYTHON = 10,
1355
1357 ITEM_TYPE_MACHINING = 11,
1358
1360 ITEM_TYPE_BALLBARVALIDATION = 12,
1361
1363 ITEM_TYPE_CALIBPROJECT = 13,
1364
1366 ITEM_TYPE_VALID_ISO9283 = 14
1368
1370 enum {
1372 INS_TYPE_INVALID = -1,
1373
1375 INS_TYPE_MOVE = 0,
1376
1378 INS_TYPE_MOVEC = 1,
1379
1381 INS_TYPE_CHANGESPEED = 2,
1382
1384 INS_TYPE_CHANGEFRAME = 3,
1385
1387 INS_TYPE_CHANGETOOL = 4,
1388
1390 INS_TYPE_CHANGEROBOT = 5,
1391
1393 INS_TYPE_PAUSE = 6,
1394
1396 INS_TYPE_EVENT = 7,
1397
1399 INS_TYPE_CODE = 8,
1400
1402 INS_TYPE_PRINT = 9
1404
1406 enum {
1408 MOVE_TYPE_INVALID = -1,
1409
1411 MOVE_TYPE_JOINT = 1,
1412
1414 MOVE_TYPE_LINEAR = 2,
1415
1417 MOVE_TYPE_CIRCULAR = 3
1419
1421 enum {
1423 RUNMODE_SIMULATE = 1,
1424
1426 RUNMODE_QUICKVALIDATE = 2,
1427
1429 RUNMODE_MAKE_ROBOTPROG = 3,
1430
1432 RUNMODE_MAKE_ROBOTPROG_AND_UPLOAD = 4,
1433
1435 RUNMODE_MAKE_ROBOTPROG_AND_START = 5,
1436
1438 RUNMODE_RUN_ROBOT = 6
1440
1442 enum {
1444 PROGRAM_RUN_ON_SIMULATOR = 1,
1445
1447 PROGRAM_RUN_ON_ROBOT = 2
1449
1451 enum {
1452
1454 CALIBRATE_TCP_BY_POINT = 0,
1455
1457 CALIBRATE_TCP_BY_PLANE = 1
1459
1461 enum {
1463 CALIBRATE_FRAME_3P_P1_ON_X = 0,
1464
1466 CALIBRATE_FRAME_3P_P1_ORIGIN = 1,
1467
1469 CALIBRATE_FRAME_6P = 2,
1470
1472 CALIBRATE_TURNTABLE = 3
1474
1476 enum {
1478 PROJECTION_NONE = 0,
1479
1481 PROJECTION_CLOSEST = 1,
1482
1484 PROJECTION_ALONG_NORMAL = 2,
1485
1487 PROJECTION_ALONG_NORMAL_RECALC = 3,
1488
1490 PROJECTION_CLOSEST_RECALC = 4,
1491
1493 PROJECTION_RECALC = 5
1495
1497 enum {
1498
1500 JOINT_FORMAT = -1,
1501
1503 EULER_RX_RYp_RZpp = 0,
1504
1506 EULER_RZ_RYp_RXpp = 1,
1507
1509 EULER_RZ_RYp_RZpp = 2,
1510
1512 EULER_RZ_RXp_RZpp = 3,
1513
1515 EULER_RX_RY_RZ = 4,
1516
1518 EULER_RZ_RY_RX = 5,
1519
1521 EULER_QUEATERNION = 6
1523
1525 enum {
1526
1528 WINDOWSTATE_HIDDEN = -1,
1529
1531 WINDOWSTATE_SHOW = 0,
1532
1534 WINDOWSTATE_MINIMIZED = 1,
1535
1537 WINDOWSTATE_NORMAL = 2,
1538
1540 WINDOWSTATE_MAXIMIZED = 3,
1541
1543 WINDOWSTATE_FULLSCREEN = 4,
1544
1546 WINDOWSTATE_CINEMA = 5,
1547
1549 WINDOWSTATE_FULLSCREEN_CINEMA = 6
1551
1553 enum {
1555 INSTRUCTION_CALL_PROGRAM = 0,
1556
1558 INSTRUCTION_INSERT_CODE = 1,
1559
1561 INSTRUCTION_START_THREAD = 2,
1562
1564 INSTRUCTION_COMMENT = 3,
1565
1567 INSTRUCTION_SHOW_MESSAGE = 4
1569
1571 enum {
1573 FEATURE_NONE = 0,
1574
1576 FEATURE_SURFACE = 1,
1577
1579 FEATURE_CURVE = 2,
1580
1582 FEATURE_POINT = 3
1584
1586 enum {
1588 SPRAY_OFF = 0,
1589 SPRAY_ON = 1
1590 };
1591
1593 enum {
1595 COLLISION_OFF = 0,
1596
1598 COLLISION_ON = 1
1600
1601 // Event types
1602 enum {
1603 EVENT_SELECTION_TREE_CHANGED = 1,
1604 EVENT_ITEM_MOVED = 2, // obsolete after RoboDK 4.2.0. Use EVENT_ITEM_MOVED_POSE instead
1605 EVENT_REFERENCE_PICKED = 3,
1606 EVENT_REFERENCE_RELEASED = 4,
1607 EVENT_TOOL_MODIFIED = 5,
1608 EVENT_CREATED_ISOCUBE = 6,
1609 EVENT_SELECTION_3D_CHANGED = 7,
1610 EVENT_3DVIEW_MOVED = 8,
1611 EVENT_ROBOT_MOVED = 9,
1612 EVENT_KEY = 10,
1613 EVENT_ITEM_MOVED_POSE = 11
1614 };
1615
1616
1618 enum {
1620 FLAG_ROBODK_TREE_ACTIVE = 1,
1621
1623 FLAG_ROBODK_3DVIEW_ACTIVE = 2,
1624
1626 FLAG_ROBODK_LEFT_CLICK = 4,
1627
1629 FLAG_ROBODK_RIGHT_CLICK = 8,
1630
1632 FLAG_ROBODK_DOUBLE_CLICK = 16,
1633
1635 FLAG_ROBODK_MENU_ACTIVE = 32,
1636
1638 FLAG_ROBODK_MENUFILE_ACTIVE = 64,
1639
1641 FLAG_ROBODK_MENUEDIT_ACTIVE = 128,
1642
1644 FLAG_ROBODK_MENUPROGRAM_ACTIVE = 256,
1645
1647 FLAG_ROBODK_MENUTOOLS_ACTIVE = 512,
1648
1650 FLAG_ROBODK_MENUUTILITIES_ACTIVE = 1024,
1651
1653 FLAG_ROBODK_MENUCONNECT_ACTIVE = 2048,
1654
1656 FLAG_ROBODK_WINDOWKEYS_ACTIVE = 4096,
1657
1659 FLAG_ROBODK_NONE = 0,
1660
1662 FLAG_ROBODK_ALL = 0xFFFF,
1663
1665 FLAG_ROBODK_MENU_ACTIVE_ALL = FLAG_ROBODK_MENU_ACTIVE | FLAG_ROBODK_MENUFILE_ACTIVE | FLAG_ROBODK_MENUEDIT_ACTIVE | FLAG_ROBODK_MENUPROGRAM_ACTIVE | FLAG_ROBODK_MENUTOOLS_ACTIVE | FLAG_ROBODK_MENUUTILITIES_ACTIVE | FLAG_ROBODK_MENUCONNECT_ACTIVE
1667
1669 enum {
1671 FLAG_ITEM_SELECTABLE = 1,
1672
1674 FLAG_ITEM_EDITABLE = 2,
1675
1677 FLAG_ITEM_DRAGALLOWED = 4,
1678
1680 FLAG_ITEM_DROPALLOWED = 8,
1681
1683 FLAG_ITEM_ENABLED = 32,
1684
1686 FLAG_ITEM_AUTOTRISTATE = 64,
1687
1689 FLAG_ITEM_NOCHILDREN = 128,
1690 FLAG_ITEM_USERTRISTATE = 256,
1691
1693 FLAG_ITEM_NONE = 0,
1694
1696 FLAG_ITEM_ALL = 64 + 32 + 8 + 4 + 2 + 1
1698
1699private:
1700 QTcpSocket *_COM;
1701 QTcpSocket *_COM_EVT;
1702 QString _IP;
1703 int _PORT;
1704 int _TIMEOUT;
1705 qint64 _PROCESS;
1706
1707 QString _ROBODK_BIN; // file path to the robodk program (executable), typically C:/RoboDK/bin/RoboDK.exe. Leave empty to use the registry key: HKEY_LOCAL_MACHINE\SOFTWARE\RoboDK
1708 QString _ARGUMENTS; // arguments to provide to RoboDK on startup
1709
1710 bool _connected();
1711 bool _connect();
1712 bool _connect_smart(); // will attempt to start RoboDK
1713 void _disconnect();
1714
1715 bool _check_connection();
1716 bool _check_status();
1717
1718 bool _waitline(QTcpSocket *com = nullptr);
1719 QString _recv_Line(QTcpSocket *com = nullptr);//QString &string);
1720 bool _send_Line(const QString &string,QTcpSocket *com = nullptr);
1721 int _recv_Int(QTcpSocket *com = nullptr);//qint32 &value);
1722 bool _send_Int(const qint32 value,QTcpSocket *com = nullptr);
1723 Item _recv_Item(QTcpSocket *com = nullptr);//Item *item);
1724 bool _send_Item(const Item *item);
1725 bool _send_Item(const Item &item);
1726 Mat _recv_Pose(QTcpSocket *com = nullptr);//Mat &pose);
1727 bool _send_Pose(const Mat &pose);
1728 bool _recv_XYZ(tXYZ pos);
1729 bool _send_XYZ(const tXYZ pos);
1730 bool _recv_Array(double *values, int *psize=nullptr,QTcpSocket *com = nullptr);
1731 bool _send_Array(const double *values, int nvalues);
1732 bool _recv_Array(tJoints *jnts);
1733 bool _send_Array(const tJoints *jnts);
1734 bool _send_Array(const Mat *mat);
1735 bool _recv_Matrix2D(tMatrix2D **mat);
1736 bool _send_Matrix2D(tMatrix2D *mat);
1737
1738
1739 void _moveX(const Item *target, const tJoints *joints, const Mat *mat_target, const Item *itemrobot, int movetype, bool blocking);
1740 void _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);
1741};
1742
1743
1749class ROBODK Item {
1750 friend class RoboDK_API::RoboDK;
1751
1752public:
1753 Item(RoboDK *rdk=nullptr, quint64 ptr=0, qint32 type=-1);
1754 Item(const Item &other);
1755 Item& operator=( const Item& x ) = default;
1756
1757 ~Item();
1758
1759 QString ToString() const;
1760
1761 RoboDK* RDK();
1762
1763 void NewLink();
1764
1766 int Type() const;
1767
1772 void Save(const QString &filename);
1773
1777 void Delete();
1778
1782 bool Valid(bool check_pointer=false) const ;
1783
1788 void setParent(Item parent);
1789
1795 void setParentStatic(Item parent);
1796
1801 Item AttachClosest();
1802
1807 Item DetachClosest(Item parent);
1808
1812 void DetachAll(Item parent);
1813
1818 Item Parent() const;
1819
1824 QList<Item> Childs() const;
1825
1830 bool Visible() const;
1831
1837 void setVisible(bool visible, int visible_frame = -1);
1838
1843 QString Name() const;
1844
1849 void setName(const QString &name);
1850
1856 void setPose(const Mat pose);
1857
1863 Mat Pose() const;
1864
1870 void setGeometryPose(const Mat pose);
1871
1876 Mat GeometryPose();
1877
1878 /*/// <summary>
1882 void setHtool(Mat pose);
1883 */
1884
1885 /*
1891 Mat Htool();
1892 */
1893
1898 Mat PoseTool();
1899
1904 Mat PoseFrame();
1905
1911 void setPoseFrame(const Mat frame_pose);
1912
1918 void setPoseFrame(const Item frame_item);
1919
1925 void setPoseTool(const Mat tool_pose);
1926
1932 void setPoseTool(const Item tool_item);
1933
1938 void setPoseAbs(const Mat pose);
1939
1944 Mat PoseAbs();
1945
1953 void setColor(double colorRGBA[4]);
1954
1955
1956
1957//---------- add more
1958
1963 void Scale(double scale);
1964
1970 void Scale(double scale_xyz[3]);
1971
2015 Item setMachiningParameters(QString ncfile = "", Item part_obj = nullptr, QString options = "");
2016
2020 void setAsCartesianTarget();
2021
2025 void setAsJointTarget();
2026
2030 bool isJointTarget() const ;
2031
2036 tJoints Joints() const ;
2037
2042 tJoints JointsHome() const;
2043
2047 void setJointsHome(const tJoints &jnts);
2048
2054 Item ObjectLink(int link_id = 0);
2055
2061 Item getLink(int type_linked = RoboDK::ITEM_TYPE_ROBOT);
2062
2066 void setJoints(const tJoints &jnts);
2067
2071 void JointLimits(tJoints *lower_limits, tJoints *upper_limits);
2072
2078 void setJointLimits(const tJoints &lower_limits, const tJoints &upper_limits);
2079
2085 void setRobot(const Item &robot);
2086
2093 Item AddTool(const Mat &tool_pose, const QString &tool_name = "New TCP");
2094
2100 Mat SolveFK(const tJoints &joints, const Mat *tool = nullptr, const Mat *ref = nullptr);
2101
2107 void JointsConfig(const tJoints &joints, tConfig config);
2108
2117 tJoints SolveIK(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr);
2118
2127 tJoints SolveIK(const Mat pose, tJoints joints_approx, const Mat *tool = nullptr, const Mat *ref = nullptr);
2128
2136 tMatrix2D *SolveIK_All_Mat2D(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr);
2137
2145 QList<tJoints> SolveIK_All(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr);
2146
2152 bool Connect(const QString &robot_ip = "");
2153
2158 bool Disconnect();
2159
2165 void MoveJ(const Item &itemtarget, bool blocking = true);
2166
2171 void MoveJ(const tJoints &joints, bool blocking = true);
2172
2177 void MoveJ(const Mat &target, bool blocking = true);
2178
2184 void MoveL(const Item &itemtarget, bool blocking = true);
2185
2190 void MoveL(const tJoints &joints, bool blocking = true);
2191
2196 void MoveL(const Mat &target, bool blocking = true);
2197
2203 void MoveC(const Item &itemtarget1, const Item &itemtarget2, bool blocking = true);
2204
2210 void MoveC(const tJoints &joints1, const tJoints &joints2, bool blocking = true);
2211
2217 void MoveC(const Mat &target1, const Mat &target2, bool blocking = true);
2218
2226 int MoveJ_Test(const tJoints &j1, const tJoints &j2, double minstep_deg = -1);
2227
2235 int MoveL_Test(const tJoints &joints1, const Mat &pose2, double minstep_mm = -1);
2236
2244 void setSpeed(double speed_linear, double accel_linear = -1, double speed_joints = -1, double accel_joints = -1);
2245
2250 void setRounding(double zonedata);
2251
2256 void ShowSequence(tMatrix2D *sequence);
2257
2262 bool Busy();
2263
2267 void Stop();
2268
2273 void WaitMove(double timeout_sec = 300) const;
2274
2279 void setAccuracyActive(int accurate = 1);
2280
2287 bool MakeProgram(const QString &filename);
2288
2294 void setRunType(int program_run_type);
2295
2305 int RunProgram();
2306
2316 int RunCode(const QString &parameters);
2317
2323 int RunInstruction(const QString &code, int run_type = RoboDK::INSTRUCTION_CALL_PROGRAM);
2324
2329 void Pause(double time_ms = -1);
2330
2336 void setDO(const QString &io_var, const QString &io_value);
2337
2343 void setAO(const QString &io_var, const QString &io_value);
2344
2349 QString getDI(const QString &io_var);
2350
2351
2356 QString getAI(const QString &io_var);
2357
2364 void waitDI(const QString &io_var, const QString &io_value, double timeout_ms = -1);
2365
2375 void customInstruction(const QString &name, const QString &path_run, const QString &path_icon = "", bool blocking = true, const QString &cmd_run_on_robot = "");
2376
2377
2378 //void addMoveJ(const Item &itemtarget);
2379 //void addMoveL(const Item &itemtarget);
2380
2385 void ShowInstructions(bool visible=true);
2386
2391 void ShowTargets(bool visible=true);
2392
2397 int InstructionCount();
2398
2409 void Instruction(int ins_id, QString &name, int &instype, int &movetype, bool &isjointtarget, Mat &target, tJoints &joints);
2410
2421 void setInstruction(int ins_id, const QString &name, int instype, int movetype, bool isjointtarget, const Mat &target, const tJoints &joints);
2422
2428 int InstructionList(tMatrix2D *instructions);
2429
2440 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);
2441
2456 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);
2457
2458
2467 QString setParam(const QString &param, const QString &value);
2468
2473 bool Finish();
2474
2475
2477 quint64 GetID();
2478
2479
2480private:
2483
2485 quint64 _PTR;
2486
2488 qint32 _TYPE;
2489};
2490
2491
2492
2494ROBODK Mat transl(double x, double y, double z);
2495
2497ROBODK Mat rotx(double rx);
2498
2500ROBODK Mat roty(double ry);
2501
2503ROBODK Mat rotz(double rz);
2504
2505
2509ROBODK tMatrix2D* Matrix2D_Create();
2510
2513ROBODK void Matrix2D_Delete(tMatrix2D **mat);
2514
2519ROBODK void Matrix2D_Set_Size(tMatrix2D *mat, int rows, int cols);
2520
2524ROBODK int Matrix2D_Size(const tMatrix2D *mat, int dim);
2525
2529ROBODK int Matrix2D_Get_ncols(const tMatrix2D *var);
2530
2534ROBODK int Matrix2D_Get_nrows(const tMatrix2D *var);
2535
2539ROBODK double Matrix2D_Get_ij(const tMatrix2D *var, int i, int j);
2540
2546ROBODK double* Matrix2D_Get_col(const tMatrix2D *var, int col);
2547
2550ROBODK void Debug_Array(const double *array, int arraysize);
2551
2554ROBODK void Debug_Matrix2D(const tMatrix2D *mat);
2555
2556
2560//ROBODK void Debug_Mat(Mat pose, char show_full_pose);
2561
2562
2563
2564
2565//QDataStream &operator<<(QDataStream &data, const QMatrix4x4 &);
2566inline QDebug operator<<(QDebug dbg, const Mat &m){ return dbg.noquote() << m.ToString(); }
2567inline QDebug operator<<(QDebug dbg, const tJoints &jnts){ return dbg.noquote() << jnts.ToString(); }
2568inline QDebug operator<<(QDebug dbg, const Item &itm){ return dbg.noquote() << itm.ToString(); }
2569
2570inline QDebug operator<<(QDebug dbg, const Mat *m){ return dbg.noquote() << (m == nullptr ? "Mat(null)" : m->ToString()); }
2571inline QDebug operator<<(QDebug dbg, const tJoints *jnts){ return dbg.noquote() << (jnts == nullptr ? "tJoints(null)" : jnts->ToString()); }
2572inline QDebug operator<<(QDebug dbg, const Item *itm){ return dbg.noquote() << (itm == nullptr ? "Item(null)" : itm->ToString()); }
2573
2574
2575#ifndef RDK_SKIP_NAMESPACE
2576}
2577
2578#endif
2579
2580
2581
2582
2583#endif // ROBODK_API
The Item class represents an item in RoboDK station. An item can be a robot, a frame,...
Definition: robodk_api.h:1749
bool Connect(const QString &robot_ip="")
Connect to a real robot using the corresponding robot driver.
qint32 _TYPE
Item type.
Definition: robodk_api.h:2488
int RunCode(const QString &parameters)
Runs a program. It returns the number of instructions that can be executed successfully (a quick prog...
bool Disconnect()
Disconnect from a real robot (when the robot driver is used)
RoboDK * _RDK
Pointer to RoboDK link object.
Definition: robodk_api.h:2482
quint64 _PTR
Pointer to the item inside RoboDK.
Definition: robodk_api.h:2485
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
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...
bool Finish()
Disconnect from the RoboDK API. This flushes any pending program generation.
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
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 _valid
Flags if a matrix is not valid.
Definition: robodk_api.h:748
This class is the iterface to the RoboDK API. With the RoboDK API you can automate certain tasks and ...
Definition: robodk_api.h:762
@ COLLISION_OFF
Do not use collision checking.
Definition: robodk_api.h:1595
@ ITEM_TYPE_ROBOT
Item of type robot (.robot file).
Definition: robodk_api.h:1333
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...
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.
@ INSTRUCTION_CALL_PROGRAM
Instruction to call a program.
Definition: robodk_api.h:1555
bool CollisionLine(tXYZ p1, tXYZ p2)
Checks the collision between a line and any objects in the station. The line is composed by 2 points....
void Disconnect()
Disconnect from the RoboDK API. This flushes any pending program generation.
bool setRobotParams(Item *robot, tMatrix2D dhm, Mat poseBase, Mat poseTool)
Set the nominal robot parameters.
void setVisible(QList< Item > itemList, QList< bool > visibleList, QList< int > visibleFrames)
Set a list of items visibile (faster than the default setVisible())
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 ...
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...
void Finish()
Disconnect from the RoboDK API. This flushes any pending program generation.
The tJoints class represents a joint position of a robot (robot axes).
Definition: robodk_api.h:384
int _nDOFs
number of degrees of freedom
Definition: robodk_api.h:485
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.
QDebug operator<<(QDebug dbg, const Mat &m)
Displays the content of a Mat through STDOUT. This is only intended for debug purposes.
Definition: robodk_api.h:2566
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 allocatedSize
Allocated size.
Definition: robodk_api.h:369
int numDimensions
Number of dimensions (usually 2)
Definition: robodk_api.h:372