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);
785 Item getItem(QString name,
int itemtype = -1);
793 QStringList getItemListNames(
int filter = -1);
801 QList<Item> getItemList(
int filter = -1);
810 Item ItemUserPick(
const QString &message =
"Pick one item",
int itemtype = -1);
836 void setWindowState(
int windowstate = WINDOWSTATE_NORMAL);
842 void setFlagsRoboDK(
int flags = FLAG_ROBODK_ALL);
849 void setFlagsItem(
Item item,
int flags = FLAG_ITEM_ALL);
856 int getFlagsItem(
Item item);
863 void ShowMessage(
const QString &message,
bool popup =
true);
869 void Copy(
const Item &tocopy);
876 Item Paste(
const Item *paste_to=
nullptr);
884 Item AddFile(
const QString &filename,
const Item *parent=
nullptr);
891 void Save(
const QString &filename,
const Item *itemsave=
nullptr);
901 Item AddShape(
tMatrix2D *trianglePoints,
Item *addTo =
nullptr,
bool shapeOverride =
false,
Color *color =
nullptr);
911 Item AddCurve(
tMatrix2D *curvePoints,
Item *referenceObject =
nullptr,
bool addToRef =
false,
int ProjectionType = PROJECTION_ALONG_NORMAL_RECALC);
921 Item AddPoints(
tMatrix2D *points,
Item *referenceObject =
nullptr,
bool addToRef =
false,
int ProjectionType = PROJECTION_ALONG_NORMAL_RECALC);
930 void ProjectPoints(
tMatrix2D *points,
tMatrix2D **projected,
Item objectProject,
int ProjectionType = PROJECTION_ALONG_NORMAL_RECALC);
944 Item AddTarget(
const QString &name,
Item *itemparent =
nullptr,
Item *itemrobot =
nullptr);
952 Item AddFrame(
const QString &name,
Item *itemparent =
nullptr);
960 Item AddProgram(
const QString &name,
Item *itemrobot =
nullptr);
966 Item AddStation(
const QString &name);
976 Item AddMachiningProject(
const QString &name =
"Curve follow settings",
Item *itemrobot =
nullptr);
982 QList<Item> getOpenStation();
988 void setActiveStation(
Item stn);
994 Item getActiveStation();
1001 int RunProgram(
const QString &function_w_params);
1009 int RunCode(
const QString &code,
bool code_is_fcn_call =
false);
1016 void RunMessage(
const QString &message,
bool message_is_comment =
false);
1022 void Render(
bool always_render =
false);
1036 bool IsInside(
Item object_inside,
Item object_parent);
1043 int setCollisionActive(
int check_state = COLLISION_ON);
1055 bool setCollisionActivePair(
int check_state,
Item item1,
Item item2,
int id1 = 0,
int id2 = 0);
1069 int Collision(
Item item1,
Item item2);
1076 QList<Item> getCollisionItems(QList<int> link_id_list);
1082 void setSimulationSpeed(
double speed);
1088 double SimulationSpeed();
1100 void setRunMode(
int run_mode = 1);
1118 QList<QPair<QString, QString> > getParams();
1131 QString getParam(
const QString ¶m);
1140 void setParam(
const QString ¶m,
const QString &value);
1148 QString Command(
const QString &cmd,
const QString &value=
"");
1159 bool LaserTrackerMeasure(
tXYZ xyz,
tXYZ estimate,
bool search =
false);
1172 void setVisible(QList<Item> itemList, QList<bool> visibleList, QList<int> visibleFrames);
1176 void ShowAsCollided(QList<Item> itemList, QList<bool> collidedList, QList<int> *robot_link_id =
nullptr);
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);
1197 Mat CalibrateReference(
tMatrix2D *poses_joints,
int method = CALIBRATE_FRAME_3P_P1_ON_X,
bool use_joints =
false,
Item *robot =
nullptr);
1208 int ProgramStart(
const QString &progname,
const QString &defaultfolder =
"",
const QString &postprocessor =
"",
Item *robot =
nullptr);
1214 void setViewPose(
const Mat &pose);
1229 Item Cam2D_Add(
const Item &item_object,
const QString &cam_params,
const Item *cam_item=
nullptr);
1238 int Cam2D_Snapshot(
const QString &file_save_img,
const Item &cam_item,
const QString ¶ms=
"");
1246 int Cam2D_SetParams(
const QString &cam_params,
const Item &cam_item);
1267 Item getCursorXYZ(
int x = -1,
int y = -1, tXYZ xyzStation =
nullptr);
1274 GetPointsResult GetPoints(
int featureType = FEATURE_HOVER_OBJECT_MESH);
1286 QList<Item> Selection();
1292 void setSelection(QList<Item> list_items);
1297 void PluginLoad(
const QString &pluginName,
int load=1);
1302 QString PluginCommand(
const QString &pluginName,
const QString &pluginCommand,
const QString &pluginValue=
"");
1311 Item Popup_ISO9283_CubeProgram(
Item *robot=
nullptr, tXYZ center=
nullptr,
double side=-1,
bool blocking=
true);
1314 bool FileSet(
const QString &file_local,
const QString &file_remote=
"",
bool load_file=
true,
Item *attach_to=
nullptr);
1317 bool FileGet(
const QString &path_file_local,
Item *station=
nullptr,
const QString path_file_remote=
"");
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);
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();
1337 ITEM_TYPE_STATION = 1,
1340 ITEM_TYPE_ROBOT = 2,
1343 ITEM_TYPE_FRAME = 3,
1349 ITEM_TYPE_OBJECT = 5,
1352 ITEM_TYPE_TARGET = 6,
1355 ITEM_TYPE_PROGRAM = 8,
1358 ITEM_TYPE_INSTRUCTION = 9,
1361 ITEM_TYPE_PROGRAM_PYTHON = 10,
1364 ITEM_TYPE_MACHINING = 11,
1367 ITEM_TYPE_BALLBARVALIDATION = 12,
1370 ITEM_TYPE_CALIBPROJECT = 13,
1373 ITEM_TYPE_VALID_ISO9283 = 14
1379 INS_TYPE_INVALID = -1,
1388 INS_TYPE_CHANGESPEED = 2,
1391 INS_TYPE_CHANGEFRAME = 3,
1394 INS_TYPE_CHANGETOOL = 4,
1397 INS_TYPE_CHANGEROBOT = 5,
1415 MOVE_TYPE_INVALID = -1,
1418 MOVE_TYPE_JOINT = 1,
1421 MOVE_TYPE_LINEAR = 2,
1424 MOVE_TYPE_CIRCULAR = 3
1430 RUNMODE_SIMULATE = 1,
1433 RUNMODE_QUICKVALIDATE = 2,
1436 RUNMODE_MAKE_ROBOTPROG = 3,
1439 RUNMODE_MAKE_ROBOTPROG_AND_UPLOAD = 4,
1442 RUNMODE_MAKE_ROBOTPROG_AND_START = 5,
1445 RUNMODE_RUN_ROBOT = 6
1451 PROGRAM_RUN_ON_SIMULATOR = 1,
1454 PROGRAM_RUN_ON_ROBOT = 2
1461 CALIBRATE_TCP_BY_POINT = 0,
1464 CALIBRATE_TCP_BY_PLANE = 1
1470 CALIBRATE_FRAME_3P_P1_ON_X = 0,
1473 CALIBRATE_FRAME_3P_P1_ORIGIN = 1,
1476 CALIBRATE_FRAME_6P = 2,
1479 CALIBRATE_TURNTABLE = 3
1485 PROJECTION_NONE = 0,
1488 PROJECTION_CLOSEST = 1,
1491 PROJECTION_ALONG_NORMAL = 2,
1494 PROJECTION_ALONG_NORMAL_RECALC = 3,
1497 PROJECTION_CLOSEST_RECALC = 4,
1500 PROJECTION_RECALC = 5
1510 EULER_RX_RYp_RZpp = 0,
1513 EULER_RZ_RYp_RXpp = 1,
1516 EULER_RZ_RYp_RZpp = 2,
1519 EULER_RZ_RXp_RZpp = 3,
1528 EULER_QUEATERNION = 6
1535 WINDOWSTATE_HIDDEN = -1,
1538 WINDOWSTATE_SHOW = 0,
1541 WINDOWSTATE_MINIMIZED = 1,
1544 WINDOWSTATE_NORMAL = 2,
1547 WINDOWSTATE_MAXIMIZED = 3,
1550 WINDOWSTATE_FULLSCREEN = 4,
1553 WINDOWSTATE_CINEMA = 5,
1556 WINDOWSTATE_FULLSCREEN_CINEMA = 6
1562 INSTRUCTION_CALL_PROGRAM = 0,
1565 INSTRUCTION_INSERT_CODE = 1,
1568 INSTRUCTION_START_THREAD = 2,
1571 INSTRUCTION_COMMENT = 3,
1574 INSTRUCTION_SHOW_MESSAGE = 4
1583 FEATURE_SURFACE = 1,
1592 FEATURE_OBJECT_MESH = 7,
1595 FEATURE_SURFACE_PREVIEW = 8,
1603 FEATURE_HOVER_OBJECT_MESH = 10,
1606 FEATURE_HOVER_OBJECT = 11
1627 EVENT_SELECTION_TREE_CHANGED = 1,
1628 EVENT_ITEM_MOVED = 2,
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,
1637 EVENT_ITEM_MOVED_POSE = 11
1644 FLAG_ROBODK_TREE_ACTIVE = 1,
1647 FLAG_ROBODK_3DVIEW_ACTIVE = 2,
1650 FLAG_ROBODK_LEFT_CLICK = 4,
1653 FLAG_ROBODK_RIGHT_CLICK = 8,
1656 FLAG_ROBODK_DOUBLE_CLICK = 16,
1659 FLAG_ROBODK_MENU_ACTIVE = 32,
1662 FLAG_ROBODK_MENUFILE_ACTIVE = 64,
1665 FLAG_ROBODK_MENUEDIT_ACTIVE = 128,
1668 FLAG_ROBODK_MENUPROGRAM_ACTIVE = 256,
1671 FLAG_ROBODK_MENUTOOLS_ACTIVE = 512,
1674 FLAG_ROBODK_MENUUTILITIES_ACTIVE = 1024,
1677 FLAG_ROBODK_MENUCONNECT_ACTIVE = 2048,
1680 FLAG_ROBODK_WINDOWKEYS_ACTIVE = 4096,
1683 FLAG_ROBODK_NONE = 0,
1686 FLAG_ROBODK_ALL = 0xFFFF,
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
1695 FLAG_ITEM_SELECTABLE = 1,
1698 FLAG_ITEM_EDITABLE = 2,
1701 FLAG_ITEM_DRAGALLOWED = 4,
1704 FLAG_ITEM_DROPALLOWED = 8,
1707 FLAG_ITEM_ENABLED = 32,
1710 FLAG_ITEM_AUTOTRISTATE = 64,
1713 FLAG_ITEM_NOCHILDREN = 128,
1714 FLAG_ITEM_USERTRISTATE = 256,
1720 FLAG_ITEM_ALL = 64 + 32 + 8 + 4 + 2 + 1
1724 QAbstractSocket *_COM;
1725 bool _USE_EXCPETIONS;
1727 QAbstractSocket *_COM_EVT;
1733 QString _ROBODK_BIN;
1738 bool _connect_smart();
1741 bool _check_connection();
1742 bool _check_status();
1744 bool _waitline(QAbstractSocket *com =
nullptr);
1745 QString _recv_Line(QAbstractSocket *com =
nullptr);
1746 bool _send_Line(
const QString &
string,QAbstractSocket *com =
nullptr);
1747 int _recv_Int(QAbstractSocket *com =
nullptr);
1748 bool _send_Int(
const qint32 value,QAbstractSocket *com =
nullptr);
1749 Item _recv_Item(QAbstractSocket *com =
nullptr);
1750 bool _send_Item(
const Item *item);
1751 bool _send_Item(
const Item &item);
1752 Mat _recv_Pose(QAbstractSocket *com =
nullptr);
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);
1763 bool _send_Bytes(
const QByteArray &data, QAbstractSocket *com =
nullptr);
1764 QByteArray _recv_Bytes(QAbstractSocket *com =
nullptr);
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);