RoboDK Plug-In Interface
iitem.h
1 #ifndef IITEM_H
2 #define IITEM_H
3
4 #include
5 #include "robodktypes.h"
6 #include "irobodk.h"
7
8
14 class IItem{
15 public:
16
18 enum{
21
24
27
30
33
36
39
42
45
48
51
54
57
60
63
66
69
72
75};
76
77 public:
78
79 virtual ~IItem(){}
80
82 virtual int Type()=0;
83
88 virtual bool Save(constQString &filename)=0;
89
93 virtual void 删除()=0;
94
99 virtual void setParent(Itemparent)=0;
100
106 virtual void setParentStatic(Itemparent)=0;
107
112 virtual Item Parent()=0;
113
119 virtualQListChilds()=0;
120
125 virtual bool Visible()=0;
126
132 virtual void setVisible(boolvisible,intvisible_frame = -1)=0;
133
138 virtualQStringName()=0;
139
144 virtual void setName(constQString &name)=0;
145
146 // Do not use this function. Just check if the item is nullptr (for example, using ItemValid())
147 //virtual bool Valid()=0;
148
155 virtualQStringCommand(constQString &cmd,constQString &value="")=0;
156
162 virtual bool setPose(const Matpose)=0;
163
169 virtual Mat Pose()=0;
170
176 virtual void setGeometryPose(Matpose,boolapply_transf=足总lse)=0;
177
182 virtual Mat GeometryPose()=0;
183
188 virtual Mat PoseTool()=0;
189
194 virtual Mat PoseFrame()=0;
195
201 virtual void setPoseFrame(const Matframe_pose)=0;
202
208 virtual void setPoseFrame(const Itemframe_item)=0;
209
215 virtual void setPoseTool(const Mattool_pose)=0;
216
222 virtual void setPoseTool(const Itemtool_item)=0;
223
224
229 virtual void setPoseAbs(const Matpose)=0;
230
235 virtual Mat PoseAbs()=0;
236
242 virtual void setColor(const tColor&clr)=0;
243
244 //---------- add more
245
246
251 virtual void Scale(doublescale)=0;
252
258 virtual void Scale(doublescale_xyz[3])=0;
259
263 virtual void setAsCartesianTarget()=0;
264
268 virtual void setAsJointTarget()=0;
269
273 virtual bool isJointTarget()=0;
274
279 virtual tJoints Joints()=0;
280
285 virtual tJoints JointsHome()=0;
286
290 virtual void setJointsHome(const tJoints&jnts)=0;
291
297 virtual Item ObjectLink(intlink_id = 0)=0;
298
304 virtual Item getLink(inttype_linked =ITEM_TYPE_ROBOT)=0;
305
309 virtual void setJoints(const tJoints&jnts)=0;
310
314 virtual int JointLimits(tJoints*lower_limits,tJoints*upper_limits)=0;
315
319 virtual int setJointLimits(const tJoints&lower_limits,const tJoints&upper_limits)=0;
320
326 virtual void setRobot(const Item&robot)=0;
327
334 virtual Item AddTool(const Mat&tool_pose,constQString &tool_name ="New TCP")=0;
335
341 virtual Mat SolveFK(const tJoints&joints,const Mat*tool_pose=nullptr,const Mat*reference_pose=nullptr)=0;
342
348 virtual void JointsConfig(const tJoints&joints, tConfig config)=0;
349
358 virtual tJoints SolveIK(const Mat&pose,const tJoints*joints_close=nullptr,const Mat*tool_pose=nullptr,const Mat*reference_pose=nullptr)=0;
359
367 virtualQListSolveIK_All(const Mat&pose,const Mat*tool_pose=nullptr,const Mat*reference_pose=nullptr)=0;
368
374 virtual bool Connect(constQString &robot_ip ="")=0;
375
380 virtual bool Disconnect()=0;
381
382
387 virtual bool MoveJ(const Item&itemtarget)=0;
388
393 virtual bool MoveJ(const tJoints&joints)=0;
394
399 virtual bool MoveJ(const Mat&target)=0;
400
405 virtual bool MoveL(const Item&itemtarget)=0;
406
411 virtual bool MoveL(const tJoints&joints)=0;
412
417 virtual bool MoveL(const Mat&target)=0;
418
424 virtual bool MoveC(const Item&itemtarget1,const Item&itemtarget2)=0;
425
431 virtual bool MoveC(const tJoints&joints1,const tJoints&joints2)=0;
432
438 virtual bool MoveC(const Mat&target1,const Mat&target2)=0;
439
447 virtual int MoveJ_Test(const tJoints&j1,const tJoints&j2,doubleminstep_deg = -1)=0;
448
456 virtual int MoveL_Test(const tJoints&joints1,const Mat&pose2,doubleminstep_mm = -1)=0;
457
465 virtual void setSpeed(doublespeed_linear,doubleaccel_linear = -1,doublespeed_joints = -1,doubleaccel_joints = -1)=0;
466
471 virtual void setRounding(doublezonedata)=0;
472
477 virtual void ShowSequence(tMatrix2D*sequence)=0;
478
483 virtual bool Busy()=0;
484
488 virtual void Stop()=0;
489
496 virtual bool MakeProgram(constQString &filename)=0;
497
498
504 virtual void setRunType(intprogram_run_type)=0;
505
515 virtual bool RunProgram(constQString ¶ms ="")=0;
516
522 virtual int RunInstruction(constQString &code,intrun_type =RoboDK::INSTRUCTION_CALL_PROGRAM)=0;
523
528 virtual void Pause(doubletime_ms = 1) = 0;
529
530
536 virtual void setDO(constQString &io_var,constQString &io_value)=0;
537
544 virtual void waitDI(constQString &io_var,constQString &io_value,doubletimeout_ms = -1)=0;
545
555 virtual void customInstruction(constQString &name,constQString &path_run,constQString &path_icon ="",boolblocking =true,constQString &cmd_run_on_robot ="")=0;
556
561 virtual void ShowInstructions(boolvisible=true)=0;
562
567 virtual void ShowTargets(boolvisible=true)=0;
568
573 virtual int InstructionCount()=0;
574
585 virtual void InstructionAt(intins_id, QString &name,int&instype,int&movetype,bool&isjointtarget,Mat&target,tJoints&joints)=0;
586
597 virtual void setInstruction(intins_id,constQString &name,intinstype,intmovetype,boolisjointtarget,const Mat&target,const tJoints&joints)=0;
598
604 virtual int InstructionList(tMatrix2D*instructions)=0;
605
616 virtual double Update(doubleout_nins_time_dist[4],intcollision_check =RoboDK::COLLISION_OFF,doublemm_step = -1,doubledeg_step = -1)=0;
617
661 virtual Item setMachiningParameters(constQString &ncfile="",Itempart_obj=nullptr,constQString &options="")=0;
662
667 virtual int ConnectedState(QString *msg=nullptr)=0;
668
671 virtual bool Selected()=0;
672
676 virtual bool Collided(int*id=nullptr)=0;
677
681 virtual bool JointsValid(const tJoints&jnts)=0;
682
688 virtual int RunType()=0;
689
694 virtual bool Scale(const doublescalexyz[3],const Mat*tr_pre_scale,const Mat*tr_post_scale=nullptr)=0;
695
700 virtual Item InstructionTargetAt(intins_id)=0;
701
702 // added with RoboDK 4.2.1 on 2020-01-31
703
708 virtual Item AttachClosest()=0;
709
714 virtual Item DetachClosest(Itemparent=nullptr)=0;
715
719 virtual void DetachAll(Itemparent=nullptr)=0;
720
734 virtual int InstructionListJoints(QString &error_msg,tMatrix2D*matrix,doublestep_mm=1,doublestep_deg=1,intcheck_collisions=IRoboDK::COLLISION_OFF,intflags=0,doubletime_step=0.1)=0;
735
739 virtual void Copy()=0;
740
744 virtual Item Paste()=0;
745
746 // added with RoboDK 4.2.2 on 2020-02-07
747
751 virtualQStringsetParam(constQString ¶m,constQString &value="", QList *itemlist=nullptr,double*values=nullptr,tMatrix2D*matrix=nullptr)=0;
752
756 virtual bool setParam(constQString &name,constQByteArray &value)=0;
757
761 virtual bool getParam(constQString &name, QByteArray &value)=0;
762
763
764 //-----------------------------------------------------
765 // added after 2020-08-21 with version RoboDK 5.1.0
766
770 virtual void setAccuracyActive(boolaccurate=true)=0;
771
778
782 virtual int InstructionSelect(intins_id=-1)=0;
783
787 virtual int InstructionDelete(intins_id=0)=0;
788
794 virtual void setAO(constQString &io_var,constQString &io_value)=0;
795
800 virtualQStringgetDI(constQString &io_var)=0;
801
810 virtual void ConnectionParams(QString &robotIP,int&port, QString &remote_path, QString &FTP_user, QString &FTP_pass)=0;
811
820 virtual void setConnectionParams(constQString &robotIP,const int&port=2000,constQString &remote_path="/",constQString &FTP_user="",constQString &FTP_pass="")=0;
821
825 virtual void Color(tColor&clr_out)=0;
826
830 virtual void SelectedFeature(bool&is_selected,intfeature_type,int&feature_id)=0;
831
832
833 //-----------------------------------------------------
834 // added after 2021-09-17 with version RoboDK 5.3.0
835
840 virtualQListJointPoses(const tJoints&jnts)=0;
841
842
843
844};
845
846
847 //inline QDebug operator<<(QDebug dbg, const IItem *itm){ return dbg.noquote() << (itm == nullptr ? "Item(null)" : itm); }
848
849 // Allows us to use Item as a QVariant. Example:
850 // QVariant::fromValue(item)
851Q_DECLARE_METATYPE (Item);
852
853 //Q_DECLARE_INTERFACE(IAppRoboDK, "RoboDK.IItem")
854
855
856 #endif // IITEM_H
The Item class represents an item in RoboDK station. An item can be a robot, a frame,...
Definition: iitem.h:14
virtual bool MakeProgram(const QString &filename)=0
Saves a program to a file.
virtual Item DetachClosest(Item parent=nullptr)=0
Detach the closest object attached to the tool (see also setParentStatic).
virtual void setDO(const QString &io_var, const QString &io_value)=0
Sets a variable (output) to a given value. This can also be used to set any variables to a desired va...
virtual bool Visible()=0
Returns 1 if the item is visible, otherwise, returns 0
virtual int RunInstruction(const QString &code, int run_type=RoboDK::INSTRUCTION_CALL_PROGRAM)=0
Adds a program call, code, message or comment inside a program.
@ ITEM_TYPE_STATION
Item of type station (RDK file)
Definition: iitem.h:23
@ ITEM_TYPE_CALIBPROJECT
Robot calibration project.
Definition: iitem.h:56
@ ITEM_TYPE_ROBOT
Item of type robot (.robot file)
Definition: iitem.h:26
@ ITEM_TYPE_VALID_ISO9283
Robot path accuracy validation project.
Definition: iitem.h:59
@ ITEM_TYPE_BALLBARVALIDATION
Ballbar validation project.
Definition: iitem.h:53
@ ITEM_TYPE_TARGET
Target item.
Definition: iitem.h:38
@ ITEM_TYPE_ROBOT_AXES
Mechanisms and axes of up to 3 degrees of freedom.
Definition: iitem.h:74
@ ITEM_TYPE_TOOL
Item of type tool (.tool)
Definition: iitem.h:32
@ ITEM_TYPE_FOLDER
Folders.
Definition: iitem.h:62
@ ITEM_TYPE_PROGRAM
Program item.
Definition: iitem.h:41
@ ITEM_TYPE_FRAME
Item of type reference frame.
Definition: iitem.h:29
@ ITEM_TYPE_MACHINING
Robot machining project, curve follow, point follow or 3D printing project.
Definition: iitem.h:50
@ ITEM_TYPE_OBJECT
Item of type object (.stl, .step or .iges for example)
Definition: iitem.h:35
@ ITEM_TYPE_ANY
Any item type.
Definition: iitem.h:20
@ ITEM_TYPE_CAMERA
Camera.
Definition: iitem.h:68
@ ITEM_TYPE_INSTRUCTION
Instruction.
Definition: iitem.h:44
@ ITEM_TYPE_GENERIC
Generic custom items (customizable)
Definition: iitem.h:71
@ ITEM_TYPE_ROBOT_ARM
Robot arms only.
Definition: iitem.h:65
@ ITEM_TYPE_PROGRAM_PYTHON
Python script.
Definition: iitem.h:47
virtual void setGeometryPose(Mat pose, bool apply_transf=false)=0
Sets the position (pose) the object geometry with respect to its own reference frame....
virtual void Delete()=0
删除s an item and its childs from the station.
virtual void setSpeed(double speed_linear, double accel_linear=-1, double speed_joints=-1, double accel_joints=-1)=0
Sets the speed and/or the acceleration of a robot.
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,...
virtual void waitDI(const QString &io_var, const QString &io_value, double timeout_ms=-1)=0
Waits for an input io_id to attain a given value io_value. Optionally, a timeout can be provided.
virtual bool MoveL(const Item &itemtarget)=0
Add a linear move to a program or move a robot to a target item ("Move Linear" mode)....
virtual int Type()=0
Item type (object, robot, tool, reference, robot machining project, ...)
virtual tJoints JointsHome()=0
Returns the home joints of a robot. These joints can be manually set in the robot "Parameters" menu,...
virtual bool Save(const QString &filename)=0
Save a station, a robot, a tool or an object to a file
virtual tJoints SolveIK(const Mat &pose, const tJoints *joints_close=nullptr, const Mat *tool_pose=nullptr, const Mat *reference_pose=nullptr)=0
Computes the inverse kinematics for the specified robot and pose. The joints returned are the closest...
virtual bool MoveL(const Mat &target)=0
Add a linear move to a program or move a robot to a pose target ("Move Linear" mode)....
virtual void setInstruction(int ins_id, const QString &name, int instype, int movetype, bool isjointtarget, const Mat &target, const tJoints &joints)=0
Sets the program instruction at position id
virtual Item AddTool(const Mat &tool_pose, const QString &tool_name="New TCP")=0
Adds an empty tool to the robot provided the tool pose (4x4 Matrix) and the tool name.
虚拟int InstructionListJoints (QString &error_msg, tMatrix2D *matrix, double step_mm=1, double step_deg=1, int check_collisions=IRoboDK::COLLISION_OFF, int flags=0, double time_step=0.1)=0
Returns a list of joints an MxN matrix, where M is the number of robot axes plus 4 columns....
virtual void setPoseTool(const Item tool_item)=0
Sets the tool of a robot or a tool object (Tool Center Point, or TCP). The tool pose can be either an...
virtual bool MoveL(const tJoints &joints)=0
Add a linear move to a program or move a robot to a joint target ("Move Linear" mode)....
virtual int InstructionList(tMatrix2D *instructions)=0
Returns the list of program instructions as an MxN matrix, where N is the number of instructions and ...
virtual void setJointsHome(const tJoints &jnts)=0
Set robot joints for the home position
virtual void setRunType(int program_run_type)=0
Sets if the program will be run in simulation mode or on the real robot (same flag obtained when righ...
virtual QString Name()=0
Returns the name of an item. The name of the item is always displayed in the RoboDK station tree
virtual QString getDI(const QString &io_var)=0
Get a Digital Input (DI). This function is only useful when connected to a real robot using the robot...
virtual void setAsCartesianTarget()=0
Sets a target as a cartesian target. A cartesian target moves to cartesian coordinates.
virtual bool MoveC(const Item &itemtarget1, const Item &itemtarget2)=0
Add a circular move to a program or move a robot through an arc given two target items ("Move Circula...
virtual void customInstruction(const QString &name, const QString &path_run, const QString &path_icon="", bool blocking=true, const QString &cmd_run_on_robot="")=0
Add a custom instruction. This instruction will execute a Python file or an executable file.
virtual int ConnectedState(QString *msg=nullptr)=0
Retrieve the robot connection status.
虚拟物品AttachClosest () = 0
Attach the closest object to the tool. Returns the item that was attached.
virtual void InstructionAt(int ins_id, QString &name, int &instype, int &movetype, bool &isjointtarget, Mat &target, tJoints &joints)=0
Returns the program instruction at position id
virtual bool Disconnect()=0
Disconnect from a real robot (when the robot driver is used)
virtual bool MoveJ(const Item &itemtarget)=0
Add a joint move to a program or move a robot to a target item ("Move Joint" mode)....
virtual void setColor(const tColor &clr)=0
Set the color of an object, tool or robot. A color must in the format COLOR=[R, G,...
virtual bool setParam(const QString &name, const QByteArray &value)=0
Set a custom parameter to store data with an item. If the parameter name does not exist it will creat...
virtual void Stop()=0
Stops a program or a robot
virtual QString setParam(const QString ¶m, const QString &value="", QList< Item > *itemlist=nullptr, double *values=nullptr, tMatrix2D *matrix=nullptr)=0
Set a specific parameter associated with an item (used for specific parameters, commands and internal...
virtual Item ObjectLink(int link_id=0)=0
Returns an item pointer to the geometry of a robot link. This is useful to show/hide certain robot li...
virtual void Color(tColor &clr_out)=0
Return the color of an :class:.Item (object, tool or robot). If the item has multiple colors it retur...
virtual bool setPose(const Mat pose)=0
Sets the local position (pose) of an object, target or reference frame. For example,...
virtual void setAccuracyActive(bool accurate=true)=0
Sets the accuracy of the robot active or inactive. A robot must have been calibrated to properly use ...
virtual int MoveJ_Test(const tJoints &j1, const tJoints &j2, double minstep_deg=-1)=0
Checks if a joint movement is possible and, optionally, free of collisions.
virtual void Pause(double time_ms=-1)=0
Generates a pause instruction for a robot or a program when generating code. Set it to -1 (default) i...
virtual Mat Pose()=0
Returns the local position (pose) of an object, target or reference frame. For example,...
virtual void SelectedFeature(bool &is_selected, int feature_type, int &feature_id)=0
Retrieve the currently selected feature for this object.
virtual int setJointLimits(const tJoints &lower_limits, const tJoints &upper_limits)=0
Set the joint limits of a robot
virtual int InstructionCount()=0
Returns the number of instructions of a program.
virtual double Update(double out_nins_time_dist[4], int collision_check=RoboDK::COLLISION_OFF, double mm_step=-1, double deg_step=-1)=0
Updates a program and returns the estimated time and the number of valid instructions....
virtual QList< Mat > JointPoses(const tJoints &jnts)=0
Returns the positions of the joint links for a provided robot configuration (joints)....
virtual void JointsConfig(const tJoints &joints, tConfig config)=0
Returns the robot configuration state for a set of robot joints.
virtual Item setMachiningParameters(const QString &ncfile="", Item part_obj=nullptr, const QString &options="")=0
Update the robot milling path input and parameters. Parameter input can be an NC file (G-code or APT ...
virtual void setRobot(const Item &robot)=0
Sets the robot of a program or a target. You must set the robot linked to a program or a target every...
virtual void Copy()=0
Copy this item (similar to Ctrl+C). The user clipboard is not altered.
virtual bool JointsValid(const tJoints &jnts)=0
Check if a set of joints are valid
virtual bool Collided(int *id=nullptr)=0
Returns true if the object is in a collision state (collision checking must be activated manually or ...
virtual Mat SolveFK(const tJoints &joints, const Mat *tool_pose=nullptr, const Mat *reference_pose=nullptr)=0
Computes the forward kinematics of the robot for the provided joints. The tool and the reference fram...
virtual bool getParam(const QString &name, QByteArray &value)=0
Get a custom parameter associated with an item. Returns False if the parameter name does not exist.
virtual bool MoveC(const tJoints &joints1, const tJoints &joints2)=0
Add a circular move to a program or move a robot through an arc given two joint targets ("Move Circul...
virtual bool Selected()=0
Returns true if the item is selected by the user (in the tree or the screen)
virtual bool Connect(const QString &robot_ip="")=0
Connect to a real robot using the corresponding robot driver.
virtual void Scale(double scale)=0
Apply a scale to an object to make it bigger or smaller. The scale can be uniform (if scale is a floa...
virtual Mat PoseFrame()=0
Returns the reference frame pose of an item. If a robot is provided it will get the tool pose of the ...
virtual bool MoveJ(const Mat &target)=0
Add a joint move to a program or move a robot to a pose target ("Move Joint" mode)....
virtual bool MoveJ(const tJoints &joints)=0
Add a joint move to a program or move a robot to a joint target ("Move Joint" mode)....
virtual Item getLink(int type_linked=ITEM_TYPE_ROBOT)=0
Returns an item linked to a robot, object, tool, program or robot machining project....
virtual void setAsJointTarget()=0
Sets a target as a joint target. A joint target moves to a joints position without regarding the cart...
virtual Item InstructionTargetAt(int ins_id)=0
Returns the target item at the specified program instruction. It returns a null pointer if the instru...
virtual void setParentStatic(Item parent)=0
Attaches the item to another parent while maintaining the current absolute position in the station....
virtual void setPoseFrame(const Mat frame_pose)=0
Sets the reference frame of a robot(user frame). The frame can be either an item or a pose....
virtual void setJoints(const tJoints &jnts)=0
Set robot joints or the joints of a target
virtual bool Busy()=0
Checks if a robot or program is currently running (busy or moving)
virtual Item Parent()=0
Return the parent item of this item
virtual bool isJointTarget()=0
Returns True if a target is a joint target (green icon). Otherwise, the target is a Cartesian target ...
virtual void setPoseFrame(const Item frame_item)=0
Sets the tool of a robot or a tool object (Tool Center Point, or TCP). The tool pose can be either an...
virtual void setAO(const QString &io_var, const QString &io_value)=0
Set an Analog Output (AO).
virtual Item Paste()=0
Paste the copied item to this item (similar to Ctrl+V). For example, you can paste to a station,...
virtual void ShowSequence(tMatrix2D *sequence)=0
Displays a sequence of joints
virtual QList< tJoints > SolveIK_All(const Mat &pose, const Mat *tool_pose=nullptr, const Mat *reference_pose=nullptr)=0
Computes the inverse kinematics for the specified robot and pose. The function returns all available ...
virtual tJoints Joints()=0
Returns the current joints of a robot or the joints of a target. If the item is a cartesian target,...
virtual int InstructionSelect(int ins_id=-1)=0
Select an instruction in the program as a reference to add new instructions. New instructions will be...
virtual void ShowInstructions(bool visible=true)=0
Show or hide instruction items of a program in the RoboDK tree
virtual void DetachAll(Item parent=nullptr)=0
Detach any object attached to a tool.
虚拟空白setVisible (bool可见,int visible_frame=-1)=0
Sets the item visiblity status
virtual void Scale(double scale_xyz[3])=0
Apply a per-axis scale to an object to make it bigger or smaller. The scale can be uniform (if scale ...
virtual void setName(const QString &name)=0
Set the name of a RoboDK item.
virtual int JointLimits(tJoints *lower_limits, tJoints *upper_limits)=0
Retrieve the joint limits of a robot
virtual void setRounding(double zonedata)=0
Sets the robot movement smoothing accuracy (also known as zone data value).
virtual int RunType()=0
Get if the program will be run in simulation mode or on the real robot (same flag obtained when right...
virtual void ConnectionParams(QString &robotIP, int &port, QString &remote_path, QString &FTP_user, QString &FTP_pass)=0
Returns the robot connection parameters
virtual void setParent(Item parent)=0
Attaches the item to a new parent while maintaining the relative position with its parent....
virtual void setConnectionParams(const QString &robotIP, const int &port=2000, const QString &remote_path="/", const QString &FTP_user="", const QString &FTP_pass="")=0
Set the robot connection parameters
virtual bool Scale(const double scalexyz[3], const Mat *tr_pre_scale, const Mat *tr_post_scale=nullptr)=0
Scale an object given a per-axis scale. Optionally provide a transformation matrix before and after t...
virtual void ShowTargets(bool visible=true)=0
Show or hide targets of a program in the RoboDK tree
virtual Mat PoseTool()=0
Returns the tool pose of an item. If a robot is provided it will get the tool pose of the active tool...
virtual bool RunProgram(const QString ¶ms="")=0
Runs a program. It returns the number of instructions that can be executed successfully (a quick prog...
virtual Mat PoseAbs()=0
Returns the global position (pose) of an item. For example, the position of an object/frame/target wi...
virtual QList< Item > Childs()=0
Returns a list of the item childs that are attached to the provided item. Exceptionally,...
virtual bool MoveC(const Mat &target1, const Mat &target2)=0
Add a circular move to a program or move a robot through an arc given two pose targets ("Move Circula...
virtual tJoints SimulatorJoints()=0
Return the current joint position of a robot (only from the simulator, never from the real robot).
virtual Mat GeometryPose()=0
Returns the position (pose) the object geometry with respect to its own reference frame....
virtual void setPoseTool(const Mat tool_pose)=0
Sets the tool of a robot or a tool object (Tool Center Point, or TCP). The tool pose can be either an...
virtual int InstructionDelete(int ins_id=0)=0
删除an instruction of a program
virtual int MoveL_Test(const tJoints &joints1, const Mat &pose2, double minstep_mm=-1)=0
Checks if a linear movement is free of issues and, optionally, collisions.
virtual void setPoseAbs(const Mat pose)=0
Sets the global position (pose) of an item. For example, the position of an object/frame/target with ...
@ COLLISION_OFF
Do not use collision checking.
Definition: irobodk.h:257
@ INSTRUCTION_CALL_PROGRAM
Instruction to call a program.
Definition: irobodk.h:217
Mat
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