RoboDK API for C++ - Documentation
Loading...
Searching...
No Matches
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 QAbstractSocket;
267
268
269#ifndef RDK_SKIP_NAMESPACE
270
272namespace RoboDK_API {
273#endif
274
275
276class Item;
277class RoboDK;
278struct GetPointsResult;
279
280
282#define RDK_SIZE_JOINTS_MAX 12
283// IMPORTANT!! Do not change this value
284
286#define RDK_SIZE_MAX_CONFIG 4
287// IMPORTANT!! Do not change this value
288
290//typedef double tJoints[RDK_SIZE_JOINTS_MAX];
291
292
297typedef double tXYZWPR[6];
298
300typedef double tXYZ[3];
301
302
311typedef double tConfig[RDK_SIZE_MAX_CONFIG];
312
313
315#define DOT(v,q) ((v)[0]*(q)[0] + (v)[1]*(q)[1] + (v)[2]*(q)[2])
316
318#define NORM(v) (sqrt((v)[0]*(v)[0] + (v)[1]*(v)[1] + (v)[2]*(v)[2]))
319
321#define CROSS(out,a,b) \
322 (out)[0] = (a)[1]*(b)[2] - (b)[1]*(a)[2]; \
323 (out)[1] = (a)[2]*(b)[0] - (b)[2]*(a)[0]; \
324 (out)[2] = (a)[0]*(b)[1] - (b)[0]*(a)[1];
325
327#define NORMALIZE(inout){\
328 double norm;\
329 norm = sqrt((inout)[0]*(inout)[0] + (inout)[1]*(inout)[1] + (inout)[2]*(inout)[2]);\
330 (inout)[0] = (inout)[0]/norm;\
331 (inout)[1] = (inout)[1]/norm;\
332 (inout)[2] = (inout)[2]/norm;}
333
334
335
337struct Color{
339 float r;
340
342 float g;
343
345 float b;
346
348 float a;
349};
350
351
352
353
354
355
356//------------------------------------------------------------------------------------------------------------
357
358
359
362struct tMatrix2D {
364 double *data;
365
367 int *size;
368
371
374
375 bool canFreeData;
376};
377
378
379
380
381
382//--------------------- Joints class -----------------------
383
385class ROBODK tJoints {
386
387public:
390 tJoints(int ndofs = 0);
391
395 tJoints(const double *joints, int ndofs = 0);
396
400 tJoints(const float *joints, int ndofs = 0);
401
404 tJoints(const tJoints &jnts);
405
410 tJoints(const tMatrix2D *mat2d, int column=0, int ndofs=-1);
411
414 tJoints(const QString &str);
415
417 operator QString() const { return ToString(); }
418
421 const double *ValuesD() const;
422
425 const float *ValuesF() const;
426
427#ifdef ROBODK_API_FLOATS
430 const float *Values() const;
431#else
434 const double *Values() const;
435#endif
436
437
438
439
440
443 double *Data();
444
447 int Length() const;
448
450 void setLength(int new_length);
451
455 bool Valid() const;
456
460 int GetValues(double *joints);
461
465 void SetValues(const double *joints, int ndofs = -1);
466
470 void SetValues(const float *joints, int ndofs = -1);
471
476 QString ToString(const QString &separator=", ", int precision = 3) const;
477
481 bool FromString(const QString &str);
482
483
484public:
487
489 double _Values[RDK_SIZE_JOINTS_MAX];
490
492 float _ValuesF[RDK_SIZE_JOINTS_MAX];
493};
494
495
505class ROBODK Mat : public QMatrix4x4 {
506
507public:
508
510 Mat();
511
513 Mat(bool valid);
514
516 Mat(const QMatrix4x4 &matrix);
517
520 Mat(const Mat &matrix);
521
542 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);
543
551 Mat(const double values[16]);
552
561 Mat(const float values[16]);
562
563 ~Mat();
564
566 operator QString() const { return ToString(); }
567
569 void setVX(double x, double y, double z);
570
572 void setVY(double x, double y, double z);
573
575 void setVZ(double x, double y, double z);
576
578 void setPos(double x, double y, double z);
579
581 void setVX(double xyz[3]);
582
584 void setVY(double xyz[3]);
585
587 void setVZ(double xyz[3]);
588
590 void setPos(double xyz[3]);
591
593 void VX(tXYZ xyz) const;
594
596 void VY(tXYZ xyz) const;
597
599 void VZ(tXYZ xyz) const;
600
602 void Pos(tXYZ xyz) const;
603
608 void Set(int r, int c, double value);
609
614 double Get(int r, int c) const;
615
617 Mat inv() const;
618
620 bool isHomogeneous() const;
621
623 bool MakeHomogeneous();
624
625
626
627
628 //------ Pose to xyzrpw and xyzrpw to pose------------
629
636 void ToXYZRPW(tXYZWPR xyzwpr) const;
637
643 QString ToString(const QString &separator=", ", int precision = 3, bool xyzwpr_only = false) const;
644
646 bool FromString(const QString &str);
647
655 void FromXYZRPW(tXYZWPR xyzwpr);
656
664 static Mat XYZRPW_2_Mat(double x, double y, double z, double r, double p, double w);
665 static Mat XYZRPW_2_Mat(tXYZWPR xyzwpr);
666
668 const double* ValuesD() const;
669
671 const float* ValuesF() const;
672
673#ifdef ROBODK_API_FLOATS
675 const float* Values() const;
676#else
678 const double* Values() const;
679#endif
680
682 void Values(double values[16]) const;
683
685 void Values(float values[16]) const;
686
688 bool Valid() const;
689
703 static Mat transl(double x, double y, double z);
704
716 static Mat rotx(double rx);
717
729 static Mat roty(double ry);
730
742 static Mat rotz(double rz);
743
744
745private:
747 bool _valid;
748
749// this is a dummy variable to easily obtain a pointer to a 16-double-array for matrix multiplications
750private:
752 double _ddata16[16];
753
754};
755
761class ROBODK RoboDK {
762 friend class RoboDK_API::Item;
763
764public:
765 explicit RoboDK(QAbstractSocket *socket, bool fUseExceptions = false);
766 RoboDK(const QString &robodk_ip="", int com_port=-1, const QString &args="", const QString &path="", bool fUseExceptions = false);
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
1169 bool CollisionLine(tXYZ p1, tXYZ p2);
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
1274 GetPointsResult GetPoints(int featureType = FEATURE_HOVER_OBJECT_MESH);
1275
1280 QString License();
1281
1286 QList<Item> Selection();
1287
1292 void setSelection(QList<Item> list_items);
1293
1297 void PluginLoad(const QString &pluginName, int load=1);
1298
1302 QString PluginCommand(const QString &pluginName, const QString &pluginCommand, const QString &pluginValue="");
1303
1311 Item Popup_ISO9283_CubeProgram(Item *robot=nullptr, tXYZ center=nullptr, double side=-1, bool blocking=true);
1312
1314 bool FileSet(const QString &file_local, const QString &file_remote="", bool load_file=true, Item *attach_to=nullptr);
1315
1317 bool FileGet(const QString &path_file_local, Item *station=nullptr, const QString path_file_remote="");
1318
1319 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);
1320
1321 bool EventsListen();
1322 bool WaitForEvent(int &evt,Item &itm);
1323 bool Event_Receive_3D_POS(double *data, int *valueCount);
1324 bool Event_Receive_Mouse_data(int *data);
1325 bool Event_Receive_Event_Moved(Mat *pose_rel_out);
1326 bool Event_Connected();
1327
1328public:
1329
1330
1332 enum {
1334 ITEM_TYPE_ANY = -1,
1335
1337 ITEM_TYPE_STATION = 1,
1338
1340 ITEM_TYPE_ROBOT = 2,
1341
1343 ITEM_TYPE_FRAME = 3,
1344
1346 ITEM_TYPE_TOOL = 4,
1347
1349 ITEM_TYPE_OBJECT = 5,
1350
1352 ITEM_TYPE_TARGET = 6,
1353
1355 ITEM_TYPE_PROGRAM = 8,
1356
1358 ITEM_TYPE_INSTRUCTION = 9,
1359
1361 ITEM_TYPE_PROGRAM_PYTHON = 10,
1362
1364 ITEM_TYPE_MACHINING = 11,
1365
1367 ITEM_TYPE_BALLBARVALIDATION = 12,
1368
1370 ITEM_TYPE_CALIBPROJECT = 13,
1371
1373 ITEM_TYPE_VALID_ISO9283 = 14
1375
1377 enum {
1379 INS_TYPE_INVALID = -1,
1380
1382 INS_TYPE_MOVE = 0,
1383
1385 INS_TYPE_MOVEC = 1,
1386
1388 INS_TYPE_CHANGESPEED = 2,
1389
1391 INS_TYPE_CHANGEFRAME = 3,
1392
1394 INS_TYPE_CHANGETOOL = 4,
1395
1397 INS_TYPE_CHANGEROBOT = 5,
1398
1400 INS_TYPE_PAUSE = 6,
1401
1403 INS_TYPE_EVENT = 7,
1404
1406 INS_TYPE_CODE = 8,
1407
1409 INS_TYPE_PRINT = 9
1411
1413 enum {
1415 MOVE_TYPE_INVALID = -1,
1416
1418 MOVE_TYPE_JOINT = 1,
1419
1421 MOVE_TYPE_LINEAR = 2,
1422
1424 MOVE_TYPE_CIRCULAR = 3
1426
1428 enum {
1430 RUNMODE_SIMULATE = 1,
1431
1433 RUNMODE_QUICKVALIDATE = 2,
1434
1436 RUNMODE_MAKE_ROBOTPROG = 3,
1437
1439 RUNMODE_MAKE_ROBOTPROG_AND_UPLOAD = 4,
1440
1442 RUNMODE_MAKE_ROBOTPROG_AND_START = 5,
1443
1445 RUNMODE_RUN_ROBOT = 6
1447
1449 enum {
1451 PROGRAM_RUN_ON_SIMULATOR = 1,
1452
1454 PROGRAM_RUN_ON_ROBOT = 2
1456
1458 enum {
1459
1461 CALIBRATE_TCP_BY_POINT = 0,
1462
1464 CALIBRATE_TCP_BY_PLANE = 1
1466
1468 enum {
1470 CALIBRATE_FRAME_3P_P1_ON_X = 0,
1471
1473 CALIBRATE_FRAME_3P_P1_ORIGIN = 1,
1474
1476 CALIBRATE_FRAME_6P = 2,
1477
1479 CALIBRATE_TURNTABLE = 3
1481
1483 enum {
1485 PROJECTION_NONE = 0,
1486
1488 PROJECTION_CLOSEST = 1,
1489
1491 PROJECTION_ALONG_NORMAL = 2,
1492
1494 PROJECTION_ALONG_NORMAL_RECALC = 3,
1495
1497 PROJECTION_CLOSEST_RECALC = 4,
1498
1500 PROJECTION_RECALC = 5
1502
1504 enum {
1505
1507 JOINT_FORMAT = -1,
1508
1510 EULER_RX_RYp_RZpp = 0,
1511
1513 EULER_RZ_RYp_RXpp = 1,
1514
1516 EULER_RZ_RYp_RZpp = 2,
1517
1519 EULER_RZ_RXp_RZpp = 3,
1520
1522 EULER_RX_RY_RZ = 4,
1523
1525 EULER_RZ_RY_RX = 5,
1526
1528 EULER_QUEATERNION = 6
1530
1532 enum {
1533
1535 WINDOWSTATE_HIDDEN = -1,
1536
1538 WINDOWSTATE_SHOW = 0,
1539
1541 WINDOWSTATE_MINIMIZED = 1,
1542
1544 WINDOWSTATE_NORMAL = 2,
1545
1547 WINDOWSTATE_MAXIMIZED = 3,
1548
1550 WINDOWSTATE_FULLSCREEN = 4,
1551
1553 WINDOWSTATE_CINEMA = 5,
1554
1556 WINDOWSTATE_FULLSCREEN_CINEMA = 6
1558
1560 enum {
1562 INSTRUCTION_CALL_PROGRAM = 0,
1563
1565 INSTRUCTION_INSERT_CODE = 1,
1566
1568 INSTRUCTION_START_THREAD = 2,
1569
1571 INSTRUCTION_COMMENT = 3,
1572
1574 INSTRUCTION_SHOW_MESSAGE = 4
1576
1578 enum {
1580 FEATURE_NONE = 0,
1581
1583 FEATURE_SURFACE = 1,
1584
1586 FEATURE_CURVE = 2,
1587
1589 FEATURE_POINT = 3,
1590
1592 FEATURE_OBJECT_MESH = 7,
1593
1595 FEATURE_SURFACE_PREVIEW = 8,
1596
1598 FEATURE_MESH = 9,
1599
1600 // The following do not require providing an object
1601
1603 FEATURE_HOVER_OBJECT_MESH = 10,
1604
1606 FEATURE_HOVER_OBJECT = 11
1608
1610 enum {
1612 SPRAY_OFF = 0,
1613 SPRAY_ON = 1
1614 };
1615
1617 enum {
1619 COLLISION_OFF = 0,
1620
1622 COLLISION_ON = 1
1624
1625 // Event types
1626 enum {
1627 EVENT_SELECTION_TREE_CHANGED = 1,
1628 EVENT_ITEM_MOVED = 2, // obsolete after RoboDK 4.2.0. Use EVENT_ITEM_MOVED_POSE instead
1629 EVENT_REFERENCE_PICKED = 3,
1630 EVENT_REFERENCE_RELEASED = 4,
1631 EVENT_TOOL_MODIFIED = 5,
1632 EVENT_CREATED_ISOCUBE = 6,
1633 EVENT_SELECTION_3D_CHANGED = 7,
1634 EVENT_3DVIEW_MOVED = 8,
1635 EVENT_ROBOT_MOVED = 9,
1636 EVENT_KEY = 10,
1637 EVENT_ITEM_MOVED_POSE = 11
1638 };
1639
1640
1642 enum {
1644 FLAG_ROBODK_TREE_ACTIVE = 1,
1645
1647 FLAG_ROBODK_3DVIEW_ACTIVE = 2,
1648
1650 FLAG_ROBODK_LEFT_CLICK = 4,
1651
1653 FLAG_ROBODK_RIGHT_CLICK = 8,
1654
1656 FLAG_ROBODK_DOUBLE_CLICK = 16,
1657
1659 FLAG_ROBODK_MENU_ACTIVE = 32,
1660
1662 FLAG_ROBODK_MENUFILE_ACTIVE = 64,
1663
1665 FLAG_ROBODK_MENUEDIT_ACTIVE = 128,
1666
1668 FLAG_ROBODK_MENUPROGRAM_ACTIVE = 256,
1669
1671 FLAG_ROBODK_MENUTOOLS_ACTIVE = 512,
1672
1674 FLAG_ROBODK_MENUUTILITIES_ACTIVE = 1024,
1675
1677 FLAG_ROBODK_MENUCONNECT_ACTIVE = 2048,
1678
1680 FLAG_ROBODK_WINDOWKEYS_ACTIVE = 4096,
1681
1683 FLAG_ROBODK_NONE = 0,
1684
1686 FLAG_ROBODK_ALL = 0xFFFF,
1687
1689 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
1691
1693 enum {
1695 FLAG_ITEM_SELECTABLE = 1,
1696
1698 FLAG_ITEM_EDITABLE = 2,
1699
1701 FLAG_ITEM_DRAGALLOWED = 4,
1702
1704 FLAG_ITEM_DROPALLOWED = 8,
1705
1707 FLAG_ITEM_ENABLED = 32,
1708
1710 FLAG_ITEM_AUTOTRISTATE = 64,
1711
1713 FLAG_ITEM_NOCHILDREN = 128,
1714 FLAG_ITEM_USERTRISTATE = 256,
1715
1717 FLAG_ITEM_NONE = 0,
1718
1720 FLAG_ITEM_ALL = 64 + 32 + 8 + 4 + 2 + 1
1722
1723private:
1724 QAbstractSocket *_COM;
1725 bool _USE_EXCPETIONS;
1726 bool _OWN_SOCKET;
1727 QAbstractSocket *_COM_EVT;
1728 QString _IP;
1729 int _PORT;
1730 int _TIMEOUT;
1731 qint64 _PROCESS;
1732
1733 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
1734 QString _ARGUMENTS; // arguments to provide to RoboDK on startup
1735
1736 bool _connected();
1737 bool _connect();
1738 bool _connect_smart(); // will attempt to start RoboDK
1739 void _disconnect();
1740
1741 bool _check_connection();
1742 bool _check_status();
1743
1744 bool _waitline(QAbstractSocket *com = nullptr);
1745 QString _recv_Line(QAbstractSocket *com = nullptr);//QString &string);
1746 bool _send_Line(const QString &string,QAbstractSocket *com = nullptr);
1747 int _recv_Int(QAbstractSocket *com = nullptr);//qint32 &value);
1748 bool _send_Int(const qint32 value,QAbstractSocket *com = nullptr);
1749 Item _recv_Item(QAbstractSocket *com = nullptr);//Item *item);
1750 bool _send_Item(const Item *item);
1751 bool _send_Item(const Item &item);
1752 Mat _recv_Pose(QAbstractSocket *com = nullptr);//Mat &pose);
1753 bool _send_Pose(const Mat &pose);
1754 bool _recv_XYZ(tXYZ pos);
1755 bool _send_XYZ(const tXYZ pos);
1756 bool _recv_Array(double *values, int *psize=nullptr,QAbstractSocket *com = nullptr);
1757 bool _send_Array(const double *values, int nvalues);
1758 bool _recv_Array(tJoints *jnts);
1759 bool _send_Array(const tJoints *jnts);
1760 bool _send_Array(const Mat *mat);
1761 bool _recv_Matrix2D(tMatrix2D **mat);
1762 bool _send_Matrix2D(tMatrix2D *mat);
1763 bool _send_Bytes(const QByteArray &data, QAbstractSocket *com = nullptr);
1764 QByteArray _recv_Bytes(QAbstractSocket *com = nullptr);
1765
1766
1767 void _moveX(const Item *target, const tJoints *joints, const Mat *mat_target, const Item *itemrobot, int movetype, bool blocking);
1768 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);
1769};
1770
1771
1777class ROBODK Item {
1778 friend class RoboDK_API::RoboDK;
1779
1780public:
1781 Item(RoboDK *rdk=nullptr, quint64 ptr=0, qint32 type=-1);
1782 Item(const Item &other);
1783 Item& operator=( const Item& x ) = default;
1784
1785 ~Item();
1786
1787 QString ToString() const;
1788
1789 RoboDK* RDK();
1790
1791 void NewLink();
1792
1794 int Type() const;
1795
1800 void Save(const QString &filename);
1801
1805 void Delete();
1806
1810 bool Valid(bool check_pointer=false) const ;
1811
1816 void setParent(Item parent);
1817
1823 void setParentStatic(Item parent);
1824
1829 Item AttachClosest();
1830
1835 Item DetachClosest(Item parent);
1836
1840 void DetachAll(Item parent);
1841
1846 Item Parent() const;
1847
1852 QList<Item> Childs() const;
1853
1858 bool Visible() const;
1859
1865 void setVisible(bool visible, int visible_frame = -1);
1866
1871 QString Name() const;
1872
1877 void setName(const QString &name);
1878
1884 void setPose(const Mat pose);
1885
1891 Mat Pose() const;
1892
1898 void setGeometryPose(const Mat pose);
1899
1904 Mat GeometryPose();
1905
1906 /*/// <summary>
1910 void setHtool(Mat pose);
1911 */
1912
1913 /*
1919 Mat Htool();
1920 */
1921
1926 Mat PoseTool();
1927
1932 Mat PoseFrame();
1933
1939 void setPoseFrame(const Mat frame_pose);
1940
1946 void setPoseFrame(const Item frame_item);
1947
1953 void setPoseTool(const Mat tool_pose);
1954
1960 void setPoseTool(const Item tool_item);
1961
1966 void setPoseAbs(const Mat pose);
1967
1972 Mat PoseAbs();
1973
1981 void setColor(double colorRGBA[4]);
1982
1983
1984
1985//---------- add more
1986
1991 void Scale(double scale);
1992
1998 void Scale(double scale_xyz[3]);
1999
2000
2009 GetPointsResult GetPoints(int featureType = RoboDK::FEATURE_SURFACE, int featureId = 0);
2010
2017 bool SelectedFeature(int &featureType, int &featureId);
2018
2062 Item setMachiningParameters(QString ncfile = "", Item part_obj = nullptr, QString options = "");
2063
2067 void setAsCartesianTarget();
2068
2072 void setAsJointTarget();
2073
2077 bool isJointTarget() const ;
2078
2083 tJoints Joints() const ;
2084
2089 tJoints JointsHome() const;
2090
2094 void setJointsHome(const tJoints &jnts);
2095
2101 Item ObjectLink(int link_id = 0);
2102
2108 Item getLink(int type_linked = RoboDK::ITEM_TYPE_ROBOT);
2109
2113 void setJoints(const tJoints &jnts);
2114
2118 void JointLimits(tJoints *lower_limits, tJoints *upper_limits);
2119
2125 void setJointLimits(const tJoints &lower_limits, const tJoints &upper_limits);
2126
2132 void setRobot(const Item &robot);
2133
2140 Item AddTool(const Mat &tool_pose, const QString &tool_name = "New TCP");
2141
2147 Mat SolveFK(const tJoints &joints, const Mat *tool = nullptr, const Mat *ref = nullptr);
2148
2154 void JointsConfig(const tJoints &joints, tConfig config);
2155
2164 tJoints SolveIK(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr);
2165
2174 tJoints SolveIK(const Mat pose, tJoints joints_approx, const Mat *tool = nullptr, const Mat *ref = nullptr);
2175
2183 tMatrix2D *SolveIK_All_Mat2D(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr);
2184
2192 QList<tJoints> SolveIK_All(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr);
2193
2199 bool Connect(const QString &robot_ip = "");
2200
2205 bool Disconnect();
2206
2212 void MoveJ(const Item &itemtarget, bool blocking = true);
2213
2218 void MoveJ(const tJoints &joints, bool blocking = true);
2219
2224 void MoveJ(const Mat &target, bool blocking = true);
2225
2231 void MoveL(const Item &itemtarget, bool blocking = true);
2232
2237 void MoveL(const tJoints &joints, bool blocking = true);
2238
2243 void MoveL(const Mat &target, bool blocking = true);
2244
2250 void MoveC(const Item &itemtarget1, const Item &itemtarget2, bool blocking = true);
2251
2257 void MoveC(const tJoints &joints1, const tJoints &joints2, bool blocking = true);
2258
2264 void MoveC(const Mat &target1, const Mat &target2, bool blocking = true);
2265
2273 int MoveJ_Test(const tJoints &j1, const tJoints &j2, double minstep_deg = -1);
2274
2282 int MoveL_Test(const tJoints &joints1, const Mat &pose2, double minstep_mm = -1);
2283
2291 void setSpeed(double speed_linear, double accel_linear = -1, double speed_joints = -1, double accel_joints = -1);
2292
2297 void setRounding(double zonedata);
2298
2303 void ShowSequence(tMatrix2D *sequence);
2304
2309 bool Busy();
2310
2314 void Stop();
2315
2320 void WaitMove(double timeout_sec = 300) const;
2321
2326 void setAccuracyActive(int accurate = 1);
2327
2334 bool MakeProgram(const QString &filename);
2335
2341 void setRunType(int program_run_type);
2342
2352 int RunProgram();
2353
2363 int RunCode(const QString &parameters);
2364
2370 int RunInstruction(const QString &code, int run_type = RoboDK::INSTRUCTION_CALL_PROGRAM);
2371
2376 void Pause(double time_ms = -1);
2377
2383 void setDO(const QString &io_var, const QString &io_value);
2384
2390 void setAO(const QString &io_var, const QString &io_value);
2391
2396 QString getDI(const QString &io_var);
2397
2398
2403 QString getAI(const QString &io_var);
2404
2411 void waitDI(const QString &io_var, const QString &io_value, double timeout_ms = -1);
2412
2422 void customInstruction(const QString &name, const QString &path_run, const QString &path_icon = "", bool blocking = true, const QString &cmd_run_on_robot = "");
2423
2424
2425 //void addMoveJ(const Item &itemtarget);
2426 //void addMoveL(const Item &itemtarget);
2427
2432 void ShowInstructions(bool visible=true);
2433
2438 void ShowTargets(bool visible=true);
2439
2444 int InstructionCount();
2445
2456 void Instruction(int ins_id, QString &name, int &instype, int &movetype, bool &isjointtarget, Mat &target, tJoints &joints);
2457
2468 void setInstruction(int ins_id, const QString &name, int instype, int movetype, bool isjointtarget, const Mat &target, const tJoints &joints);
2469
2475 int InstructionList(tMatrix2D *instructions);
2476
2487 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);
2488
2503 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);
2504
2505
2514 QString setParam(const QString &param, const QString &value);
2515
2521 void setParam(const QString &param, const QByteArray &value);
2522
2527 QByteArray getParam(const QString &param);
2528
2533 bool Finish();
2534
2535
2537 quint64 GetID();
2538
2539
2540private:
2543
2545 quint64 _PTR;
2546
2548 qint32 _TYPE;
2549};
2550
2551
2554{
2555 Item item;
2556 int featureType;
2557 int featureId;
2558 QString featureName;
2559 tMatrix2D* points;
2560};
2561
2562
2563
2565ROBODK Mat transl(double x, double y, double z);
2566
2568ROBODK Mat rotx(double rx);
2569
2571ROBODK Mat roty(double ry);
2572
2574ROBODK Mat rotz(double rz);
2575
2576
2580ROBODK tMatrix2D* Matrix2D_Create();
2581
2584ROBODK void Matrix2D_Delete(tMatrix2D **mat);
2585
2590ROBODK void Matrix2D_Set_Size(tMatrix2D *mat, int rows, int cols);
2591
2595ROBODK int Matrix2D_Size(const tMatrix2D *mat, int dim);
2596
2600ROBODK int Matrix2D_Get_ncols(const tMatrix2D *var);
2601
2605ROBODK int Matrix2D_Get_nrows(const tMatrix2D *var);
2606
2610ROBODK double Matrix2D_Get_ij(const tMatrix2D *var, int i, int j);
2611
2617ROBODK double* Matrix2D_Get_col(const tMatrix2D *var, int col);
2618
2621ROBODK void Debug_Array(const double *array, int arraysize);
2622
2625ROBODK void Debug_Matrix2D(const tMatrix2D *mat);
2626
2627
2631//ROBODK void Debug_Mat(Mat pose, char show_full_pose);
2632
2633
2634
2635
2636//QDataStream &operator<<(QDataStream &data, const QMatrix4x4 &);
2637inline QDebug operator<<(QDebug dbg, const Mat &m){ return dbg.noquote() << m.ToString(); }
2638inline QDebug operator<<(QDebug dbg, const tJoints &jnts){ return dbg.noquote() << jnts.ToString(); }
2639inline QDebug operator<<(QDebug dbg, const Item &itm){ return dbg.noquote() << itm.ToString(); }
2640
2641inline QDebug operator<<(QDebug dbg, const Mat *m){ return dbg.noquote() << (m == nullptr ? "Mat(null)" : m->ToString()); }
2642inline QDebug operator<<(QDebug dbg, const tJoints *jnts){ return dbg.noquote() << (jnts == nullptr ? "tJoints(null)" : jnts->ToString()); }
2643inline QDebug operator<<(QDebug dbg, const Item *itm){ return dbg.noquote() << (itm == nullptr ? "Item(null)" : itm->ToString()); }
2644
2645
2646#ifndef RDK_SKIP_NAMESPACE
2647}
2648
2649#endif
2650
2651
2652
2653
2654#endif // ROBODK_API
The Item class represents an item in RoboDK station. An item can be a robot, a frame,...
qint32 _TYPE
Item type.
RoboDK * _RDK
Pointer to RoboDK link object.
quint64 _PTR
Pointer to the item inside RoboDK.
The Mat class represents a 4x4 pose matrix. The main purpose of this object is to represent a pose in...
Definition robodk_api.h:505
QString ToString(const QString &separator=", ", int precision=3, bool xyzwpr_only=false) const
Retrieve a string representation of the pose.
bool _valid
Flags if a matrix is not valid.
Definition robodk_api.h:747
This class is the iterface to the RoboDK API. With the RoboDK API you can automate certain tasks and ...
Definition robodk_api.h:761
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....
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())
The tJoints class represents a joint position of a robot (robot axes).
Definition robodk_api.h:385
int _nDOFs
number of degrees of freedom
Definition robodk_api.h:486
All RoboDK API functions are wrapped in the RoboDK_API namespace. If you prefer to forget about the R...
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.
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.
double tConfig[RDK_SIZE_MAX_CONFIG]
The robot configuration defines a specific state of the robot without crossing any singularities....
Definition robodk_api.h:311
Mat transl(double x, double y, double z)
Translation matrix class: Mat::transl.
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.
QDebug operator<<(QDebug dbg, const Mat &m)
Displays the content of a Mat through STDOUT. This is only intended for debug purposes.
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.
double tXYZ[3]
tXYZ (mm) represents a position or a vector in mm
Definition robodk_api.h:300
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:297
The Color struct represents an RGBA color (each color component should be in the range [0-1])
Definition robodk_api.h:337
float r
Red color.
Definition robodk_api.h:339
float a
Alpha value (0 = transparent; 1 = opaque)
Definition robodk_api.h:348
float b
Blue color.
Definition robodk_api.h:345
float g
Green color.
Definition robodk_api.h:342
The GetPointsResult method represents the results of executing the GetPoints function.
The tMatrix2D struct represents a variable size 2d Matrix. Use the Matrix2D_... functions to oeprate ...
Definition robodk_api.h:362
double * data
Pointer to the data.
Definition robodk_api.h:364
int * size
Pointer to the size array.
Definition robodk_api.h:367
int allocatedSize
Allocated size.
Definition robodk_api.h:370
int numDimensions
Number of dimensions (usually 2)
Definition robodk_api.h:373