250#ifdef RDK_WITH_EXPORTS
252 #define ROBODK __declspec(dllexport)
254 #define ROBODK __declspec(dllimport)
261#include <QtCore/QString>
262#include <QtGui/QMatrix4x4>
269#ifndef RDK_SKIP_NAMESPACE
281#define RDK_SIZE_JOINTS_MAX 12
285#define RDK_SIZE_MAX_CONFIG 4
314#define DOT(v,q) ((v)[0]*(q)[0] + (v)[1]*(q)[1] + (v)[2]*(q)[2])
317#define NORM(v) (sqrt((v)[0]*(v)[0] + (v)[1]*(v)[1] + (v)[2]*(v)[2]))
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];
326#define NORMALIZE(inout){\
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;}
394 tJoints(
const double *joints,
int ndofs = 0);
399 tJoints(
const float *joints,
int ndofs = 0);
416 operator QString()
const {
return ToString(); }
420 const double *ValuesD()
const;
424 const float *ValuesF()
const;
426#ifdef ROBODK_API_FLOATS
429 const float *Values()
const;
433 const double *Values()
const;
449 void setLength(
int new_length);
459 int GetValues(
double *joints);
464 void SetValues(
const double *joints,
int ndofs = -1);
469 void SetValues(
const float *joints,
int ndofs = -1);
475 QString ToString(
const QString &separator=
", ",
int precision = 3)
const;
480 bool FromString(
const QString &str);
488 double _Values[RDK_SIZE_JOINTS_MAX];
491 float _ValuesF[RDK_SIZE_JOINTS_MAX];
506class ROBODK
Mat :
public QMatrix4x4 {
517 Mat(
const QMatrix4x4 &matrix);
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);
552 Mat(
const double values[16]);
562 Mat(
const float values[16]);
567 operator QString()
const {
return ToString(); }
570 void setVX(
double x,
double y,
double z);
573 void setVY(
double x,
double y,
double z);
576 void setVZ(
double x,
double y,
double z);
579 void setPos(
double x,
double y,
double z);
582 void setVX(
double xyz[3]);
585 void setVY(
double xyz[3]);
588 void setVZ(
double xyz[3]);
591 void setPos(
double xyz[3]);
594 void VX(
tXYZ xyz)
const;
597 void VY(
tXYZ xyz)
const;
600 void VZ(
tXYZ xyz)
const;
603 void Pos(
tXYZ xyz)
const;
609 void Set(
int r,
int c,
double value);
615 double Get(
int r,
int c)
const;
621 bool isHomogeneous()
const;
624 bool MakeHomogeneous();
637 void ToXYZRPW(
tXYZWPR xyzwpr)
const;
644 QString ToString(
const QString &separator=
", ",
int precision = 3,
bool xyzwpr_only =
false)
const;
647 bool FromString(
const QString &str);
656 void FromXYZRPW(
tXYZWPR xyzwpr);
665 static Mat XYZRPW_2_Mat(
double x,
double y,
double z,
double r,
double p,
double w);
669 const double* ValuesD()
const;
672 const float* ValuesF()
const;
674#ifdef ROBODK_API_FLOATS
676 const float* Values()
const;
679 const double* Values()
const;
683 void Values(
double values[16])
const;
686 void Values(
float values[16])
const;
704 static Mat transl(
double x,
double y,
double z);
766 RoboDK(
const QString &robodk_ip=
"",
int com_port=-1,
const QString &args=
"",
const QString &path=
"");
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);
1279 QList<Item> Selection();
1285 void setSelection(QList<Item> list_items);
1290 void PluginLoad(
const QString &pluginName,
int load=1);
1295 QString PluginCommand(
const QString &pluginName,
const QString &pluginCommand,
const QString &pluginValue=
"");
1304 Item Popup_ISO9283_CubeProgram(
Item *robot=
nullptr,
tXYZ center=
nullptr,
double side=-1,
bool blocking=
true);
1307 bool FileSet(
const QString &file_local,
const QString &file_remote=
"",
bool load_file=
true,
Item *attach_to=
nullptr);
1310 bool FileGet(
const QString &path_file_local,
Item *station=
nullptr,
const QString path_file_remote=
"");
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);
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();
1330 ITEM_TYPE_STATION = 1,
1333 ITEM_TYPE_ROBOT = 2,
1336 ITEM_TYPE_FRAME = 3,
1342 ITEM_TYPE_OBJECT = 5,
1345 ITEM_TYPE_TARGET = 6,
1348 ITEM_TYPE_PROGRAM = 8,
1351 ITEM_TYPE_INSTRUCTION = 9,
1354 ITEM_TYPE_PROGRAM_PYTHON = 10,
1357 ITEM_TYPE_MACHINING = 11,
1360 ITEM_TYPE_BALLBARVALIDATION = 12,
1363 ITEM_TYPE_CALIBPROJECT = 13,
1366 ITEM_TYPE_VALID_ISO9283 = 14
1372 INS_TYPE_INVALID = -1,
1381 INS_TYPE_CHANGESPEED = 2,
1384 INS_TYPE_CHANGEFRAME = 3,
1387 INS_TYPE_CHANGETOOL = 4,
1390 INS_TYPE_CHANGEROBOT = 5,
1408 MOVE_TYPE_INVALID = -1,
1411 MOVE_TYPE_JOINT = 1,
1414 MOVE_TYPE_LINEAR = 2,
1417 MOVE_TYPE_CIRCULAR = 3
1423 RUNMODE_SIMULATE = 1,
1426 RUNMODE_QUICKVALIDATE = 2,
1429 RUNMODE_MAKE_ROBOTPROG = 3,
1432 RUNMODE_MAKE_ROBOTPROG_AND_UPLOAD = 4,
1435 RUNMODE_MAKE_ROBOTPROG_AND_START = 5,
1438 RUNMODE_RUN_ROBOT = 6
1444 PROGRAM_RUN_ON_SIMULATOR = 1,
1447 PROGRAM_RUN_ON_ROBOT = 2
1454 CALIBRATE_TCP_BY_POINT = 0,
1457 CALIBRATE_TCP_BY_PLANE = 1
1463 CALIBRATE_FRAME_3P_P1_ON_X = 0,
1466 CALIBRATE_FRAME_3P_P1_ORIGIN = 1,
1469 CALIBRATE_FRAME_6P = 2,
1472 CALIBRATE_TURNTABLE = 3
1478 PROJECTION_NONE = 0,
1481 PROJECTION_CLOSEST = 1,
1484 PROJECTION_ALONG_NORMAL = 2,
1487 PROJECTION_ALONG_NORMAL_RECALC = 3,
1490 PROJECTION_CLOSEST_RECALC = 4,
1493 PROJECTION_RECALC = 5
1503 EULER_RX_RYp_RZpp = 0,
1506 EULER_RZ_RYp_RXpp = 1,
1509 EULER_RZ_RYp_RZpp = 2,
1512 EULER_RZ_RXp_RZpp = 3,
1521 EULER_QUEATERNION = 6
1528 WINDOWSTATE_HIDDEN = -1,
1531 WINDOWSTATE_SHOW = 0,
1534 WINDOWSTATE_MINIMIZED = 1,
1537 WINDOWSTATE_NORMAL = 2,
1540 WINDOWSTATE_MAXIMIZED = 3,
1543 WINDOWSTATE_FULLSCREEN = 4,
1546 WINDOWSTATE_CINEMA = 5,
1549 WINDOWSTATE_FULLSCREEN_CINEMA = 6
1555 INSTRUCTION_CALL_PROGRAM = 0,
1558 INSTRUCTION_INSERT_CODE = 1,
1561 INSTRUCTION_START_THREAD = 2,
1564 INSTRUCTION_COMMENT = 3,
1567 INSTRUCTION_SHOW_MESSAGE = 4
1576 FEATURE_SURFACE = 1,
1603 EVENT_SELECTION_TREE_CHANGED = 1,
1604 EVENT_ITEM_MOVED = 2,
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,
1613 EVENT_ITEM_MOVED_POSE = 11
1620 FLAG_ROBODK_TREE_ACTIVE = 1,
1623 FLAG_ROBODK_3DVIEW_ACTIVE = 2,
1626 FLAG_ROBODK_LEFT_CLICK = 4,
1629 FLAG_ROBODK_RIGHT_CLICK = 8,
1632 FLAG_ROBODK_DOUBLE_CLICK = 16,
1635 FLAG_ROBODK_MENU_ACTIVE = 32,
1638 FLAG_ROBODK_MENUFILE_ACTIVE = 64,
1641 FLAG_ROBODK_MENUEDIT_ACTIVE = 128,
1644 FLAG_ROBODK_MENUPROGRAM_ACTIVE = 256,
1647 FLAG_ROBODK_MENUTOOLS_ACTIVE = 512,
1650 FLAG_ROBODK_MENUUTILITIES_ACTIVE = 1024,
1653 FLAG_ROBODK_MENUCONNECT_ACTIVE = 2048,
1656 FLAG_ROBODK_WINDOWKEYS_ACTIVE = 4096,
1659 FLAG_ROBODK_NONE = 0,
1662 FLAG_ROBODK_ALL = 0xFFFF,
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
1671 FLAG_ITEM_SELECTABLE = 1,
1674 FLAG_ITEM_EDITABLE = 2,
1677 FLAG_ITEM_DRAGALLOWED = 4,
1680 FLAG_ITEM_DROPALLOWED = 8,
1683 FLAG_ITEM_ENABLED = 32,
1686 FLAG_ITEM_AUTOTRISTATE = 64,
1689 FLAG_ITEM_NOCHILDREN = 128,
1690 FLAG_ITEM_USERTRISTATE = 256,
1696 FLAG_ITEM_ALL = 64 + 32 + 8 + 4 + 2 + 1
1701 QTcpSocket *_COM_EVT;
1707 QString _ROBODK_BIN;
1712 bool _connect_smart();
1715 bool _check_connection();
1716 bool _check_status();
1718 bool _waitline(QTcpSocket *com =
nullptr);
1719 QString _recv_Line(QTcpSocket *com =
nullptr);
1720 bool _send_Line(
const QString &
string,QTcpSocket *com =
nullptr);
1721 int _recv_Int(QTcpSocket *com =
nullptr);
1722 bool _send_Int(
const qint32 value,QTcpSocket *com =
nullptr);
1723 Item _recv_Item(QTcpSocket *com =
nullptr);
1724 bool _send_Item(
const Item *item);
1725 bool _send_Item(
const Item &item);
1726 Mat _recv_Pose(QTcpSocket *com =
nullptr);
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);
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);
1753 Item(
RoboDK *rdk=
nullptr, quint64 ptr=0, qint32 type=-1);
1755 Item& operator=(
const Item& x ) =
default;
1759 QString ToString()
const;
1772 void Save(
const QString &filename);
1782 bool Valid(
bool check_pointer=
false)
const ;
1788 void setParent(
Item parent);
1795 void setParentStatic(
Item parent);
1801 Item AttachClosest();
1812 void DetachAll(
Item parent);
1818 Item Parent()
const;
1824 QList<Item> Childs()
const;
1830 bool Visible()
const;
1837 void setVisible(
bool visible,
int visible_frame = -1);
1843 QString Name()
const;
1849 void setName(
const QString &name);
1856 void setPose(
const Mat pose);
1870 void setGeometryPose(
const Mat pose);
1911 void setPoseFrame(
const Mat frame_pose);
1918 void setPoseFrame(
const Item frame_item);
1925 void setPoseTool(
const Mat tool_pose);
1932 void setPoseTool(
const Item tool_item);
1938 void setPoseAbs(
const Mat pose);
1953 void setColor(
double colorRGBA[4]);
1963 void Scale(
double scale);
1970 void Scale(
double scale_xyz[3]);
2015 Item setMachiningParameters(QString ncfile =
"",
Item part_obj =
nullptr, QString options =
"");
2020 void setAsCartesianTarget();
2025 void setAsJointTarget();
2030 bool isJointTarget()
const ;
2047 void setJointsHome(
const tJoints &jnts);
2054 Item ObjectLink(
int link_id = 0);
2066 void setJoints(
const tJoints &jnts);
2078 void setJointLimits(
const tJoints &lower_limits,
const tJoints &upper_limits);
2085 void setRobot(
const Item &robot);
2093 Item AddTool(
const Mat &tool_pose,
const QString &tool_name =
"New TCP");
2100 Mat SolveFK(
const tJoints &joints,
const Mat *tool =
nullptr,
const Mat *ref =
nullptr);
2117 tJoints SolveIK(
const Mat &pose,
const Mat *tool=
nullptr,
const Mat *ref=
nullptr);
2136 tMatrix2D *SolveIK_All_Mat2D(
const Mat &pose,
const Mat *tool=
nullptr,
const Mat *ref=
nullptr);
2145 QList<tJoints> SolveIK_All(
const Mat &pose,
const Mat *tool=
nullptr,
const Mat *ref=
nullptr);
2152 bool Connect(
const QString &robot_ip =
"");
2165 void MoveJ(
const Item &itemtarget,
bool blocking =
true);
2171 void MoveJ(
const tJoints &joints,
bool blocking =
true);
2177 void MoveJ(
const Mat &target,
bool blocking =
true);
2184 void MoveL(
const Item &itemtarget,
bool blocking =
true);
2190 void MoveL(
const tJoints &joints,
bool blocking =
true);
2196 void MoveL(
const Mat &target,
bool blocking =
true);
2203 void MoveC(
const Item &itemtarget1,
const Item &itemtarget2,
bool blocking =
true);
2210 void MoveC(
const tJoints &joints1,
const tJoints &joints2,
bool blocking =
true);
2217 void MoveC(
const Mat &target1,
const Mat &target2,
bool blocking =
true);
2226 int MoveJ_Test(
const tJoints &j1,
const tJoints &j2,
double minstep_deg = -1);
2235 int MoveL_Test(
const tJoints &joints1,
const Mat &pose2,
double minstep_mm = -1);
2244 void setSpeed(
double speed_linear,
double accel_linear = -1,
double speed_joints = -1,
double accel_joints = -1);
2250 void setRounding(
double zonedata);
2273 void WaitMove(
double timeout_sec = 300)
const;
2279 void setAccuracyActive(
int accurate = 1);
2287 bool MakeProgram(
const QString &filename);
2294 void setRunType(
int program_run_type);
2316 int RunCode(
const QString ¶meters);
2329 void Pause(
double time_ms = -1);
2336 void setDO(
const QString &io_var,
const QString &io_value);
2343 void setAO(
const QString &io_var,
const QString &io_value);
2349 QString getDI(
const QString &io_var);
2356 QString getAI(
const QString &io_var);
2364 void waitDI(
const QString &io_var,
const QString &io_value,
double timeout_ms = -1);
2375 void customInstruction(
const QString &name,
const QString &path_run,
const QString &path_icon =
"",
bool blocking =
true,
const QString &cmd_run_on_robot =
"");
2385 void ShowInstructions(
bool visible=
true);
2391 void ShowTargets(
bool visible=
true);
2397 int InstructionCount();
2409 void Instruction(
int ins_id, QString &name,
int &instype,
int &movetype,
bool &isjointtarget,
Mat &target,
tJoints &joints);
2421 void setInstruction(
int ins_id,
const QString &name,
int instype,
int movetype,
bool isjointtarget,
const Mat &target,
const tJoints &joints);
2428 int InstructionList(
tMatrix2D *instructions);
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);
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);
2467 QString
setParam(
const QString ¶m,
const QString &value);
2494ROBODK
Mat transl(
double x,
double y,
double z);
2550ROBODK
void Debug_Array(
const double *array,
int arraysize);
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(); }
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()); }
2575#ifndef RDK_SKIP_NAMESPACE
The Item class represents an item in RoboDK station. An item can be a robot, a frame,...
bool Connect(const QString &robot_ip="")
Connect to a real robot using the corresponding robot driver.
int RunCode(const QString ¶meters)
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.
quint64 _PTR
Pointer to the item inside RoboDK.
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
QString setParam(const QString ¶m, 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...
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.
This class is the iterface to the RoboDK API. With the RoboDK API you can automate certain tasks and ...
@ COLLISION_OFF
Do not use collision checking.
@ ITEM_TYPE_ROBOT
Item of type robot (.robot file).
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.
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 ¶m, 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).
int _nDOFs
number of degrees of freedom
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....
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.
QDebug operator<<(QDebug dbg, const Mat &m)
Displays the content of a Mat through STDOUT. This is only intended for debug purposes.
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.
double tXYZ[3]
tXYZ (mm) represents a position or a vector in mm
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)
The Color struct represents an RGBA color (each color component should be in the range [0-1])
float a
Alpha value (0 = transparent; 1 = opaque)
The tMatrix2D struct represents a variable size 2d Matrix. Use the Matrix2D_... functions to oeprate ...
double * data
Pointer to the data.
int * size
Pointer to the size array.
int allocatedSize
Allocated size.
int numDimensions
Number of dimensions (usually 2)