RoboDK Plug-In Interface
irobodk.h
1#ifndef IROBODK_H
2#define IROBODK_H
3
4
5#include "robodktypes.h"
6#include <QString>
7
8
14class IRoboDK {
15
16public:
17
18 virtual ~IRoboDK(){}
19
20public:
21
23 enum {
26
29
32
35
38
41
44
47
50
53
56 };
57
59 enum {
62
65
68
71
74 };
75
77 enum {
80
83
86
89
92
95 };
96
98 enum {
101
104 };
105
107 enum {
108
111
114 };
115
117 enum {
120
123
126
129
132 };
133
135 enum {
138
141
144
147
150
153 };
154
156 enum {
157
160
163
166
169
172
175
178
181 };
182
184 enum {
185
188
191
194
197
200
203
206
209
212 };
213
215 enum {
218
221
224
227
230 };
231
233 enum {
236
239
242
244 FEATURE_POINT = 3
245 };
246
248 enum {
251 SPRAY_ON = 1
252 };
253
255 enum {
258
260 COLLISION_ON = 1
261 };
262
264 enum {
267
270
273
276
279
282
285
288
291
294
297
300
303
306
309
312
315
318
321 };
322
324 enum {
327
330
333
336
339
342
345 FLAG_ITEM_USERTRISTATE = 256,
346
349
351 FLAG_ITEM_ALL = 64 + 32 + 8 + 4 + 2 + 1
352 };
353
355 enum {
358
361
364
366 RenderComplete = 0xff
367 };
368
370 enum {
373
376
379
381 DrawSpheres = 4
382 };
383
384
385public:
386
393 virtual Item getItem(const QString &name, int itemtype = -1)=0;
394
401 virtual QStringList getItemListNames(int filter = -1)=0;
402
409 virtual QList<Item> getItemList(int filter = -1)=0;
410
415 virtual bool Valid(const Item item_check)=0;
416
424 virtual Item ItemUserPick(const QString &message = "Pick one item", int itemtype = -1)=0;
425
434 virtual Item ItemUserPick(const QString &message, const QList<Item> &list_choices, int id_selected=-1)=0;
435
439 virtual void ShowRoboDK()=0;
440
444 virtual void HideRoboDK()=0;
445
449 virtual void CloseRoboDK()=0;
450
454 virtual QString Version()=0;
455
460 virtual void setWindowState(int windowstate = WINDOWSTATE_NORMAL)=0;
461
466 virtual void setFlagsRoboDK(int flags = FLAG_ROBODK_ALL)=0;
467
473 virtual void setFlagsItem(int flags = FLAG_ITEM_ALL, Item item=nullptr)=0;
474
480 virtual int getFlagsItem(Item item)=0;
481
482
488 virtual void ShowMessage(const QString &message, bool popup = true)=0;
489
496 virtual Item AddFile(const QString &filename, const Item parent=nullptr)=0;
497
503 virtual void Save(const QString &filename, const Item itemsave=nullptr)=0;
504
513 virtual Item AddShape(const tMatrix2D *trianglePoints, Item addTo = nullptr, bool shapeOverride = false, tColor *color = nullptr)=0;
514
515
524 virtual Item AddCurve(const tMatrix2D *curvePoints, Item referenceObject = nullptr,bool addToRef = false,int ProjectionType = PROJECTION_ALONG_NORMAL_RECALC)=0;
525
526
535 virtual Item AddPoints(const tMatrix2D *points, Item referenceObject = nullptr, bool addToRef = false, int ProjectionType = PROJECTION_ALONG_NORMAL_RECALC)=0;
536
544 virtual bool ProjectPoints(tMatrix2D *points, Item objectProject, int ProjectionType = PROJECTION_ALONG_NORMAL_RECALC)=0;
545
549 virtual void CloseStation()=0;
550
558 virtual Item AddTarget(const QString &name, Item itemparent = nullptr, Item itemrobot = nullptr)=0;
559
566 virtual Item AddFrame(const QString &name, Item itemparent = nullptr)=0;
567
574 virtual Item AddProgram(const QString &name, Item itemrobot = nullptr)=0;
575
580 virtual Item AddStation(QString name)=0;
581
590 virtual Item AddMachiningProject(QString name = "Curve follow settings", Item itemrobot = nullptr)=0;
591
596 virtual QList<Item> getOpenStations()=0;
597
602 virtual void setActiveStation(Item stn)=0;
603
609
615 virtual int RunProgram(const QString &function_w_params)=0;
616
623 virtual int RunCode(const QString &code, bool code_is_fcn_call = false)=0;
624
630 virtual void RunMessage(const QString &message, bool message_is_comment = false)=0;
631
636 virtual void Render(int flags=RenderComplete)=0;
637
644 virtual bool IsInside(Item object_inside, Item object_parent)=0;
645
651 virtual int setCollisionActive(int check_state = COLLISION_ON)=0;
652
663 virtual bool setCollisionActivePair(int check_state, Item item1, Item item2, int id1 = 0, int id2 = 0)=0;
664
669 virtual int Collisions()=0;
670
677 virtual int Collision(Item item1, Item item2)=0;
678
684 virtual QList<Item> getCollisionItems(QList<int> *link_id_list=nullptr)=0;
685
690 virtual void setSimulationSpeed(double speed)=0;
691
696 virtual double SimulationSpeed()=0;
697
708 virtual void setRunMode(int run_mode = 1)=0;
709
718 virtual int RunMode()=0;
719
726 virtual QList<QPair<QString, QString> > getParams()=0;
727
739 virtual QString getParam(const QString &param)=0;
740
741
749 virtual void setParam(const QString &param, const QString &value)=0;
750
757 virtual QString Command(const QString &cmd, const QString &value="")=0;
758
759
760 // --- add calibrate reference, calibrate tool, measure tracker, etc...
761
762
770 virtual bool LaserTrackerMeasure(tXYZ xyz, const tXYZ estimate, bool search = false)=0;
771
781 virtual bool MeasurePose(Mat *pose, double data[10], int target=-1, int time_avg_ms=0, const tXYZ tool_tip=nullptr)=0;
782
791 virtual bool CollisionLine(const tXYZ p1, const tXYZ p2)=0;
792
802 virtual void CalibrateTool(const 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)=0;
803
812 virtual Mat CalibrateReference(const tMatrix2D *poses_joints, int method = CALIBRATE_FRAME_3P_P1_ON_X, bool use_joints = false, Item robot = nullptr)=0;
813
823 virtual bool ProgramStart(const QString &progname, const QString &defaultfolder = "", const QString &postprocessor = "", Item robot = nullptr)=0;
824
825
830 virtual void setViewPose(const Mat &pose)=0;
831
836 virtual Mat ViewPose()=0;
837
846 virtual bool SetRobotParams(Item robot,tMatrix2D dhm, Mat poseBase, Mat poseTool)=0;
847
857 virtual Item getCursorXYZ(int x = -1, int y = -1, tXYZ xyzStation = nullptr)=0;
858
863 virtual QString License()=0;
864
869 virtual QList<Item> Selection()=0;
870
878 virtual Item Popup_ISO9283_CubeProgram(Item robot=nullptr, tXYZ center=nullptr, double side=-1)=0;
879
880
887 virtual QByteArray getData(const QString &param)=0;
888
889
897 virtual void setData(const QString &param, const QByteArray &value)=0;
898
899
902 virtual int CollisionActive()=0;
903
914 virtual bool DrawGeometry(int drawtype, float *vtx_pointer, int vtx_size, float color[4], float geo_size=2.0, float *vtx_normals=nullptr)=0;
915
925 virtual bool DrawTexture(const QImage *image, const float *vtx_pointer, const float *texture_coords, int num_triangles, float *vtx_normals=nullptr)=0;
926
927
928 //-----------------------------------------------------
929 // added after 2020-08-21 with version RoboDK 5.1.0
930
934 virtual void setSelection(const QList<Item> &listitems)=0;
935
943 virtual void setInteractiveMode(int mode_type, int default_ref_flags, const QList<Item> *custom_object=nullptr, int custom_ref_flags=0)=0;
944
950 virtual void PluginLoad(const QString &plugin_name="", int load=1)=0;
951
958 virtual QString PluginCommand(const QString &plugin_name="", const QString &plugin_command="", const QString &value="")=0;
959
966 virtual QByteArray getParamBytes(const QString &param)=0;
967
968
975 virtual void setParamBytes(const QString &param, const QByteArray &value)=0;
976
989 virtual int StereoCamera_Measure(Mat pose1, Mat pose2, int &npoints1, int &npoints2, double *data=nullptr, float time_avg=0, const tXYZ tip_xyz=nullptr)=0;
990
1007 virtual Item BuildMechanism(int type, const QList<Item> &list_obj, const double *parameters, const tJoints &joints_build, const tJoints &joints_home, const tJoints &joints_senses, const tJoints &joints_lim_low, const tJoints &joints_lim_high, const Mat base, const Mat tool, const QString &name, Item robot=nullptr)=0;
1008
1009
1010 //-----------------------------------------------------
1011 // added after 2021-09-17 with version RoboDK 5.3.0
1012
1013
1018 virtual Item Cam2D_Add(const Item attach_to, const QString &params="")=0;
1019
1024 virtual QImage Cam2D_Snapshot(const QString &file, const Item camera=nullptr, const QString &params="")=0;
1025
1026
1027
1031 virtual Item MergeItems(const QList<Item> &listitems)=0;
1032
1033 /*
1034
1035 SprayAdd
1036 */
1037
1038};
1039
1040
1041//Q_DECLARE_INTERFACE(IRoboDK, "RoboDK.IRoboDK")
1042
1043#endif // IROBODK_H
The Item class represents an item in RoboDK station. An item can be a robot, a frame,...
Definition: iitem.h:14
This class is the iterface to the RoboDK API. With the RoboDK API you can automate certain tasks and ...
Definition: irobodk.h:14
virtual void setParam(const QString &param, const QString &value)=0
Sets a global parameter from the RoboDK station. If the parameters exists, it will be modified....
@ PROJECTION_NONE
No curve projection.
Definition: irobodk.h:137
@ PROJECTION_RECALC
The normals are recalculated according to the surface normal of the closest projection....
Definition: irobodk.h:152
@ PROJECTION_ALONG_NORMAL
The projection will be done along the normal.
Definition: irobodk.h:143
@ PROJECTION_ALONG_NORMAL_RECALC
The projection will be done along the normal. Furthermore, the normal will be recalculated according ...
Definition: irobodk.h:146
@ PROJECTION_CLOSEST
The projection will the closest point on the surface.
Definition: irobodk.h:140
@ PROJECTION_CLOSEST_RECALC
The projection will be the closest point on the surface and the normals will be recalculated.
Definition: irobodk.h:149
virtual void setViewPose(const Mat &pose)=0
Set the pose of the wold reference frame with respect to the user view (camera/screen).
@ COLLISION_ON
Use collision checking.
Definition: irobodk.h:260
@ COLLISION_OFF
Do not use collision checking.
Definition: irobodk.h:257
virtual Item AddCurve(const tMatrix2D *curvePoints, Item referenceObject=nullptr, bool addToRef=false, int ProjectionType=PROJECTION_ALONG_NORMAL_RECALC)=0
Adds a curve provided point coordinates. The provided points must be a list of vertices....
virtual void setFlagsItem(int flags=FLAG_ITEM_ALL, Item item=nullptr)=0
Update item flags. Item flags allow defining how much access the user has to item-specific features....
virtual int getFlagsItem(Item item)=0
Retrieve current item flags. Item flags allow defining how much access the user has to item-specific ...
virtual Item AddPoints(const tMatrix2D *points, Item referenceObject=nullptr, bool addToRef=false, int ProjectionType=PROJECTION_ALONG_NORMAL_RECALC)=0
Adds a list of points to an object. The provided points must be a list of vertices....
virtual QString Command(const QString &cmd, const QString &value="")=0
Send a special command. These commands are meant to have a specific effect in RoboDK,...
@ FLAG_ROBODK_RIGHT_CLICK
Allow right clicks on the 3D navigation screen.
Definition: irobodk.h:275
@ FLAG_ROBODK_WINDOWKEYS_ACTIVE
Allow using keyboard shortcuts.
Definition: irobodk.h:302
@ FLAG_ROBODK_DOUBLE_CLICK
Allow double clicks on the 3D navigation screen.
Definition: irobodk.h:278
@ FLAG_ROBODK_NONE
Disallow everything.
Definition: irobodk.h:314
@ FLAG_ROBODK_MENU_ACTIVE_ALL
Allow using the full menu.
Definition: irobodk.h:320
@ FLAG_ROBODK_TREE_VISIBLE
Make the tree visible.
Definition: irobodk.h:305
@ FLAG_ROBODK_MENUPROGRAM_ACTIVE
Enable the program menu (FLAG_ROBODK_MENU_ACTIVE must be allowed).
Definition: irobodk.h:290
@ FLAG_ROBODK_3DVIEW_ACTIVE
Allow using the 3D navigation.
Definition: irobodk.h:269
@ FLAG_ROBODK_MENU_ACTIVE
Enable/display the menu bar.
Definition: irobodk.h:281
@ FLAG_ROBODK_MENUUTILITIES_ACTIVE
Enable the utilities menu (FLAG_ROBODK_MENU_ACTIVE must be allowed).
Definition: irobodk.h:296
@ FLAG_ROBODK_MENUEDIT_ACTIVE
Enable the edit menu (FLAG_ROBODK_MENU_ACTIVE must be allowed).
Definition: irobodk.h:287
@ FLAG_ROBODK_LEFT_CLICK
Allow left clicks on the 3D navigation screen.
Definition: irobodk.h:272
@ FLAG_ROBODK_TREE_ACTIVE
Allow using the RoboDK station tree.
Definition: irobodk.h:266
@ FLAG_ROBODK_REFERENCES_VISIBLE
Make the reference frames visible.
Definition: irobodk.h:308
@ FLAG_ROBODK_STATUSBAR_VISIBLE
Make the statusbar visible.
Definition: irobodk.h:311
@ FLAG_ROBODK_MENUFILE_ACTIVE
Enable the file menu (FLAG_ROBODK_MENU_ACTIVE must be allowed).
Definition: irobodk.h:284
@ FLAG_ROBODK_MENUTOOLS_ACTIVE
Enable the tools menu (FLAG_ROBODK_MENU_ACTIVE must be allowed).
Definition: irobodk.h:293
@ FLAG_ROBODK_MENUCONNECT_ACTIVE
Enable the connect menu (FLAG_ROBODK_MENU_ACTIVE must be allowed).
Definition: irobodk.h:299
@ FLAG_ROBODK_ALL
Allow everything (default).
Definition: irobodk.h:317
virtual void setWindowState(int windowstate=WINDOWSTATE_NORMAL)=0
Set the state of the RoboDK window
virtual QString License()=0
Returns the license as a readable string (same name shown in the RoboDK's title bar,...
virtual bool DrawTexture(const QImage *image, const float *vtx_pointer, const float *texture_coords, int num_triangles, float *vtx_normals=nullptr)=0
Draw a texture in the RoboDK's 3D view. This function must be called only inside a PluginEvent of typ...
virtual bool DrawGeometry(int drawtype, float *vtx_pointer, int vtx_size, float color[4], float geo_size=2.0, float *vtx_normals=nullptr)=0
Draw geometry in the RoboDK's 3D view. This function must be called only inside a PluginEvent of type...
virtual Item getCursorXYZ(int x=-1, int y=-1, tXYZ xyzStation=nullptr)=0
Returns the position of the cursor as XYZ coordinates (by default), or the 3D position of a given set...
virtual Item AddProgram(const QString &name, Item itemrobot=nullptr)=0
Adds a new Frame that can be referenced by a robot.
virtual QList< Item > getCollisionItems(QList< int > *link_id_list=nullptr)=0
Return the list of items that are in a collision state. This function can be used after calling Colli...
virtual void setFlagsRoboDK(int flags=FLAG_ROBODK_ALL)=0
Update the RoboDK flags. RoboDK flags allow defining how much access the user has to certain RoboDK f...
virtual Item AddFrame(const QString &name, Item itemparent=nullptr)=0
Adds a new Frame that can be referenced by a robot.
virtual int RunProgram(const QString &function_w_params)=0
Adds a function call in the program output. RoboDK will handle the syntax when the code is generated ...
virtual Mat ViewPose()=0
Get the pose of the wold reference frame with respect to the user view (camera/screen).
@ INSTRUCTION_COMMENT
Comment output.
Definition: irobodk.h:226
@ INSTRUCTION_START_THREAD
Instruction to start a parallel thread. Program execution will continue and also trigger a thread.
Definition: irobodk.h:223
@ INSTRUCTION_CALL_PROGRAM
Instruction to call a program.
Definition: irobodk.h:217
@ INSTRUCTION_INSERT_CODE
Instructio to insert raw code (this will not provoke a program call).
Definition: irobodk.h:220
@ INSTRUCTION_SHOW_MESSAGE
Instruction to pop up a message on the robot teach pendant.
Definition: irobodk.h:229
virtual Item AddMachiningProject(QString name="Curve follow settings", Item itemrobot=nullptr)=0
Add a new robot machining project. Machining projects can also be used for 3D printing,...
virtual Item Cam2D_Add(const Item attach_to, const QString &params="")=0
Open a simulated 2D camera view. Returns a handle pointer that can be used in case more than one simu...
virtual Item ItemUserPick(const QString &message="Pick one item", int itemtype=-1)=0
Shows a RoboDK popup to select one object from the open RoboDK station. An item type can be specified...
virtual bool setCollisionActivePair(int check_state, Item item1, Item item2, int id1=0, int id2=0)=0
Set collision checking ON or OFF (COLLISION_ON/COLLISION_OFF) for a specific pair of objects....
virtual void CalibrateTool(const 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)=0
Calibrate a tool (TCP) given a number of points or calibration joints. Important: If the robot is cal...
virtual void ShowMessage(const QString &message, bool popup=true)=0
Show a message in RoboDK (it can be blocking or non blocking in the status bar)
virtual Item MergeItems(const QList< Item > &listitems)=0
Merge multiple object items as one. Source objects are not deleted and a new object is created.
virtual QList< Item > getOpenStations()=0
Returns the list of open stations in RoboDK.
virtual Item Popup_ISO9283_CubeProgram(Item robot=nullptr, tXYZ center=nullptr, double side=-1)=0
Show the popup menu to create the ISO9283 path for position accuracy, repeatability and path accuracy...
virtual bool CollisionLine(const tXYZ p1, const tXYZ p2)=0
Checks the collision between a line and any objects in the station. The line is composed by 2 points....
@ CALIBRATE_TCP_BY_POINT
Calibrate the TCP by poses touching the same point.
Definition: irobodk.h:110
@ CALIBRATE_TCP_BY_PLANE
Calibrate the TCP by poses touching the same plane.
Definition: irobodk.h:113
virtual Item getActiveStation()=0
Returns the active station item (station currently visible).
virtual QImage Cam2D_Snapshot(const QString &file, const Item camera=nullptr, const QString &params="")=0
Take a snapshot from a simulated camera view and save it to a file. Returns 1 if success,...
virtual Item AddFile(const QString &filename, const Item parent=nullptr)=0
Loads a file and attaches it to parent. It can be any file supported by RoboDK.
virtual void setSelection(const QList< Item > &listitems)=0
Set the selection in the tree
virtual int CollisionActive()=0
Returns the status of collision checking (COLLISION_ON=1 if the user want to have collision checking ...
virtual bool ProjectPoints(tMatrix2D *points, Item objectProject, int ProjectionType=PROJECTION_ALONG_NORMAL_RECALC)=0
Projects a list of points given its coordinates. The provided points must be a list of [XYZ] coordina...
virtual Mat CalibrateReference(const tMatrix2D *poses_joints, int method=CALIBRATE_FRAME_3P_P1_ON_X, bool use_joints=false, Item robot=nullptr)=0
Calibrate a Reference Frame given a list of points or joint values. Important: If the robot is calibr...
@ CALIBRATE_TURNTABLE
Calibrate turntable.
Definition: irobodk.h:128
@ CALIBRATE_FRAME_6P
Calibrate by 6 points.
Definition: irobodk.h:125
@ CALIBRATE_FRAME_3P_P1_ORIGIN
Calibrate by 3 points: [Origin, X+, XY+] (p1 is origin).
Definition: irobodk.h:122
@ CALIBRATE_FRAME_3P_P1_ON_X
Calibrate by 3 points: [X, X+, Y+] (p1 on X axis).
Definition: irobodk.h:119
@ CALIBRATE_TURNTABLE_2X
Calibrate a 2 axis turntable.
Definition: irobodk.h:131
virtual QList< Item > Selection()=0
Returns the list of items selected (it can be one or more items).
virtual void ShowRoboDK()=0
Shows or raises the RoboDK window.
@ DrawTriangles
Draw surfaces.
Definition: irobodk.h:372
@ DrawLines
Draw lines.
Definition: irobodk.h:375
@ DrawSpheres
Draw spheres.
Definition: irobodk.h:381
@ DrawPoints
Draw points.
Definition: irobodk.h:378
virtual QStringList getItemListNames(int filter=-1)=0
Returns a list of items (list of names or Items) of all available items in the currently open station...
virtual QByteArray getParamBytes(const QString &param)=0
Gets a user parameter from the open RoboDK station (Bytes type). Special QByteArray parameters can be...
virtual bool SetRobotParams(Item robot, tMatrix2D dhm, Mat poseBase, Mat poseTool)=0
Set the nominal robot parameters.
virtual Item AddShape(const tMatrix2D *trianglePoints, Item addTo=nullptr, bool shapeOverride=false, tColor *color=nullptr)=0
Adds a shape provided triangle coordinates. Triangles must be provided as a list of vertices....
virtual void setRunMode(int run_mode=1)=0
Sets the behavior of the RoboDK API. By default, RoboDK shows the path simulation for movement instru...
virtual int StereoCamera_Measure(Mat pose1, Mat pose2, int &npoints1, int &npoints2, double *data=nullptr, float time_avg=0, const tXYZ tip_xyz=nullptr)=0
Takes a measurement with a 6D measurement device. It returns two poses, the base reference frame and ...
@ MOVE_TYPE_INVALID
Invalid robot movement.
Definition: irobodk.h:61
@ MOVE_TYPE_LINEAR
Linear movement (MoveL).
Definition: irobodk.h:67
@ MOVE_TYPE_LINEARSEARCH
Linear search function.
Definition: irobodk.h:73
@ MOVE_TYPE_JOINT
Joint axes movement (MoveJ).
Definition: irobodk.h:64
@ MOVE_TYPE_CIRCULAR
Circular movement (MoveC).
Definition: irobodk.h:70
virtual void setActiveStation(Item stn)=0
Set the active station (project currently visible).
virtual bool IsInside(Item object_inside, Item object_parent)=0
Check if an object is fully inside another one.
virtual QList< QPair< QString, QString > > getParams()=0
Gets all the user parameters from the open RoboDK station. The parameters can also be modified by rig...
virtual QString PluginCommand(const QString &plugin_name="", const QString &plugin_command="", const QString &value="")=0
Send a specific command to a RoboDK plugin. The command and value (optional) must be handled by your ...
virtual QList< Item > getItemList(int filter=-1)=0
Returns a list of items (list of names or pointers) of all available items in the currently open stat...
virtual bool MeasurePose(Mat *pose, double data[10], int target=-1, int time_avg_ms=0, const tXYZ tool_tip=nullptr)=0
Takes a pose measurement (requires a supported measurement system).
virtual Item AddTarget(const QString &name, Item itemparent=nullptr, Item itemrobot=nullptr)=0
Adds a new target that can be reached with a robot.
virtual QString getParam(const QString &param)=0
Gets a global or a user parameter from the open RoboDK station. The parameters can also be modified b...
virtual bool ProgramStart(const QString &progname, const QString &defaultfolder="", const QString &postprocessor="", Item robot=nullptr)=0
Defines the name of the program when the program is generated. It is also possible to specify the nam...
@ RenderComplete
Provokes an update and then screen display (full update and render).
Definition: irobodk.h:366
@ RenderNone
Do not render the screen.
Definition: irobodk.h:357
@ RenderUpdateOnly
Update all positions of modified items (robots, references and objects) and their child items.
Definition: irobodk.h:363
@ RenderScreen
Redisplay the screen.
Definition: irobodk.h:360
@ WINDOWSTATE_CINEMA
Display RoboDK in cinema mode (hide the toolbar and the menu).
Definition: irobodk.h:205
@ WINDOWSTATE_MAXIMIZED
Maximize the RoboDK Window.
Definition: irobodk.h:199
@ WINDOWSTATE_NORMAL
Display the RoboDK window in a normal state (not maximized)
Definition: irobodk.h:196
@ WINDOWSTATE_FULLSCREEN
Make the RoboDK window fullscreen.
Definition: irobodk.h:202
@ WINDOWSTATE_MINIMIZED
Minimize the RoboDK window.
Definition: irobodk.h:193
@ WINDOWSTATE_FULLSCREEN_CINEMA
Display RoboDK in cinema mode and fullscreen.
Definition: irobodk.h:208
@ WINDOWSTATE_HIDDEN
Hide the RoboDK window. RoboDK will keep running as a process.
Definition: irobodk.h:187
@ WINDOWSTATE_SHOW
Display the RoboDK window.
Definition: irobodk.h:190
@ WINDOWSTATE_VIDEO
Display RoboDK in video mode.
Definition: irobodk.h:211
virtual Item BuildMechanism(int type, const QList< Item > &list_obj, const double *parameters, const tJoints &joints_build, const tJoints &joints_home, const tJoints &joints_senses, const tJoints &joints_lim_low, const tJoints &joints_lim_high, const Mat base, const Mat tool, const QString &name, Item robot=nullptr)=0
Takes a measurement with a 6D measurement device. It returns two poses, the base reference frame and ...
@ FLAG_ITEM_NONE
Disallow everything.
Definition: irobodk.h:348
@ FLAG_ITEM_NOCHILDREN
Do not allow adding nested items.
Definition: irobodk.h:344
@ FLAG_ITEM_SELECTABLE
Allow selecting RoboDK items.
Definition: irobodk.h:326
@ FLAG_ITEM_DROPALLOWED
Allow dropping to an item.
Definition: irobodk.h:335
@ FLAG_ITEM_AUTOTRISTATE
Allow having nested items, expand and collapse the item.
Definition: irobodk.h:341
@ FLAG_ITEM_ALL
Allow everything (default).
Definition: irobodk.h:351
@ FLAG_ITEM_DRAGALLOWED
Allow draggin an item.
Definition: irobodk.h:332
@ FLAG_ITEM_EDITABLE
Allow modifying RoboDK items.
Definition: irobodk.h:329
@ FLAG_ITEM_ENABLED
Enable the item.
Definition: irobodk.h:338
@ FEATURE_SURFACE
Surface selection.
Definition: irobodk.h:238
@ FEATURE_NONE
No selection.
Definition: irobodk.h:235
@ FEATURE_CURVE
Curve selection.
Definition: irobodk.h:241
@ FEATURE_POINT
Point selection.
Definition: irobodk.h:244
@ RUNMODE_MAKE_ROBOTPROG_AND_START
Makes the robot program and starts it on the robot (independently from the PC).
Definition: irobodk.h:91
@ RUNMODE_QUICKVALIDATE
Performs a quick check to validate the robot movements.
Definition: irobodk.h:82
@ RUNMODE_RUN_ROBOT
Moves the real robot from the PC (PC is the client, the robot behaves like a server).
Definition: irobodk.h:94
@ RUNMODE_MAKE_ROBOTPROG
Makes the robot program.
Definition: irobodk.h:85
@ RUNMODE_MAKE_ROBOTPROG_AND_UPLOAD
Makes the robot program and updates it to the robot.
Definition: irobodk.h:88
@ RUNMODE_SIMULATE
Performs the simulation moving the robot (default)
Definition: irobodk.h:79
virtual void setSimulationSpeed(double speed)=0
Sets the current simulation speed. Set the speed to 1 for a real-time simulation. The slowest speed a...
@ EULER_RZ_RYp_RZpp
Kawasaki, Adept, Staubli.
Definition: irobodk.h:168
@ EULER_RZ_RY_RX
CRS.
Definition: irobodk.h:177
@ JOINT_FORMAT
joints.
Definition: irobodk.h:159
@ EULER_RZ_RYp_RXpp
ABB RobotStudio.
Definition: irobodk.h:165
@ EULER_RX_RYp_RZpp
Staubli, Mecademic.
Definition: irobodk.h:162
@ EULER_RX_RY_RZ
Fanuc, Kuka, Motoman, Nachi.
Definition: irobodk.h:174
@ EULER_RZ_RXp_RZpp
CATIA, SolidWorks.
Definition: irobodk.h:171
@ EULER_QUEATERNION
ABB Rapid.
Definition: irobodk.h:180
virtual Item AddStation(QString name)=0
Add a new empty station. It returns the station item added.
virtual Item ItemUserPick(const QString &message, const QList< Item > &list_choices, int id_selected=-1)=0
Shows a RoboDK popup to select one object from the open RoboDK station. You can provide a few items t...
virtual int RunMode()=0
Returns the behavior of the RoboDK API. By default, RoboDK shows the path simulation for movement ins...
@ SPRAY_OFF
Activate the spray simulation.
Definition: irobodk.h:250
virtual void Save(const QString &filename, const Item itemsave=nullptr)=0
Save an item to a file. If no item is provided, the open station is saved.
virtual int Collision(Item item1, Item item2)=0
Returns 1 if item1 and item2 collided. Otherwise returns 0.
virtual bool Valid(const Item item_check)=0
Check if an item is valid (not null and available in the open station)
virtual double SimulationSpeed()=0
Gets the current simulation speed. Set the speed to 1 for a real-time simulation.
virtual void CloseRoboDK()=0
Closes RoboDK window and finishes RoboDK execution
virtual void RunMessage(const QString &message, bool message_is_comment=false)=0
Shows a message or a comment in the output robot program.
virtual Item getItem(const QString &name, int itemtype=-1)=0
Returns an item by its name. If there is no exact match it will return the last closest match.
virtual QByteArray getData(const QString &param)=0
Gets a plugin defined parameter from the open RoboDK station. Saved parameters can be viewed or delet...
virtual int setCollisionActive(int check_state=COLLISION_ON)=0
Turn collision checking ON or OFF (COLLISION_OFF/COLLISION_OFF) according to the collision map....
@ PROGRAM_RUN_ON_SIMULATOR
Set the robot program to run on the simulator.
Definition: irobodk.h:100
@ PROGRAM_RUN_ON_ROBOT
Set the robot program to run on the robot.
Definition: irobodk.h:103
@ INS_TYPE_MOVEC
Circular movement instruction.
Definition: irobodk.h:31
@ INS_TYPE_CHANGEROBOT
Set the robot instruction (obsolete).
Definition: irobodk.h:43
@ INS_TYPE_EVENT
Simulation event instruction.
Definition: irobodk.h:49
@ INS_TYPE_CHANGESPEED
Set speed instruction.
Definition: irobodk.h:34
@ INS_TYPE_CODE
Program call or raw code output.
Definition: irobodk.h:52
@ INS_TYPE_INVALID
Invalid instruction.
Definition: irobodk.h:25
@ INS_TYPE_MOVE
Linear or joint movement instruction.
Definition: irobodk.h:28
@ INS_TYPE_PRINT
Display message on the teach pendant.
Definition: irobodk.h:55
@ INS_TYPE_PAUSE
Pause instruction.
Definition: irobodk.h:46
@ INS_TYPE_CHANGEFRAME
Set reference frame instruction.
Definition: irobodk.h:37
@ INS_TYPE_CHANGETOOL
Set the tool (TCP) instruction.
Definition: irobodk.h:40
virtual void setData(const QString &param, const QByteArray &value)=0
Sets a data parameter saved with the RoboDK station. If the parameters exists, it will be updated....
virtual int Collisions()=0
Returns the number of pairs of objects that are currently in a collision state. If collision checking...
virtual void PluginLoad(const QString &plugin_name="", int load=1)=0
Load or unload the specified plugin (path to DLL, dylib or SO file). If the plugin is already loaded ...
virtual void setParamBytes(const QString &param, const QByteArray &value)=0
Gets a user parameter from the open RoboDK station (Bytes type). Special QByteArray parameters can be...
virtual void CloseStation()=0
Close the current station without asking to save.
virtual QString Version()=0
Return the vesion of RoboDK as a 4 digit string: Major.Minor.Revision.Build
virtual void Render(int flags=RenderComplete)=0
Update the scene.
virtual int RunCode(const QString &code, bool code_is_fcn_call=false)=0
Adds code to run in the program output. If the program exists it will also run the program in simulat...
virtual void setInteractiveMode(int mode_type, int default_ref_flags, const QList< Item > *custom_object=nullptr, int custom_ref_flags=0)=0
Set the interactive mode to define the behavior when navigating and selecting items in RoboDK's 3D vi...
virtual bool LaserTrackerMeasure(tXYZ xyz, const tXYZ estimate, bool search=false)=0
Takes a laser tracker measurement with respect to its own reference frame. If an estimate point is pr...
virtual void HideRoboDK()=0
Hides the RoboDK window. RoboDK will continue running in the background.
The Mat class represents a 4x4 pose matrix. The main purpose of this object is to represent a pose in...
Definition: robodktypes.h:361
The tJoints class represents a joint position of a robot (robot axes).
Definition: robodktypes.h:239
The Color struct represents an RGBA color (each color component should be in the range [0-1])
Definition: robodktypes.h:120
The tMatrix2D struct represents a variable size 2d Matrix. Use the Matrix2D_... functions to oeprate ...
Definition: robodktypes.h:145