2. robolink Module¶
The robolink module is the bridge between RoboDK and Python. Every object in the RoboDK item tree can be retrieved and it is represented by the object Item. An item can be a robot, a reference frame, a tool, an object or a specific project.
2.2. robolink Module¶
robolink.
EmbedWindow
(window_name, docked_name=None, size_w=-1, size_h=-1, pid=0, area_add=1, area_allowed=15, timeout=500)¶Embed a window from a separate process in RoboDK as a docked window. Returns True if successful.
- 参数
window_name (str) -- The name of the window currently open. Make sure the window name is unique and it is a top level window
docked_name (str) -- Name of the docked tab in RoboDK (optional, if different from the window name)
pid (int) -- Process ID (optional)
area_add (int) -- Set to 1 (right) or 2 (left) (default is 1)
area_allowed (int) -- Areas allowed (default is 15:no constrain)
timeout (int) -- Timeout to abort attempting to embed the window
from tkinter import * from robolink import * import threading # Create a new window window = tkinter.Tk() # Close the window def onClose(): window.destroy() quit(0) # Trigger Select button # IMPORTANT: We need to run the action on a separate thread because # (otherwise, if we want to interact with RoboDK window it will freeze) def on_btnSelect(): def thread_btnSelect(): # Run button action (example to select an item and display its name) RDK = Robolink() item = RDK.ItemUserPick('Select an item') if item.Valid(): RDK.ShowMessage("You selected the item: " + item.Name()) threading.Thread(target=thread_btnSelect).start() # Set the window title (must be unique for the docking to work, try to be creative!) window_title = 'RoboDK API Docked Window' window.title(window_title) # Delete the window when we close it window.protocol("WM_DELETE_WINDOW", onClose) # Add a button (Select action) btnSelect = Button(window, text='Trigger on_btnSelect', height=5, width=60, command=on_btnSelect) btnSelect.pack(fill=X) # Embed the window EmbedWindow(window_title) # Run the window event loop. This is like an app and will block until we close the window window.mainloop()
- class
robolink.
Item
(link, ptr_item=0, itemtype=-1)¶ The Item class represents an item in RoboDK station. An item can be a robot, a frame, a tool, an object, a target, ... any item visible in the station tree. An item can also be seen as a node where other items can be attached to (child items). Every item has one parent item/node and can have one or more child items/nodes.
RoboDK Items are automatically created and retrieved by generated by
Robolink
methods such asItem()
andItemUserPick()
from robolink import * # import the robolink library RDK = Robolink() # connect to the RoboDK API (RoboDK starts if it has not started tool = RDK.Item('Tool') # Get an item named Tool (name in the RoboDK station tree) robot = RDK.Item('', ITEM_TYPE_ROBOT) # Get the first available robot target = RDK.Item('Target 1', ITEM_TYPE_TARGET) # Get a target called "Target 1" frame = RDK.ItemUserPick('Select a reference frame', ITEM_TYPE_FRAME) # Promt the user to select a reference frame robot.setPoseFrame(frame) robot.setPoseTool(tool) robot.MoveJ(target) # Move the robot to the target using the selected reference frame
AddCurve
(curve_points, add_to_ref=False, projection_type=3)¶Adds a curve provided point coordinates. The provided points must be a list of vertices. A vertex normal can be provided optionally.
AddFile
(filename)¶Adds an object attached to this object
- 参数
filename (str) -- file path
AddGeometry
(fromitem, pose)¶Makes a copy of the geometry fromitem adding it at a given position (pose), relative to this item.
AddPoints
(points, add_to_ref=False, projection_type=3)¶Adds a list of points to an object. The provided points must be a list of vertices. A vertex normal can be provided optionally.
AddShape
(triangle_points)¶Adds a shape to the object provided some triangle coordinates. Triangles must be provided as a list of vertices. A vertex normal can be optionally provided.
AddTool
(tool_pose, tool_name='New TCP')¶Add a tool to a robot given the tool pose and the tool name. It returns the tool as an
Item
.- 参数
tool_pose (
Mat
) -- Tool pose (TCP) of the tool with respect to the robot flangetool_name (str) -- name of the tool
参见
AddFrame()
,PoseTool()
,setPoseTool()
AttachClosest
()¶Attach the closest object to the tool. Returns the item that was attached. Use item.Valid() to check if an object was attached to the tool.
Busy
()¶Checks if a robot or program is currently running (busy or moving). Returns a busy status (1=moving, 0=stopped)
Example:
from robolink import * # import the robolink library RDK = Robolink() # Connect to the RoboDK API prog = RDK.Item('MainProgram', ITEM_TYPE_PROGRAM) prog.RunProgram() while prog.Busy(): pause(0.1) print("Program done")
Collision
(item_check)¶Returns True if this item is in a collision state with another
Item
, otherwise it returns False.- 参数
item_check (
Item
) -- item to check for collisions
Color
()¶Return the color of an
Item
(object, tool or robot). If the item has multiple colors it returns the first color available). A color is in the format COLOR=[R,G,B,(A=1)] where all values range from 0 to 1.
Connect
(robot_ip='')¶Connect to a real robot and wait for a connection to succeed. Returns 1 if connection succeeded, or 0 if it failed.
- 参数
robot_ip (str) -- Robot IP. Leave blank to use the IP selected in the connection panel of the robot.
ConnectSafe
(robot_ip='', max_attempts=5, wait_connection=10)¶Connect to a real robot and wait for a connection to succeed. Returns 1 if connection succeeded 0 if it failed.
- 参数
robot_ip (str) -- Robot IP. Leave blank to use the IP selected in the connection panel of the robot.
max_attempts (int) -- maximum connection attemps before reporting an unsuccessful connection
wait_connection (float) -- time to wait in seconds between connection attempts
ConnectedState
()¶Check connection status with a real robobt Out 1 : status code -> (int) ROBOTCOM_READY if the robot is ready to move, otherwise, status message will provide more information about the issue Out 2 : status message -> Message description of the robot status
Example:
from robolink import * # import the robolink library robot = RDK.Item('', ITEM_TYPE_ROBOT) # Get the first robot available state = robot.Connect() print(state) # Check the connection status and message state, msg = robot.ConnectedState() print(state) print(msg) if state != ROBOTCOM_READY: print('Problems connecting: ' + robot.Name() + ': ' + msg) quit() # Move the robot (real robot if we are connected) robot.MoveJ(jnts, False)
ConnectionParams
()¶Returns the robot connection parameters :return: [robotIP (str), port (int), remote_path (str), FTP_user (str), FTP_pass (str)]
Copy
()¶Copy the item to the clipboard (same as Ctrl+C). Use together with Paste() to duplicate items.
Delete
()¶Remove this item and all its children from the station.
DetachAll
(parent=0)¶Detaches any object attached to a tool.
- 参数
parent (
Item
) -- New parent item to attach, such as a reference frame (optional). If not provided, the items held by the tool will be placed at the station root.
DetachClosest
(parent=0)¶Detach the closest object attached to the tool (see also: setParentStatic).
- 参数
parent (
Item
) -- New parent item to attach, such as a reference frame (optional). If not provided, the items held by the tool will be placed at the station root.
Disconnect
()¶Disconnect from a real robot (when the robot driver is used) Returns 1 if it disconnected successfully, 0 if it failed. It can fail if it was previously disconnected manually for example.
FilterProgram
(filestr)¶Filter a program file to improve accuracy for a specific robot. The robot must have been previously calibrated. It returns 0 if the filter succeeded, or a negative value if there are filtering problems. It also returns a summary of the filtering.
- 参数
filestr (str) -- File path of the program. Formats supported include: JBI (Motoman), SRC (KUKA), MOD (ABB), PRG (ABB), LS (FANUC).
FilterTarget
(pose, joints_approx=None)¶Filters a target to improve accuracy. This option requires a calibrated robot. :param pose: pose of the robot TCP with respect to the robot reference frame :type pose:
Mat
:param joints_approx: approximated desired joints to define the preferred configuration :type joints_approx: list of float orMat
Frame
()¶Obsolete. Use
PoseFrame()
instead. Returns the pose (Mat
) of the robot reference frame with respect to the robot base
GeometryPose
()¶Returns the position (pose as
Mat
) the object geometry with respect to its own reference frame. This procedure works for tools and objects.
GetPoints
(feature_type=1, feature_id=0)¶Retrieves the point under the mouse cursor, a curve or the 3D points of an object. The points are provided in [XYZijk] format in relative coordinates. The XYZ are the local point coordinate and ijk is the normal of the surface.
- 参数
feature_type (int) -- set to FEATURE_SURFACE to retrieve the point under the mouse cursor, FEATURE_CURVE to retrieve the list of points for that wire, or FEATURE_POINT to retrieve the list of points.
feature_id (int) -- used only if FEATURE_CURVE is specified, it allows retrieving the appropriate curve id of an object
- 返回
List of points
# Example to display the XYZ position of a selected object from robolink import * # Import the RoboDK API RDK = Robolink() # Start RoboDK API # Ask the user to select an object obj = RDK.ItemUserPick("Select an object", ITEM_TYPE_OBJECT) while True: is_selected, feature_type, feature_id = OBJECT.SelectedFeature() if is_selected and feature_type == FEATURE_SURFACE: point_mouse, name_feature = OBJECT.GetPoints(FEATURE_SURFACE) print("Selected %i (%i): %s %s" % (feature_id, feature_type, str(point_mouse), name_feature)) else: print("Object Not Selected. Select a point in the object surface...") pause(0.1)
Htool
()¶Obsolete. Use
PoseTool()
instead. Returns the pose (Mat
) of the robot tool (TCP) with respect to the robot flange
Instruction
(ins_id=-1)¶Return the current program instruction or the instruction given the instruction id (if provided). It returns the following information about an instruction: name: name of the instruction (displayed in the RoboDK tree) instype: instruction type (INS_TYPE_*). For example, INS_TYPE_MOVE for a movement instruction. movetype: type of movement for INS_TYPE_MOVE instructions: MOVE_TYPE_JOINT for joint moves, or MOVE_TYPE_LINEAR for linear moves isjointtarget: 1 if the target is specified in the joint space, otherwise, the target is specified in the cartesian space (by the pose) target: pose of the target as
Item
joints: robot joints for that target- 参数
ins_id (int) -- instruction id to return
参见
AddProgram()
,setInstruction()
InstructionCount
()¶Return the number of instructions of a program.
InstructionList
()¶Returns the list of program instructions as an MxN matrix, where N is the number of instructions and M equals to 1 plus the number of robot axes. This is the equivalent sequence that used to be supported by RoKiSim. Tip: Use RDK.ShowSequence(matrix) to dipslay a joint list or a RoKiSim sequence of instructions.
Out 1: Returns the matrix
Out 2: Returns 0 if the program has no issues
InstructionListJoints
(mm_step=10, deg_step=5, save_to_file=None, collision_check=0, flags=0, time_step=0.1)¶Returns a list of joints an MxN matrix, where M is the number of robot axes plus 4 columns. Linear moves are rounded according to the smoothing parameter set inside the program.
- 参数
mm_step (float) -- step in mm to split the linear movements
deg_step (float) -- step in deg to split the joint movements
save_to_file (str) -- (optional) save the result to a file as Comma Separated Values (CSV). If the file name is not provided it will return the matrix. If step values are very small, the returned matrix can be very large.
collision_check (int) -- (optional) check for collisions
flags (int) -- (optional) set to 1 to include the timings between movements, set to 2 to also include the joint speeds (deg/s), set to 3 to also include the accelerations, set to 4 to include all previous information and make the splitting time-based.
time_step (float) -- (optional) set the time step in seconds for time based calculation
- 返回
[message (str), joint_list (
Mat
), status (int)]
Outputs:
message (str): Returns a human readable error message (if any).
joint_list (
Mat
): 2D matrix with all the joint information and corresponding information such as step, time stamp and speeds. Each entry is one column. It also returns the list of joints as [J1, J2, ..., Jn, ERROR, MM_STEP, DEG_STEP, MOVE_ID, TIME, X,Y,Z] or the file name if a file path is provided to save the result. Default units are MM and DEG. Use list(Mat
) to extract each column in a list. The ERROR is returned as an int but it needs to be interpreted as a binary number.status (int): Status is 0 if no problems arised. Otherwise it returns the number of instructions that can be successfully executed. If status is negative it means that one or more targets are not defined (missing target item).
# If error is not 0, check the binary error using the following bit masks error_bin = int(str(ERROR),2) ERROR_KINEMATIC = 0b001 # One or more points in the path is not reachable ERROR_PATH_LIMIT = 0b010 # The path reached a joint axis limit ERROR_PATH_NEARSINGULARITY = 0b1000 # The robot is too close to a wrist singularity (J5). Lower the singularity tolerance to allow the robot to continue. ERROR_PATH_SINGULARITY = 0b100 # The robot reached a singularity point ERROR_COLLISION = 0b100000 # Collision detected
InstructionSelect
(ins_id=-1)¶Select an instruction in the program as a reference to add new instructions. New instructions will be added after the selected instruction. If no instruction ID is specified, the active instruction will be selected and returned.
IsInside
(object)¶Return True if the object is inside the provided object
- 参数
object (
Item
) -- object to check
JointLimits
()¶Retrieve the joint limits of a robot. Returns (lower limits, upper limits, joint type).
JointPoses
(joints=None)¶Returns the positions of the joint links for a provided robot configuration (joints). If no joints are provided it will return the poses for the current robot position. Out 1 : 4x4 x n -> array of 4x4 homogeneous matrices. Index 0 is the base frame reference (it never moves when the joints move).
Joints
()¶Return the current joint position as a
Mat
of a robot or the joints of a target. If the item is a cartesian target, it returns the preferred joints (configuration) to go to that cartesian position.Example:
from robolink import * # import the robolink library RDK = Robolink() # connect to the RoboDK API (RoboDK starts if it has not started) tool = RDK.Item('', ITEM_TYPE_ROBOT) # Retrieve the robot joints = robot.Joints().list() # retrieve the current robot joints as a list joints[5] = 0 # set joint 6 to 0 deg robot.MoveJ(joints) # move the robot to the new joint position
JointsConfig
(joints)¶Returns the robot configuration state for a set of robot joints. The configuration state is defined as: [REAR, LOWERARM, FLIP]
- 参数
joints (list of float) -- robot joints
JointsHome
()¶Return the home joints of a robot. The home joints can be manually set in the robot "Parameters" menu of the robot panel in RoboDK, then select "Set home position".
参见
MakeProgram
(filestr='', run_mode=3)¶Generate the program file. Returns True if the program was successfully generated.
- 参数
filestr (str) -- Path to save the program ending with a slash (not including the file name and extension). Make sure the folder ends with a slash. You can use backslashes or forward slashes to define the path. In most cases, the file name is defined by the program name (visible in the RoboDK tree) and the extension is defined by the Post Processor (the file extension must match the extension supported by your robot controller). It can be left empty to use the default action (save to the default programs location)
run_mode -- RUNMODE_MAKE_ROBOTPROG to generate the program file. Alternatively, Use RUNMODE_MAKE_ROBOTPROG_AND_UPLOAD or RUNMODE_MAKE_ROBOTPROG_AND_START to transfer the program through FTP and execute the program.
- 返回
[success (True or False), log (str), transfer_succeeded (True/False)]
Transfer succeeded is True if there was a successful program transfer (if RUNMODE_MAKE_ROBOTPROG_AND_UPLOAD or RUNMODE_MAKE_ROBOTPROG_AND_START are used)
MoveC
(target1, target2, blocking=True)¶Move a robot to a specific target ("Move Circular" mode). By default, this procedure waits (blocks) until the robot finishes the movement.
MoveJ
(target, blocking=True)¶Move a robot to a specific target ("Move Joint" mode). This function waits (blocks) until the robot finishes its movements. If this is used with a program item, a new joint movement instruction will be added to the program. Important note when adding new movement instructions to programs: only target items supported, not poses.
- 参数
target (
Mat
, list of joints orItem
) -- Target to move to. It can be the robot joints (Nx1 or 1xN), the pose (4x4) or a target (item pointer)blocking (bool) -- Set to True to wait until the robot finished the movement (default=True). Set to false to make it a non blocking call. Tip: If set to False, use robot.Busy() to check if the robot is still moving.
MoveJ_Test
(j1, j2, minstep_deg=-1)¶Checks if a joint movement is feasible and free of collision (if collision checking is activated).
- 参数
j1 (list of float) -- start joints
j2 (list of float) -- end joints
minstep_deg (float) -- joint step in degrees
- 返回
returns 0 if the movement is free of collision or any other issues. Otherwise it returns the number of pairs of objects that collided if there was a collision.
- 返回类型
int
MoveL
(target, blocking=True)¶Moves a robot to a specific target ("Move Linear" mode). This function waits (blocks) until the robot finishes its movements. This function can also be called on Programs and a new movement instruction will be added at the end of the program. If this is used with a program item, a new linear movement instruction will be added to the program. Important note when adding new movement instructions to programs: only target items supported, not poses.
- 参数
target (
Mat
, list of joints orItem
) -- Target to move to. It can be the robot joints (Nx1 or 1xN), the pose (4x4) or a target (item pointer)blocking (bool) -- Set to True to wait until the robot finished the movement (default=True). Set to false to make it a non blocking call. Tip: If set to False, use robot.Busy() to check if the robot is still moving.
MoveL_Test
(j1, pose, minstep_mm=-1)¶Checks if a linear movement is feasible and free of collision (if collision checking is activated).
- 参数
j1 (list of float) -- start joints
pose (
Mat
) -- end pose (position of the active tool with respect to the active reference frame)minstep_mm (float) -- linear step in mm
- 返回
returns 0 if the movement is free of collision or any other issues.
- 返回类型
int
If the robot can not reach the target pose it returns -2. If the robot can reach the target but it can not make a linear movement it returns -1.
Name
()¶Returns the item name. The name of the item is always displayed in the RoboDK station tree. Returns the name as a string (str)
- 返回
New item name
- 返回类型
str
ObjectLink
(link_id=0)¶Returns an item pointer (
Item
) to a robot link. This is useful to show/hide certain robot links or alter their geometry.- 参数
link_id (int) -- link index (0 for the robot base, 1 for the first link, ...)
Paste
()¶Paste the copied
Item
from the clipboard as a child of this item (same as Ctrl+V) Returns the new item created (pasted)
Pause
(time_ms=-1)¶Pause instruction for a robot or insert a pause instruction to a program (when generating code offline -offline programming- or when connected to the robot -online programming-).
- 参数
time_ms (float) -- time in miliseconds. Do not provide a value (leave the default -1) to pause until the user desires to resume the execution of a program.
Pose
()¶Returns the relative position (pose) of an object, target or reference frame. For example, the position of an object, target or reference frame with respect to its parent. If a robot is provided, it will provide the pose of the end efector with respect to the robot base (same as PoseTool()) Returns the pose as
Mat
.Tip: Use a Pose_2_* function from the robodk module (such as
robodk.Pose_2_KUKA
) to convert the pose to XYZABC (XYZ position in mm and ABC orientation in degrees), specific to a robot brand.Example: 焊接 举例
PoseAbs
()¶Return the position (
Mat
) of this item given the pose with respect to the absolute reference frame (station reference) For example, the position of an object/frame/target with respect to the origin of the station.
ProgramStart
(programname, folder='', postprocessor='')¶Defines the name of the program when a program must be generated. It is possible to specify the name of the post processor as well as the folder to save the program. This method must be called before any program output is generated (before any robot movement or other program instructions).
- 参数
progname (str) -- name of the program
folder (str) -- folder to save the program, leave empty to use the default program folder
postprocessor (str) -- name of the post processor (for a post processor in C:/RoboDK/Posts/Fanuc_post.py it is possible to provide "Fanuc_post.py" or simply "Fanuc_post")
ProjectPoints
(points, projection_type=3)¶Projects a point or a list of points to the object given its coordinates. The provided points must be a list of [XYZ] coordinates. Optionally, a vertex normal can be provided [XYZijk].
RDK
()¶Returns the RoboDK link Robolink(). It is important to have different links (Robolink) for multithreaded applications.
参见
Recolor
(tocolor, fromcolor=None, tolerance=None)¶Changes the color of an
Item
(object, tool or robot). Colors must in the format COLOR=[R,G,B,(A=1)] where all values range from 0 to 1. Alpha (A) defaults to 1 (100% opaque). Set A to 0 to make an object transparent.- 参数
tocolor (list of float) -- color to set
fromcolor (list of float) -- color to change
tolerance (float (defaults to 0.1)) -- tolerance to replace colors (set to 0 for exact match)
RunCode
(prog_parameters=None)¶Run a program. It returns the number of instructions that can be executed successfully (a quick program check is performed before the program starts) This is a non-blocking call. Use program.Busy() to check if the program execution finished, or program.WaitFinished() to wait until the program finishes.
- 参数
prog_parameters (list of str) -- Program parameters can be provided for Python programs as a string
If setRunMode(RUNMODE_SIMULATE) is used: the program will be simulated (default run mode)
If setRunMode(RUNMODE_RUN_ROBOT) is used: the program will run on the robot (default when RUNMODE_RUN_ROBOT is used)
If setRunMode(RUNMODE_RUN_ROBOT) is used together with program.setRunType(PROGRAM_RUN_ON_ROBOT) -> the program will run sequentially on the robot the same way as if we right clicked the program and selected "Run on robot" in the RoboDK GUI
RunCodeCustom
(code, run_type=0)¶Obsolete, use RunInstruction instead. Adds a program call, code, message or comment to the program. Returns 0 if succeeded.
RunInstruction
(code, run_type=0)¶Adds a program call, code, message or comment to the program. Returns 0 if succeeded.
- 参数
code (str) -- The code to insert, program to run, or comment to add.
run_type (int) -- Use INSTRUCTION_* variable to specify if the code is a program call or just a raw code insert. For example, to add a line of customized code use:
INSTRUCTION_CALL_PROGRAM = 0 # Program call INSTRUCTION_INSERT_CODE = 1 # Insert raw code in the generated program INSTRUCTION_START_THREAD = 2 # Start a new process INSTRUCTION_COMMENT = 3 # Add a comment in the code INSTRUCTION_SHOW_MESSAGE = 4 # Add a message
Example:
program.RunInstruction('Setting the spindle speed', INSTRUCTION_COMMENT) program.RunInstruction('SetRPM(25000)', INSTRUCTION_INSERT_CODE) program.RunInstruction('Done setting the spindle speed. Ready to start!', INSTRUCTION_SHOW_MESSAGE) program.RunInstruction('Program1', INSTRUCTION_CALL_PROGRAM)
RunProgram
(prog_parameters=None)¶Obsolete. Use
RunCode()
instead. RunProgram is available for backwards compatibility.
Save
(filename)¶Save a station or object to a file
Scale
(scale)¶Apply a scale to an object to make it bigger or smaller. The scale can be uniform (if scale is a float value) or per axis (if scale is an array/list [scale_x, scale_y, scale_z]).
- 参数
scale (float or list of 3 float [scale_x, scale_y, scale_z]) -- scale parameter (1 means no change)
SearchL
(target, blocking=True)¶Moves a robot to a specific target and stops when a specific input switch is detected ("Search Linear" mode). This function waits (blocks) until the robot finishes its movements.
- 参数
target (
Mat
, list of joints orItem
) -- Target to move to. It can be the robot joints (Nx1 or 1xN), the pose (4x4) or a target (item pointer)blocking (bool) -- Set to True to wait until the robot finished the movement (default=True). Set to false to make it a non blocking call. Tip: If set to False, use robot.Busy() to check if the robot is still moving.
参见
SelectedFeature
()¶Retrieve the currently selected feature for this object.
参见
GetPoints()
Example:
# Show the point selected object = RDK.Item('Object', ITEM_TYPE_OBJECT) is_selected, feature_type, feature_id = OBJECT.SelectedFeature() points, name_selected = object.GetPoints(feature_type, feature_id) point = None if len(points) > 1: point = points[feature_id] else: point = points[0] RDK.ShowMessage("Selected Point: %s = [%.3f, %.3f, %.3f]" % (name_selected, point[0], point[1], point[2]))
ShowInstructions
(show=True)¶Show or hide instruction items of a program in the RoboDK tree
- 参数
show (bool) -- Set to True to show the instruction nodes, otherwise, set to False
ShowSequence
(matrix)¶Displays a sequence of joints in RoboDK and displays a slider.
- 参数
matrix (list of list of float or a matrix of joints as a
Mat
) -- list of joints as a matrix or as a list of joint arrays. An sequence of instructions is also supported (same sequence that was supported with RoKiSim).
ShowTargets
(show=True)¶Show or hide targets of a program in the RoboDK tree
- 参数
show (bool) -- Set to False to remove the target item (the target is not deleted as it remains inside the program), otherwise, set to True to show the targets
SimulatorJoints
()¶Return the current joint position of a robot (only from the simulator, never from the real robot). This should be used only when RoboDK is connected to the real robot and only the simulated robot needs to be retrieved (for example, if we want to move the robot using a spacemouse).
Note: Use robot.Joints() instead to retrieve the simulated and real robot position when connected.
参见
SolveFK
(joints, tool=None, reference=None)¶Calculate the forward kinematics of the robot for the provided joints. Returns the pose of the robot flange with respect to the robot base reference (
Mat
).- 参数
joints (list of float or
Mat
) -- robot jointstool (
Mat
) -- Optionally provide the tool used to calculate the forward kinematics. If this parameter is ignored it will use the robot flange.reference (
Mat
) -- Optionally provide the reference frame used to calculate the forward kinematics. If this parameter is ignored it will use the robot base frame.
Example:
from robolink import * # import the robolink library RDK = Robolink() # connect to the RoboDK API (RoboDK starts if it has not started robot = RDK.Item('', ITEM_TYPE_ROBOT) # Retrieve the robot # get the current robot joints robot_joints = robot.Joints() # get the robot position from the joints (calculate forward kinematics) robot_position = robot.SolveFK(robot_joints) # get the robot configuration (robot joint state) robot_config = robot.JointsConfig(robot_joints) # calculate the new robot position new_robot_position = transl([x_move,y_move,z_move])*robot_position # calculate the new robot joints new_robot_joints = robot.SolveIK(new_robot_position) if len(new_robot_joints.tolist()) < 6: print("No robot solution!! The new position is too far, out of reach or close to a singularity") continue # calculate the robot configuration for the new joints new_robot_config = robot.JointsConfig(new_robot_joints) if robot_config[0] != new_robot_config[0] or robot_config[1] != new_robot_config[1] or robot_config[2] != new_robot_config[2]: print("Warning! Robot configuration changed: this may lead to unextected movements!") print(robot_config) print(new_robot_config) # move the robot to the new position robot.MoveJ(new_robot_joints) #robot.MoveL(new_robot_joints)
SolveIK
(pose, joints_approx=None, tool=None, reference=None)¶Calculates the inverse kinematics for the specified pose. It returns the joints solution as a list of floats which are the closest match to the current robot configuration (see SolveIK_All()). Optionally, specify a preferred robot position using the parameter joints_approx.
- 参数
pose (
Mat
) -- pose of the robot flange with respect to the robot base framejoints_approx (list of float) -- approximate solution. Leave blank to return the closest match to the current robot position.
SolveIK_All
(pose, tool=None, reference=None)¶Calculates the inverse kinematics for the specified robot and pose. The function returns all available joint solutions as a 2D matrix. Returns a list of joints as a 2D matrix (float x n x m)
- 参数
pose (
Mat
) -- pose of the robot flange with respect to the robot base frame
Stop
()¶Stop a program or a robot
Tool
()¶Obsolete. Use
PoseTool()
instead. Returns the pose (Mat
) of the robot tool (TCP) with respect to the robot flange
Type
()¶Return the type of the item (robot, object, tool, frame, ...). Tip: Compare the returned value against ITEM_TYPE_* variables
参见
Update
(check_collisions=0, timeout_sec=3600, mm_step=-1, deg_step=-1)¶Updates a program and returns the estimated time and the number of valid instructions. An update can also be applied to a robot machining project. The update is performed on the generated program.
- 参数
check_collisions (int) -- Check collisions (COLLISION_ON -yes- or COLLISION_OFF -no-)
timeout_sec (int) -- Maximum time to wait for the update to complete (in seconds)
mm_step (float) -- Step in mm to split the program (-1 means default, as specified in Tools-Options-Motion)
deg_step (float) -- Step in deg to split the program (-1 means default, as specified in Tools-Options-Motion)
- 返回
[valid_instructions, program_time, program_distance, valid_ratio, readable_msg]
valid_instructions: The number of valid instructions
program_time: Estimated cycle time (in seconds)
program_distance: Estimated distance that the robot TCP will travel (in mm)
valid_ratio: This is a ratio from [0.00 to 1.00] showing if the path can be fully completed without any problems (1.0 means the path 100% feasible) or valid_ratio is <1.0 if there were problems along the path.
valid_ration will be < 0 if Update is called on a machining project and the machining project can't be achieved successfully.
readable_msg: a readable message as a string
Valid
()¶Checks if the item is valid. Returns True if the item is valid or False if the item is not valid. An invalid item will be returned by an unsuccessful function call (wrong name or because an item was deleted)
参见
Example:
from robolink import * # import the robolink library RDK = Robolink() # connect to the RoboDK API (RoboDK starts if it has not started tool = RDK.Item('Tool') # Retrieve an item named tool if not tool.Valid(): print("The tool item does not exist!") quit()
Visible
()¶Returns 1 if the item is visible, otherwise it returns 0.
WaitMove
(timeout=300)¶Waits (blocks) until the robot finishes its movement.
- 参数
timeout (float) -- Maximum time to wait for robot to finish its movement (in seconds)
addMoveC
(itemtarget1, itemtarget2)¶Adds a new circular move instruction to a program (This function is obsolete. Use MoveL instead.)
- 参数
itemtarget (
Item
) -- target item to move to
addMoveJ
(itemtarget)¶Adds a new robot joint move instruction to a program. This function is obsolete. Use MoveJ instead.
- 参数
itemtarget (
Item
) -- target item to move to
addMoveL
(itemtarget)¶Adds a new linear move instruction to a program. This function is obsolete. Use MoveL instead.
- 参数
itemtarget (
Item
) -- target item to move to
customInstruction
(name, path_run, path_icon='', blocking=1, cmd_run_on_robot='')¶Add a custom instruction. This instruction will execute a Python file or an executable file.
- 参数
name (str or int) -- digital input (string or number)
path_run (str) -- path to run (relative to RoboDK/bin folder or absolute path)
path_icon (str) -- icon path (relative to RoboDK/bin folder or absolute path)
blocking (int) -- 1 if blocking, 0 if it is a non blocking executable trigger
cmd_run_on_robot (str) -- Command to run through the driver when connected to the robot
equals
(item2)¶Returns True if an item is the same as this item
Item
- 参数
item2 (
Item
) -- item to compare
getLink
(type_linked=2)¶Returns an item pointer (
Item
) to a robot, object, tool or program. This is useful to retrieve the relationship between programs, robots, tools and other specific projects.- 参数
type_linked (int) -- type of linked object to retrieve
setAcceleration
(accel_linear)¶Sets the linear acceleration of a robot in mm/s2
- 参数
accel_linear (float) -- acceleration in mm/s2
setAccelerationJoints
(accel_joints)¶Sets the joint acceleration of a robot
- 参数
accel_joints (float) -- acceleration in deg/s2 for rotary joints and mm/s2 for linear joints
setAccuracyActive
(accurate=1)¶Sets the accuracy of the robot active or inactive. A robot must have been calibrated to properly use this option.
- 参数
accurate (int) -- set to 1 to use the accurate model or 0 to use the nominal model
setAsCartesianTarget
()¶Sets a target as a cartesian target. A cartesian target moves to cartesian coordinates.
setAsJointTarget
()¶Sets a target as a joint target. A joint target moves to the joint position without taking into account the cartesian coordinates.
setColor
(tocolor)¶Set the color of an object, tool or robot. A color must in the format COLOR=[R,G,B,(A=1)] where all values range from 0 to 1.
- 参数
tocolor (list of float) -- color to set
setColorCurve
(tocolor, curve_id=-1)¶Set the color of a curve object. It can also be used for tools. A color must in the format COLOR=[R,G,B,(A=1)] where all values range from 0 to 1.
- 参数
tocolor (list of float) -- color to set
curve_id (int) -- ID of the curve: the ID is the order in which the shape was added using AddCurve()
setColorShape
(tocolor, shape_id)¶Set the color of an object shape. It can also be used for tools. A color must in the format COLOR=[R,G,B,(A=1)] where all values range from 0 to 1.
- 参数
tocolor (list of float) -- color to set
shape_id (int) -- ID of the shape: the ID is the order in which the shape was added using AddShape()
setConnectionParams
(robot_ip, port, remote_path, ftp_user, ftp_pass)¶Retrieve robot connection parameters
- 参数
robot_ip (str) -- robot IP
port (int) -- robot communication port
remote_path (str) -- path to transfer files on the robot controller
ftp_user (str) -- user name for the FTP connection
ftp_pass (str) -- password credential for the FTP connection
setDO
(io_var, io_value)¶Set a digital output to a given value. This can also be used to set any variables to a desired value.
- 参数
io_var (str or int) -- digital output (string or number)
io_value (str, int or float) -- value
setFrame
(frame)¶Obsolete. Use
setPoseFrame()
instead. Sets the reference frame of a robot (user frame). The frame can be an item or a 4x4 Matrix
setGeometryPose
(pose)¶Set the position (pose) the object geometry with respect to its own reference frame. This can be applied to tools and objects. The pose must be a
Mat
setHtool
(tool)¶Obsolete.
setPoseTool()
instead. Sets the robot tool pose (TCP) with respect to the robot flange. The tool pose can be an item or a 4x4 Matrix
setInstruction
(ins_id, name, instype, movetype, isjointtarget, target, joints)¶Update a program instruction.
- 参数
ins_id (int) -- index of the instruction (0 for the first instruction, 1 for the second, and so on)
name (str) -- Name of the instruction (displayed in the RoboDK tree)
instype (int) -- Type of instruction. INS_TYPE_*
movetype (int) -- Type of movement if the instruction is a movement (MOVE_TYPE_JOINT or MOVE_TYPE_LINEAR)
isjointtarget (int) -- 1 if the target is defined in the joint space, otherwise it means it is defined in the cartesian space (by the pose)
target (
Mat
) -- target posejoints (list of float) -- robot joints for the target
参见
AddProgram()
,Instruction()
setJointLimits
(lower_limit, upper_limit)¶Update the robot joint limits
- 参数
lower_limit (list of float) -- lower joint limits
upper_limit (list of float) -- upper joint limits
setJoints
(joints)¶Set the current joints of a robot or a target. If robot joints are set, the robot position will be updated on the screen.
- 参数
joints (list of float or
Mat
) -- robot joints
参见
setJointsHome
(joints)¶Set the home position of the robot in the joint space.
- 参数
joints (list of float or
Mat
) -- robot joints
setMachiningParameters
(ncfile='', part=0, params='')¶Update the robot milling path input and parameters. Parameter input can be an NC file (G-code or APT file) or an object item in RoboDK. A curve or a point follow project will be automatically set up for a robot manufacturing project. Tip: Use getLink(), setPoseTool(), setPoseFrame() to get/set the robot tool, reference frame, robot and program linked to the project. Tip: Use setPose() and setJoints() to update the path to tool orientation or the preferred start joints.
- 参数
ncfile (str) -- path to the NC file (G-code or APT) to be loaded (optional)
part (
Item
) -- object holding curves or points to automatically set up a curve/point follow project (optional)params -- Additional options
参见
AddMachiningProject()
,Joints()
,getLink()
,setJoints()
,setToolPose()
,setFramePose()
Example:
object_curve = RDK.AddCurve(POINTS) object_curve.setName('AutoPoints n%i' % NUM_POINTS) path_settings = RDK.AddMillingProject("AutoCurveFollow settings") prog, status = path_settings.setMillingParameters(part=object_curve)
setMillingParameters
(ncfile='', part=0, params='')¶Obsolete, use
setMachiningParameters()
instead
setName
(name)¶Set the name of the item. The name of the item will be displayed in the station tree.
- 参数
name (str) -- New item name
参见
setParam
(param, value='')¶Send a specific parameter for an item.
- 参数
command (str) -- Command name
value (str) -- Comand value (optional, not all commands require a value)
from robolink import * RDK = Robolink() # Start the RoboDK API # How to change the number of threads using by the RoboDK application: robot = RDK.Item("", ITEM_TYPE_ROBOT) # Set the robot post processor (name of the py file in the posts folder) robot.setParam("PostProcessor", "Fanuc_RJ3")
setParamRobotTool
(tool_mass=5, tool_cog=None)¶Sets the tool mass and center of gravity. This is only used with accurate robots to improve accuracy.
- 参数
tool_mass (float) -- tool weigth in Kg
tool_cog (list) -- tool center of gravity as [x,y,z] with respect to the robot flange
setParent
(parent)¶Attaches the item to a new parent while maintaining the relative position with its parent. The absolute position is changed.
- 参数
parent (
Item
) -- parent to attach the item
setParentStatic
(parent)¶Attaches the item to another parent while maintaining the current absolute position in the station. The relationship between this item and its parent is changed to maintain the abosolute position.
- 参数
parent (
Item
) -- parent to attach the item
setPose
(pose)¶Set the position (pose) of the item with respect to its parent (item it is attached to). For example, the position of an object, frame or target with respect to its parent reference frame.
- 参数
pose (
Mat
) -- pose of the item with respect to its parent
setPoseAbs
(pose)¶Sets the position of the item given the pose (
Mat
) with respect to the absolute reference frame (station reference)- 参数
pose (
Mat
) -- pose of the item with respect to the station reference
setPoseFrame
(frame)¶Sets the reference frame of a robot (user frame). The frame can be an item or a 4x4 Matrix
setPoseTool
(tool)¶Set the robot tool pose (TCP) with respect to the robot flange. The tool pose can be an item or a 4x4 Matrix
setRobot
(robot=None)¶Assigns a specific robot to a program, target or robot machining project.
- 参数
robot (
Item
) -- robot to link
setRounding
(rounding_mm)¶Sets the rounding accuracy to smooth the edges of corners. In general, it is recommended to allow a small approximation near the corners to maintain a constant speed. Setting a rounding values greater than 0 helps avoiding jerky movements caused by constant acceleration and decelerations.
- 参数
rounding_mm (float) -- rounding accuracy in mm. Set to -1 (default) for best accuracy and to have point to point movements (might have a jerky behavior)
This rounding parameter is also known as ZoneData (ABB), CNT (Fanuc), C_DIS/ADVANCE (KUKA), cornering (Mecademic) or blending (Universal Robots)
setRunType
(program_run_type)¶Set the Run Type of a program to specify if a program made using the GUI will be run in simulation mode or on the real robot ("Run on robot" option).
- 参数
program_run_type (int) -- Use "PROGRAM_RUN_ON_SIMULATOR" to set the program to run on the simulator only or "PROGRAM_RUN_ON_ROBOT" to force the program to run on the robot
setSpeed
(speed_linear, speed_joints=-1, accel_linear=-1, accel_joints=-1)¶Sets the linear speed of a robot. Additional arguments can be provided to set linear acceleration or joint speed and acceleration.
- 参数
speed_linear (float) -- linear speed -> speed in mm/s (-1 = no change)
speed_joints (float) -- joint speed (optional) -> acceleration in mm/s2 (-1 = no change)
accel_linear (float) -- linear acceleration (optional) -> acceleration in mm/s2 (-1 = no change)
accel_joints (float) -- joint acceleration (optional) -> acceleration in deg/s2 (-1 = no change)
setSpeedJoints
(speed_joints)¶Sets the joint speed of a robot in deg/s for rotary joints and mm/s for linear joints
- 参数
speed_joints (float) -- speed in deg/s for rotary joints and mm/s for linear joints
setTool
(tool)¶Obsolete. Use
setPoseTool()
instead. Sets the robot tool pose (TCP) with respect to the robot flange. The tool pose can be an item or a 4x4 Matrix
setValue
(varname, value)¶Set a specific property name to a given value. This is reserved for internal purposes and future compatibility.
- 参数
varname (str) -- property name
value (str) -- property value
Example:
# How to change the display style of an object (color as AARRGGBB): obj = RDK.ItemUserPick('Select an object to change the style', ITEM_TYPE_OBJECT) obj.setValue('Display','PARTICLE=CUBE(0.2,0.2,0.2) COLOR=#FF771111') # Another way to change display style of points: obj.setValue('Display','PARTICLE=SPHERE(4,8) COLOR=red') # How to change the size of displayed curves: obj.setValue('Display','LINEW=4')
setVisible
(visible, visible_frame=None)¶Sets the item visiblity
- 参数
visible (bool) -- Set the object as visible (1/True) or invisible (0/False)
visible_frame (bool) -- Set the reference frame as visible (1/True) or invisible (0/False). It is also possible to provide flags to control the visibility of each robot link (only for robot items)
setZoneData
(zonedata)¶Obsolete. Use
setRounding()
instead.
waitDI
(io_var, io_value, timeout_ms=-1)¶Wait for an digital input io_var to attain a given value io_value. Optionally, a timeout can be provided.
- 参数
io_var (str or int) -- digital input (string or number)
io_value (str, int or float) -- value
timeout_ms (int or float) -- timeout in milliseconds
robolink.
RoboDKInstallFound
()¶Check if RoboDK is installed
- class
robolink.
Robolink
(robodk_ip='localhost', port=None, args=[], robodk_path=None)¶ The Robolink class is the link to to RoboDK and allows creating macros for Robodk, simulate applications and generate programs offline. Any interaction is made through "items" (Item() objects). An item is an object in the robodk tree (it can be either a robot, an object, a tool, a frame, a program, ...).
- 参数
robodk_ip (str) -- IP of the RoboDK API server (default='localhost')
port (int) -- Port of the RoboDK API server (default=None, it will use the default value)
args (list) --
Command line arguments to pass to RoboDK on startup (for example: '/NOSPLASH /NOSHOW' should be passed as args=['/NOSPLASH','/NOSHOW'] to not display RoboDK). Arguments have no effect if RoboDK is already running.
For more information: RoboDK list of arguments on startup.
robodk_path (str) -- RoboDK installation path. It defaults to RoboDK's default path (C:/RoboDK/bin/RoboDK.exe on Windows or /Applications/RoboDK.app/Contents/MacOS/RoboDK on Mac)
参见
ActiveStation
()¶Returns the active station item (station currently visible)
AddCurve
(curve_points, reference_object=0, add_to_ref=False, projection_type=3)¶Adds a curve provided point coordinates. The provided points must be a list of vertices. A vertex normal can be provided optionally.
- 参数
curve_points (
robodk.Mat
(3xN matrix, or 6xN to provide curve normals as ijk vectors)) -- List of points defining the curvereference_object (
Item
) -- item to attach the newly added geometry (optional)add_to_ref (bool) -- If True, the curve will be added as part of the object in the RoboDK item tree (a reference object must be provided)
projection_type (int) -- type of projection. Use the PROJECTION_* flags.
- 返回
added object/shape (0 if failed)
- 返回类型
PROJECTION_NONE = 0 # No projection PROJECTION_CLOSEST = 1 # The projection will be the closest point on the surface PROJECTION_ALONG_NORMAL = 2 # The projection will be done along the normal. PROJECTION_ALONG_NORMAL_RECALC = 3 # The projection will be done along the normal. Furthermore, the normal will be recalculated according to the surface normal. PROJECTION_CLOSEST_RECALC = 4 # The projection will be the closest point on the surface and the normals will be recalculated PROJECTION_RECALC = 5 # The normals are recalculated according to the surface normal of the closest projection. The points are not changed.
AddFile
(filename, parent=0)¶Load a file and attach it to parent (if provided). The call returns the newly added
Item
. If the new file is an object and it is attached to a robot it will be automatically converted to a tool.- 参数
filename (str) -- any file to load, supported by RoboDK. Supported formats include STL, STEP, IGES, ROBOT, TOOL, RDK,... It is also possible to load supported robot programs, such as SRC (KUKA), SCRIPT (Universal Robots), LS (Fanuc), JBI (Motoman), MOD (ABB), PRG (ABB), ...
parent (
Item
) -- item to attach the newly added object (optional)
Example:
RDK = Robolink() item = RDK.AddFile(r'C:\Users\Name\Desktop\object.step') item.setPose(transl(100,50,500)) # Add a tool to an existing robot: tool = RDK.AddFile(r'C:\Users\Name\Desktop\robot-tool.stl', robot) tool.setPoseTool(transl(100,50,500)) # Add a reference frame, move it and add an object to that reference frame (locally): frame = AddFrame('Reference A') frame.setPose(transl(100,200,300)) new_object = RDK.Addfile('path-to-object.stl', frame)
参见
Save()
,AddFrame()
,AddTool()
,Copy()
,Paste()
AddFrame
(name, itemparent=0)¶Adds a new reference Frame. It returns the new
Item
created.- 参数
name (str) -- name of the new reference frame
itemparent (
Item
) -- Item to attach the new reference frame (such as another reference frame)
AddMachiningProject
(name='Milling settings', itemrobot=0)¶Add a new robot machining project. Machining projects can also be used for 3D printing, following curves and following points. It returns the newly created
Item
containing the project settings. Tip: Use the MoveRobotThroughLine.py macro to see an example that creates a new "curve follow project" given a list of points to follow (Option 4).- 参数
name (str) -- Name of the project settings
itemrobot (
Item
) -- Robot to use for the project settings (optional). It is not required to specify the robot if only one robot or mechanism is available in the RoboDK station.
AddMillingProject
(name='Milling settings', itemrobot=0)¶Obsolete, use
AddMachiningProject()
instead
AddPoints
(points, reference_object=0, add_to_ref=False, projection_type=3)¶Adds a list of points to an object. The provided points must be a list of vertices. A vertex normal can be provided optionally.
- 参数
points (
robodk.Mat
(3xN matrix, or 6xN to provide point normals as ijk vectors)) -- list of points or matrixreference_object (
Item
) -- item to attach the newly added geometry (optional)add_to_ref (bool) -- If True, the points will be added as part of the object in the RoboDK item tree (a reference object must be provided)
projection_type (int) -- type of projection. Use the PROJECTION_* flags.
- 返回
added object/shape (0 if failed)
- 返回类型
The difference between ProjectPoints and AddPoints is that ProjectPoints does not add the points to the RoboDK station.
AddProgram
(name, itemrobot=0)¶Add a new program to the RoboDK station. Programs can be used to simulate a specific sequence, to generate vendor specific programs (Offline Programming) or to run programs on the robot (Online Programming). It returns the new
Item
created. Tip: Use the MoveRobotThroughLine.py macro to create programs in the RoboDK station (Option 2).- 参数
name (str) -- Name of the program
itemrobot (
Item
) -- Robot that will be used for this program. It is not required to specify the robot if the station has only one robot or mechanism.
- 返回
New program item
- 返回类型
参见
AddTarget()
,MoveJ()
,MoveL()
,setDO()
,waitDI()
,Pause()
,RunCodeCustom()
,RunInstruction()
,ShowInstructions()
,ShowTargets()
,Update()
Example 1 - Generic program with movements:
# Turn off rendering (faster) RDK.Render(False) prog = RDK.AddProgram('AutoProgram') # Hide program instructions (optional, but faster) prog.ShowInstructions(False) # Retrieve the current robot position: pose_ref = robot.Pose() # Iterate through a number of points for i in range(len(POINTS)): # add a new target ti = RDK.AddTarget('Auto Target %i' % (i+1)) # use the reference pose and update the XYZ position pose_ref.setPos(POINTS[i]) ti.setPose(pose_ref) # force to use the target as a Cartesian target (default) ti.setAsCartesianTarget() # Add the target as a Linear/Joint move in the new program prog.MoveL(ti) # Hide the target items from the tree: it each movement still keeps its own target. # Right click the movement instruction and select "Select Target" to see the target in the tree program.ShowTargets(False) # Turn rendering ON before starting the simulation (automatic if we are done) RDK.Render(True) #-------------------------------------- # Update the program path to display the yellow path in RoboDK. # Set collision checking ON or OFF check_collisions = COLLISION_OFF # Update the path (can take some time if collision checking is active) update_result = program.Update(check_collisions) # Retrieve the result n_insok = update_result[0] time = update_result[1] distance = update_result[2] percent_ok = update_result[3]*100 str_problems = update_result[4] if percent_ok < 100.0: msg_str = "WARNING! Problems with <strong>%s</strong> (%.1f):<br>%s" % (program_name, percent_ok, str_problems) else: msg_str = "No problems found for program %s" % program_name # Notify the user: print(msg_str) RDK.ShowMessage(msg_str)
Example 2 - Program flow, manage inputs/outputs and program calls:
# Add a pause (in miliseconds) program.Pause(1000) # pause motion 1 second # Stop the program so that it can be resumed # It provokes a STOP (pause until the operator desires to resume) program.Pause() # Add a program call or specific code in the program: program.RunInstruction('ChangeTool(2)',INSTRUCTION_CALL_PROGRAM) program.RunInstruction('ChangeTool(2);',INSTRUCTION_INSERT_CODE) # Set a digital output program.setDO('DO_NAME', 1) # Wait for a digital input: program.waitDI('DI_NAME', 1)
Example 3 - Add movements with external axes:
# Add a new movement involving external axes: # First: create a new target target = RDK.AddTarget("T1", reference) # Set the target as Cartesian (default) target.setAsCartesianTarget() # Specify the position of the external axes: external_axes = [10, 20] # The robot joints are calculated to reach the target # given the position of the external axes target.setJoints([0,0,0,0,0,0] + external_axes) # Specify the pose (position with respect to the reference frame): target.setPose(KUKA_2_Pose([x,y,z,w,p,r])) # Add a new movement instruction linked to that target: program.MoveJ(target)
Example 4 - Add a program call after each movement instruction inside a program:
from robolink import * # API to communicate with RoboDK from robodk import * # basic matrix operations RDK = Robolink() # Ask the user to select a program: prog = RDK.ItemUserPick("Select a Program to modify", ITEM_TYPE_PROGRAM) if not prog.Valid(): print("Operation cancelled or no programs available") quit() # Ask the user to enter a function call that will be added after each movement: print("Program selected: " + prog.Name()) ins_call = mbox("Enter a program call to add after each movement", entry="SynchRobot") if not ins_call: print("Operation cancelled") quit() # Iterate through all the instructions in a program: ins_id = 0 ins_count = prog.InstructionCount() while ins_id < ins_count: # Retrieve instruction ins_nom, ins_type, move_type, isjointtarget, pose, joints = prog.Instruction(ins_id) if ins_type == INS_TYPE_MOVE: # Select the movement instruction as a reference prog.InstructionSelect(ins_id) # Add a new program call prog.RunInstruction(ins_call, INSTRUCTION_CALL_PROGRAM) # Advance one additional instruction as we just added another instruction ins_id = ins_id + 1 ins_count = ins_count + 1 ins_id = ins_id + 1
More examples to generate programs directly from your script or move the robot directly from your program here: lbl-move-through-points. or the macro available in RoboDK/Library/Macros/MoveRobotThroughLine.py
AddShape
(triangle_points, add_to=0, override_shapes=False)¶Adds a shape provided triangle coordinates. Triangles must be provided as a list of vertices. A vertex normal can be provided optionally.
- 参数
triangle_points (
robodk.Mat
(3xN or 6xN matrix, N must be multiple of 3 because vertices must be stacked by groups of 3)) -- List of vertices grouped by triangles.parent (
Item
) -- item to attach the newly added geometry (optional)override_shapes (bool) -- Set to True to fill the object with a new shape
- 返回
added object/shape (0 if failed)
- 返回类型
AddStation
(name='New Station')¶Add a new empty station. It returns the station
Item
created.- 参数
name (str) -- name of the station
AddTarget
(name, itemparent=0, itemrobot=0)¶Add a new target that can be reached with a robot.
BuildMechanism
(type, list_obj, parameters, joints_build, joints_home, joints_senses, joints_lim_low, joints_lim_high, base=Matrix: (4, 4) Pose(0.000, 0.000, 0.000, 0.000, 0.000, 0.000): [[ 1, 0, 0, 0 ], [ 0, 1, 0, 0 ], [ 0, 0, 1, 0 ], [ 0, 0, 0, 1 ]] , tool=Matrix: (4, 4) Pose(0.000, 0.000, 0.000, 0.000, 0.000, 0.000): [[ 1, 0, 0, 0 ], [ 0, 1, 0, 0 ], [ 0, 0, 1, 0 ], [ 0, 0, 0, 1 ]] , name='New robot', robot=None)¶Create a new robot or mechanism.
- 参数
type (int) -- Type of the mechanism
list_obj (list) -- list of object items that build the robot
parameters (list) -- robot parameters in the same order as shown in the RoboDK menu: Utilities-Build Mechanism or robot
list_joints_build -- current state of the robot (joint axes) to build the robot
joints_home (list) -- joints for the home position (it can be changed later)
robot (
Item
) -- existing robot in the station to replace it (optional)name (str) -- robot name
CalibrateReference
(joints_points, method=0, use_joints=False, robot=None)¶Calibrate a reference frame given a number of points and following a specific algorithm/method. Important: Provide the list of joints to maximize accuracy for calibrated robots.
- 参数
joints_points (
Mat
or a list of list of float) -- List of points or a list of robot joints (matrix 3xN or nDOFsxN)method (int) -- method/algorithm to use to calculate the new TCP. Tip: use CALIBRATE_FRAME ...
use_joints (bool) -- use points or joint values (bool): Set to True if joints_points is a list of joints
robot (
Item
) -- the robot must be provided to calculate the reference frame by joints
- 返回
The pose of the reference frame with respect to the robot base frame
- 返回类型
CALIBRATE_FRAME_3P_P1_ON_X = 0 # Calibrate by 3 points: [X, X+, Y+] (p1 on X axis) CALIBRATE_FRAME_3P_P1_ORIGIN = 1 # Calibrate by 3 points: [Origin, X+, XY+] (p1 is origin) CALIBRATE_FRAME_6P = 2 # Calibrate by 6 points CALIBRATE_TURNTABLE = 3 # Calibrate turntable
CalibrateTool
(poses_xyzwpr, input_format=4, algorithm=0, robot=None, tool=None)¶Calibrate a TCP given a list of poses/joints and following a specific algorithm/method. Tip: Provide the list of joints instead of poses to maximize accuracy for calibrated robots.
- 参数
poses_xyzwpr (
Mat
or a list of list of float) -- List of points or a list of robot joints (matrix 3xN or nDOFsxN)input_format (int) -- Euler format. Optionally, use JOINT_FORMAT and provide the robot.
algorithm (int) -- method/algorithm to use to calculate the new TCP. Tip: use CALIBRATE_TCP ...
robot (
Item
) -- the robot must be provided to calculate the reference frame by jointstool (
Item
) -- provide a tool item to store the calibration data with that tool (the TCP is not updated, only the calibration joints)
- 返回
[TCP, stats, errors]
Out 1 (TCP) - the TCP as a list [x,y,z] with respect to the robot flange
Out 2 (stats) - Statistics as [mean, standard deviation, max] - error stats summary
Out 3 (errors) - errors for each pose (array 1xN)
CALIBRATE_TCP_BY_POINT # Take the same point using different orientations CALIBRATE_TCP_BY_PLANE # Take the same point on a plane
Cam2D_Add
(item_object, cam_params='')¶Open a simulated 2D camera view. Returns a handle pointer that can be used in case more than one simulated view is used. An example to use this option is available in the SetupCamera2D.py macro.
- 参数
item_object (
Item
) -- object to attach the cameracam_params (str) -- Camera parameters as a string. Add one or more of the following commands (in mm and degrees)
Example:
from robolink import * # API to communicate with RoboDK RDK = Robolink() # Close any open 2D camera views RDK.Cam2D_Close() # Retrieve the camera reference frame camref = RDK.ItemUserPick('Select a reference frame', ITEM_TYPE_FRAME) # set parameters in mm and degrees: # FOV: Field of view in degrees (atan(0.5*height/distance) of the sensor divided by # FOCAL_LENGHT: focal lenght in mm # FAR_LENGHT: maximum working distance (in mm) # SIZE: size of the sensor in pixels # DEPTH: Tag as depth to show the depth image in grey # BG_COLOR: background color (rgb color or named color: AARRGGBB) # LIGHT_AMBIENT: ambient color (rgb color or named color: AARRGGBB) # LIGHT_SPECULAR: specular color (rgb color or named color: AARRGGBB) # LIGHT_DIFFUSE: diffuse color (rgb color or named color: AARRGGBB) cam_id = RDK.Cam2D_Add(camref, 'FOCAL_LENGHT=6 FOV=32 FAR_LENGHT=1000 SIZE=640x480 BG_COLOR=black') cam_id = RDK.Cam2D_Add(camref, 'FOCAL_LENGHT=6 FOV=32 FAR_LENGHT=1000 SIZE=640x480') cam_id = RDK.Cam2D_Add(camref, 'FOCAL_LENGHT=6 FOV=32 FAR_LENGHT=1000 SIZE=640x480 BG_COLOR=black LIGHT_AMBIENT=red LIGHT_DIFFUSE=#FF00FF00 LIGHT_SPECULAR=black') cam_id = RDK.Cam2D_Add(camref, 'FOCAL_LENGHT=6 FOV=32 FAR_LENGHT=1000 SIZE=640x480 DEPTH') cam_id = RDK.Cam2D_Add(camref, 'FOCAL_LENGHT=6 FOV=32 FAR_LENGHT=1000 SIZE=640x480 BG_COLOR=black LIGHT_AMBIENT=red LIGHT_DIFFUSE=black LIGHT_SPECULAR=white')
Cam2D_Close
(cam_handle=0)¶Closes all camera windows or one specific camera if the camera handle is provided. Returns 1 if success, 0 otherwise.
- 参数
cam_handle (int) -- camera handle (pointer returned by Cam2D_Add). Leave to 0 to close all simulated views.
Cam2D_SetParams
(params, cam_handle=0)¶Set the parameters of the simulated camera. Returns 1 if success, 0 otherwise.
- 参数
params (str) -- parameter settings according to the parameters supported by Cam2D_Add
Cam2D_Snapshot
(file_save_img, cam_handle=0)¶Take a snapshot from a simulated camera view and save it to a file. Returns 1 if success, 0 otherwise.
- 参数
file_save_img (str) -- file path to save. Formats supported include PNG, JPEG, TIFF, ...
cam_handle (int) -- camera handle (pointer returned by Cam2D_Add)
CloseRoboDK
()¶Close RoboDK window and finish RoboDK's execution.
CloseStation
()¶Closes the current RoboDK station without suggesting to save
Collision
(item1, item2)¶Returns 1 if item1 and item2 collided. Otherwise returns 0.
CollisionItems
()¶Return the list of items that are in a collision state. This function can be used after calling Collisions() to retrieve the items that are in a collision state.
CollisionPairs
()¶Return the list of pairs of items that are in a collision state.
Collision_Line
(p1, p2, ref=Matrix: (4, 4) Pose(0.000, 0.000, 0.000, 0.000, 0.000, 0.000): [[ 1, 0, 0, 0 ], [ 0, 1, 0, 0 ], [ 0, 0, 1, 0 ], [ 0, 0, 0, 1 ]] )¶Checks the collision between a line and any objects in the station. The line is composed by 2 points.
- 参数
p1 (list of float [x,y,z]) -- start point of the line
p2 (list of float [x,y,z]) -- end point of the line
ref (
Mat
) -- Reference of the two points with respect to the absolute station reference.
- 返回
[collision (True or False), item (collided), point (point of collision with respect to the station)]
- 返回类型
[bool,
Item
, list of float as xyz]
Collisions
()¶Return the number of pairs of objects that are currently in a collision state.
Command
(cmd, value='')¶Send a special command. These commands are meant to have a specific effect in RoboDK, such as changing a specific setting or provoke specific events.
- 参数
command (str) -- Command Name, such as Trace, Threads or Window.
value (str) -- Comand value (optional, not all commands require a value)
from robolink import * RDK = Robolink() # Start the RoboDK API # How to change the number of threads using by the RoboDK application: RDK.Command("Threads", "4") # How to change the default behavior of 3D view using the mouse: RDK.Command("MouseClick_Left", "Select") # Set the left mouse click to select RDK.Command("MouseClick_Mid", "Pan") # Set the mid mouse click to Pan the 3D view RDK.Command("MouseClick_Right", "Rotate") # Set the right mouse click to Rotate the 3D view RDK.Command("MouseClick", "Default") # Set the default mouse 3D navigation settings # Provoke a resize event RDK.Command("Window", "Resize") # Reset the trace RDK.Command("Trace", "Reset")
Connect
()¶Establish a connection with RoboDK. If RoboDK is not running it will attempt to start RoboDK from the default installation path (otherwise APPLICATION_DIR must be set properly). If the connection succeeds it returns 1, otherwise it returns 0
Copy
(item)¶Makes a copy of an item (same as Ctrl+C), which can be pasted (Ctrl+V) using Paste().
- 参数
item (
Item
) -- Item to copy to the clipboard
Example:
RDK = Robolink() object = RDK.Item('My Object') object.Copy() # same as RDK.Copy(object) also works object_copy1 = RDK.Paste() object_copy1.setName('My Object (copy 1)') object_copy2 = RDK.Paste() object_copy2.setName('My Object (copy 2)')
CursorXYZ
(x_coord=-1, y_coord=-1)¶Returns the position of the cursor as XYZ coordinates (by default), or the 3D position of a given set of 2D coordinates of the window (x & y coordinates in pixels from the top left corner) The XYZ coordinates returned are given with respect to the RoboDK station (absolute reference). If no coordinates are provided, the current position of the cursor is retrieved.
- 参数
x_coord (int) -- X coordinate in pixels
y_coord (int) -- Y coordinate in pixels
RDK = Robolink() while True: xyz, item = RDK.CursorXYZ() print(str(item) + " " + str(xyz))
Disconnect
()¶Stops the communication with RoboDK. If setRunMode is set to RUNMODE_MAKE_ROBOTPROG for offline programming, any programs pending will be generated.
EmbedWindow
(window_name, docked_name=None, size_w=-1, size_h=-1, pid=0, area_add=1, area_allowed=15, timeout=500)¶Embed a window from a separate process in RoboDK as a docked window. Returns True if successful.
- 参数
window_name (str) -- The name of the window currently open. Make sure the window name is unique and it is a top level window
docked_name (str) -- Name of the docked tab in RoboDK (optional, if different from the window name)
pid (int) -- Process ID (optional)
area_add (int) -- Set to 1 (right) or 2 (left) (default is 1)
area_allowed (int) -- Areas allowed (default is 15:no constrain)
timeout (int) -- Timeout to abort attempting to embed the window
参见
Use the static function:
EmbedWindow()
(this function should usually be called on a separate thread)
Finish
()¶Stops the communication with RoboDK. If setRunMode is set to RUNMODE_MAKE_ROBOTPROG for offline programming, any programs pending will be generated.
HideRoboDK
()¶Hide the RoboDK window. RoboDK will keep running as a process
IsInside
(object_inside, object)¶Return 1 (True) if object_inside is inside the object, otherwise, it returns 0 (False). Both objects must be of type
Item
Item
(name, itemtype=None)¶Returns an item by its name. If there is no exact match it will return the last closest match. Specify what type of item you are looking for with itemtype. This is useful if 2 items have the same name but different type. (check variables ITEM_TYPE_*)
- 参数
name (str) -- name of the item (name of the item shown in the RoboDK station tree)
itemtype (int) -- type of the item to be retrieved (avoids confusion if there are similar name matches). Use ITEM_TYPE_*.
ITEM_TYPE_STATION=1 # station item (.rdk files) ITEM_TYPE_ROBOT=2 # robot item (.robot files) ITEM_TYPE_FRAME=3 # reference frame item ITEM_TYPE_TOOL=4 # tool item (.tool files or tools without geometry) ITEM_TYPE_OBJECT=5 # object item (.stl, .step, .iges, ...) ITEM_TYPE_TARGET=6 # target item ITEM_TYPE_PROGRAM=8 # program item (made using the GUI) ITEM_TYPE_PROGRAM_PYTHON=10 # Python program or macro
Example:
from robolink import * # import the robolink library RDK = Robolink() # connect to the RoboDK API (RoboDK starts if it has not started tool = RDK.Item('Tool') # Retrieve an item named tool robot = RDK.Item('', ITEM_TYPE_ROBOT) # the first available robot
ItemList
(filter=None, list_names=False)¶Returns a list of items (list of name or pointers) of all available items in the currently open station of RoboDK.
- 参数
filter (int) -- (optional) Filter the list by a specific item type (ITEM_TYPE_*). For example: RDK.ItemList(filter = ITEM_TYPE_ROBOT)
list_names (int) -- (optional) Set to True to return a list of names instead of a list of
Item
ItemUserPick
(message='Pick one item', itemtype=None)¶Shows a RoboDK popup to select one object from the open station. An item type can be specified to filter desired items. If no type is specified, all items are selectable. (check variables ITEM_TYPE_*) Example:
RDK.ItemUserPick("Pick a robot", ITEM_TYPE_ROBOT)
- 参数
message (str) -- message to display
itemtype (int) -- filter choices by a specific item type (ITEM_TYPE_*)
参见
Joints
(robot_item_list)¶Return the current joints of a list of robots.
参见
setJoints()
(item),Joints()
(item),setJoints()
LaserTracker_Measure
(estimate=[0, 0, 0], search=False)¶Takes a laser tracker measurement with respect to its own reference frame. If an estimate point is provided, the laser tracker will first move to those coordinates. If search is True, the tracker will search for a target. Returns the XYZ coordinates of target if it was found. Othewise it retuns None.
License
()¶Get the license string
MergeItems
(list_items=[])¶Merge multiple object items as one. Source objects are not deleted and a new object is created.
- 参数
list_items (list) -- List of items to set as selected
- 返回
New object created
- 返回类型
MoveC
(target1, target2, itemrobot, blocking=True)¶Performs a circular movement. Use robot.MoveC instead.
NewLink
()¶Reconnect the API using a different communication link.
Paste
(paste_to=0, paste_times=1)¶Paste the copied item as a dependency of another item (same as Ctrl+V). Paste should be used after Copy(). It returns the newly created item.
- 参数
paste_to (
Item
) -- Item to attach the copied item (optional)paste_times (int) -- number of times to paste the item (returns a list if greater than 1)
- 返回
New item created
- 返回类型
参见
PluginCommand
(plugin_name, plugin_command='', value='')¶Send a specific command to a RoboDK plugin. The command and value (optional) must be handled by your plugin. It returns the result as a string.
- 参数
plugin_name (str) -- The plugin name must match the PluginName() implementation in the RoboDK plugin.
command (str) -- Specific command handled by your plugin
value (str) -- Specific value (optional) handled by your plugin
PluginLoad
(plugin_name='', load=1)¶Load or unload the specified plugin (path to DLL, dylib or SO file). If the plugin is already loaded it will unload the plugin and reload it. Pass an empty plugin_name to reload all plugins.
- 参数
plugin_name (str) -- name of the plugin or path (if it is not in the default directory.
load (int) -- load the plugin (1/default) or unload (0)
RDK = Robolink() RDK.PluginLoad("C:/RoboDK/bin/plugin/yourplugin.dll")
Popup_ISO9283_CubeProgram
(robot=0)¶Popup the menu to create the ISO9283 cube program (Utilities-Create Cube ISO)
- 返回
Created program. The program is invalid.
- 返回类型
ProgramStart
(programname, folder='', postprocessor='', robot=None)¶Defines the name of the program when the program is generated (offline programming). It is also possible to specify the name of the post processor as well as the folder to save the program. This method must be called before any program output is generated (before any robot movement or other instruction).
- 参数
progname (str) -- Name of the program
folder (str) -- Folder to save the program, leave empty to use the default program folder (usually Desktop)
postprocessor (str) -- Name of the post processor. For example, to select the post processor C:/RoboDK/Posts/Fanuc_RJ3.py, specify "Fanuc_RJ3.py" or simply "Fanuc_RJ3".
robot (
Item
) -- Robot used for program generation
Example:
from robolink import * # import the robolink library RDK = Robolink() # connect to the RoboDK API (RoboDK starts if it has not started robot = RDK.Item('', ITEM_TYPE_ROBOT) # use the first available robot RDK.ProgramStart('Prog1','C:/MyProgramFolder/', "ABB_RAPID_IRC5", robot) # specify the program name for program generation # RDK.setRunMode(RUNMODE_MAKE_ROBOTPROG) # redundant robot.MoveJ(target) # make a simulation ... RDK.Finish() # Provokes the program generation (disconnects the API)
ProjectPoints
(points, object_project, projection_type=3)¶Project a point or a list of points given its coordinates. The provided points must be a list of [XYZ] coordinates. Optionally, a vertex normal can be provided [XYZijk]. It returns the projected points as a list of points (empty matrix if failed).
- 参数
points (list of points (XYZ or XYZijk list of floats), or
robodk.Mat
(3xN matrix, or 6xN to provide point normals as ijk vectors)) -- list of points to projectobject_project (
Item
) -- object to project the pointsprojection_type (int) -- Type of projection. For example: PROJECTION_ALONG_NORMAL_RECALC will project along the point normal and recalculate the normal vector on the surface projected.
The difference between ProjectPoints and AddPoints is that ProjectPoints does not add the points to the RoboDK station.
Render
(always_render=False)¶Display/render the scene: update the display. This function turns default rendering (rendering after any modification of the station unless always_render is set to true). Use Update to update the internal links of the complete station without rendering (when a robot or item has been moved).
- 参数
always_render (bool) -- Set to True to update the screen every time the station is modified (default behavior when Render() is not used).
参见
RunCode
(code, code_is_fcn_call=False)¶Generate a program call or a customized instruction output in a program. If code_is_fcn_call is set to True it has the same behavior as RDK.RunProgram(). In this case, when generating a program offline (offline programming), a function/procedure call will be generated in the program output (RoboDK will handle the syntax when the code is generated for a specific robot using the post processor). If the program exists it will also run the program in simulate mode.
- 参数
code (str) -- program name or code to generate
code_is_fcn_call (bool) -- Set to True if the provided code corresponds to a function call (same as RunProgram()), if so, RoboDK will handle the syntax when the code is generated for a specific robot.
Example to run an existing program in the RoboDK station:
from robolink import * # import the robolink library RDK = Robolink() # connect to the RoboDK API (RoboDK starts if it has not started RDK.RunCode("Prog1", True) # Run a program named Prog1 available in the RoboDK station
RunMessage
(message, message_is_comment=False)¶Show a message or a comment in the program generated offline (program generation). The message (or code) is displayed on the teach pendant of the robot.
- 参数
message (str) -- message or comment to display.
message_is_comment (bool) -- Set to True to generate a comment in the generated code instead of displaying a message on the teach pendant of the robot.
RunMode
()¶Return the current run mode (behavior) of the script. By default, robodk simulates any movements requested from the API (such as prog.MoveL) simulation for movement instructions (run_mode=RUNMODE_SIMULATE).
RunProgram
(fcn_param, wait_for_finished=False)¶Run a program (start a program). If the program exists in the RoboDK station it has the same behavior as right clicking a and selecting Run (or Run Python script for Python programs). When generating a program offline (Offline Programming), the program call will be generated in the program output (RoboDK will handle the syntax when the code is generated for a specific robot using the post processor).
- 参数
fcn_param (str) -- program name and parameters. Parameters can be provided for Python programs available in the RoboDK station as well.
wait_for_finished (bool) -- Set to True to block execution during a simulation until the program finishes (skipped if the program does not exist or when the program is generated)
参见
Save
(filename, itemsave=0)¶Save an item or a station to a file (formats supported include RDK, STL, ROBOT, TOOL, ...). If no item is provided, the open station is saved.
- 参数
filename (str) -- File path to save
itemsave (
Item
) -- Item to save (leave at 0 to save the current RoboDK station as an RDK file
ShowMessage
(message, popup=True)¶Show a message from the RoboDK window. By default, the message will be a blocking popup. Alternatively, it can be a message displayed at the bottom of RoboDK's main window.
- 参数
message (str) -- message to display
popup (bool) -- Set to False to display the message in the RoboDK's status bar (not blocking)
ShowRoboDK
()¶Show or raise the RoboDK window
ShowSequence
(matrix)¶Display a sequence of joints given a list of joints as a matrix. This function can also display a sequence of instructions (RoKiSim format).
- 参数
matrix (
Mat
) -- joint sequence as a 6xN matrix or instruction sequence as a 7xN matrix
Tip: use
InstructionList()
to retrieve the instruction list in RoKiSim format.
SimulationSpeed
()¶Return the simulation speed. A simulation speed of 1 means real-time simulation. A simulation speed of 5 (default) means that 1 second of simulation time equals to 5 seconds in a real application.
Spray_Add
(item_tool=0, item_object=0, params='', points=None, geometry=None)¶Add a simulated spray gun that allows projecting particles to a part. This is useful to simulate applications such as: arc welding, spot welding, 3D printing, painting or inspection to verify the trace. The SprayOn.py macro shows an example to use this option. It returns a pointer that can be used later for other operations, such as turning the spray ON or OFF.
- 参数
params (str) -- A string specifying the behavior of the simulated particles. The string can contain one or more of the following commands (separated by a space). See the allowed parameter options.
points (
Mat
) -- provide the volume as a list of points as described in the sample macro SprayOn.pygeometry (
Mat
) -- (optional) provide a list of points describing triangles to define a specific particle geometry. Use this option instead of the PARTICLE command.
STEP=AxB: Defines the grid to be projected 1x1 means only one line of particle projection (for example, for welding) PARTICLE: Defines the shape and size of particle (sphere or particle), unless a specific geometry is provided: a- SPHERE(radius, facets) b- SPHERE(radius, facets, scalex, scaley, scalez) b- CUBE(sizex, sizey, sizez) RAND=factor: Defines a random factor factor 0 means that the particles are not deposited randomly ELLYPSE: defines the volume as an ellypse (default) RECTANGLE: defines the volume as a rectangle PROJECT: project the particles to the surface (default) (for welding, painting or scanning) NO_PROJECT: does not project the particles to the surface (for example, for 3D printing)
Example:
tool = 0 # auto detect active tool obj = 0 # auto detect object in active reference frame options_command = "ELLYPSE PROJECT PARTICLE=SPHERE(4,8,1,1,0.5) STEP=8x8 RAND=2" # define the ellypse volume as p0, pA, pB, colorRGBA (close and far), in mm # coordinates must be provided with respect to the TCP close_p0 = [ 0, 0, -200] # xyz in mm: Center of the conical ellypse (side 1) close_pA = [ 5, 0, -200] # xyz in mm: First vertex of the conical ellypse (side 1) close_pB = [ 0, 10, -200] # xyz in mm: Second vertex of the conical ellypse (side 1) close_color = [ 1, 0, 0, 1] # RGBA (0-1) far_p0 = [ 0, 0, 50] # xyz in mm: Center of the conical ellypse (side 2) far_pA = [ 60, 0, 50] # xyz in mm: First vertex of the conical ellypse (side 2) far_pB = [ 0, 120, 50] # xyz in mm: Second vertex of the conical ellypse (side 2) far_color = [ 0, 0, 1, 0.2] # RGBA (0-1) close_param = close_p0 + close_pA + close_pB + close_color far_param = far_p0 + far_pA + far_pB + far_color volume = Mat([close_param, far_param]).tr() RDK.Spray_Add(tool, obj, options_command, volume) RDK.Spray_SetState(SPRAY_ON)
Spray_Clear
(id_spray=-1)¶Stops simulating a spray gun. This will clear the simulated particles.
- 参数
id_spray (int) -- spray handle (pointer returned by Spray_Add). Leave the default -1 to apply to all simulated sprays.
Spray_GetStats
(id_spray=-1)¶Gets statistics from all simulated spray guns or a specific spray gun.
- 参数
id_spray (int) -- spray handle (pointer returned by Spray_Add). Leave to -1 to apply to all simulated sprays.
Spray_SetState
(state=1, id_spray=-1)¶Sets the state of a simulated spray gun (ON or OFF)
- 参数
state (int) -- Set to ON or OFF. Use the defined constants: SPRAY_*
id_spray (int) -- spray handle (pointer returned by Spray_Add). Leave to -1 to apply to all simulated sprays.
StereoCamera_Measure
()¶Takes a measurement with the C-Track stereocamera. It returns two poses, the base reference frame and the measured object reference frame. Status is 0 if measurement succeeded.
Update
()¶Update the screen. This updates the position of all robots and internal links according to previously set values. This function is useful when Render is turned off (Example: "RDK.Render(False)"). Otherwise, by default RoboDK will update all links after any modification of the station (when robots or items are moved).
参见
Version
()¶Close RoboDK window and finish RoboDK's execution.
ViewPose
()¶Get the pose of the wold reference frame with respect to the view (camera/screen)
getFlagsItem
(item)¶Retrieve current item flags. Item flags allow defining how much access the user has to item-specific features. Use FLAG_ITEM_* flags to set one or more flags.
- 参数
item (
Item
) -- item to get flags
FLAG_ITEM_SELECTABLE = 1 # Allow selecting the item FLAG_ITEM_EDITABLE = 2 # Allow editing the item FLAG_ITEM_DRAGALLOWED = 4 # Allow dragging the item FLAG_ITEM_DROPALLOWED = 8 # Allow dropping nested items FLAG_ITEM_ENABLED = 32 # Enable this item in the tree FLAG_ITEM_NONE = 0 # Disable everything FLAG_ITEM_ALL = 64+32+8+4+2+1 # Enable everything
getOpenStations
()¶Returns the list of open stations in RoboDK
getParam
(param='PATH_OPENSTATION', str_type=True)¶Get a global or a station parameter from the open RoboDK station. Station parameters can also be modified manually by right clicking the station item and selecting "Station parameters"
- 参数
param (str) -- name of the parameter
str_type (bool) -- True to retrieve a string parameter (False for binary/bytes type)
- 返回
value of the parameter.
- 返回类型
str, float or None if the parameter is unknown
PATH_OPENSTATION # Full path of the current station (.rdk file) FILE_OPENSTATION # File name of the current station (name of the .rdk file) PATH_DESKTOP # Full path to the desktop folder
getParams
()¶Get all the user parameters from the open RoboDK station. Station parameters can also be modified manually by right clicking the station item and selecting "Station parameters" :return: list of pairs of strings :rtype: list of str
setActiveStation
(stn)¶Set the active station (project currently visible)
- 参数
stn (
Item
) -- station item, it can be previously loaded as an RDK file
setCollisionActive
(check_state=1)¶Set collision checking ON or OFF (COLLISION_ON/COLLISION_OFF) for a specific pair of objects (
Item
). This allows altering the collision map for Collision checking.
setCollisionActivePair
(check_state, item1, item2, id1=0, id2=0)¶Set collision checking ON or OFF (COLLISION_ON/COLLISION_OFF) for a specific pair of objects. Specify the link id for robots or moving mechanisms (id 0 is the base) Returns 1 if succeeded. Returns 0 if setting the pair failed (wrong id is provided)
setCollisionActivePairList
(list_check_state, list_item1, list_item2, list_id1=None, list_id2=None)¶Set collision checking ON or OFF (COLLISION_ON/COLLISION_OFF) for a specific list of pairs of objects. This allows altering the collision map for Collision checking. Specify the link id for robots or moving mechanisms (id 0 is the base).
参见
setCollisionActive()
,Collisions()
,setCollisionActivePair()
setFlagsItem
(item, flags=111)¶Update item flags. Item flags allow defining how much access the user has to item-specific features. Use FLAG_ITEM_* flags to set one or more flags.
- 参数
item (
Item
) -- item to set (set to 0 to apply to all items)flags (int) -- set the item flags (FLAG_ITEM_*)
setFlagsRoboDK
(flags=65535)¶Update the RoboDK flags. RoboDK flags allow defining how much access the user has to RoboDK features. Use a FLAG_ROBODK_* variables to set one or more flags.
- 参数
flags (int) -- state of the window (FLAG_ROBODK_*)
FLAG_ROBODK_TREE_ACTIVE = 1 # Enable the tree FLAG_ROBODK_3DVIEW_ACTIVE = 2 # Enable the 3D view (3D mouse navigation) FLAG_ROBODK_LEFT_CLICK = 4 # Enable left clicks FLAG_ROBODK_RIGHT_CLICK = 8 # Enable right clicks FLAG_ROBODK_DOUBLE_CLICK = 16 # Enable double clicks FLAG_ROBODK_MENU_ACTIVE = 32 # Enable the main menu (complete menu) FLAG_ROBODK_MENUFILE_ACTIVE = 64 # Enable the File menu FLAG_ROBODK_MENUEDIT_ACTIVE = 128 # Enable the Edit menu FLAG_ROBODK_MENUPROGRAM_ACTIVE = 256 # Enable the Program menu FLAG_ROBODK_MENUTOOLS_ACTIVE = 512 # Enable the Tools menu FLAG_ROBODK_MENUUTILITIES_ACTIVE = 1024 # Enable the Utilities menu FLAG_ROBODK_MENUCONNECT_ACTIVE = 2048 # Enable the Connect menu FLAG_ROBODK_WINDOWKEYS_ACTIVE = 4096 # Enable the keyboard FLAG_ROBODK_TREE_VISIBLE = 8192 # Make the station tree visible FLAG_ROBODK_REFERENCES_VISIBLE = 16384 # Make the reference frames visible FLAG_ROBODK_NONE = 0 # Disable everything FLAG_ROBODK_ALL = 0xFFFF # Enable everything FLAG_ROBODK_MENU_ACTIVE_ALL # Enable the menu only
setInteractiveMode
(mode_type=5, default_ref_flags=-1, custom_objects=None, custom_ref_flags=None)¶Set the interactive mode to define the behavior when navigating and selecting items in RoboDK's 3D view.
- 参数
mode_type (int) -- The mode type defines what accion occurs when the 3D view is selected (Select object, Pan, Rotate, Zoom, Move Objects, ...)
default_ref_flags (int) -- When a movement is specified, we can provide what motion we allow by default with respect to the coordinate system (set apropriate flags)
custom_objects (list) -- Provide a list of optional items to customize the move behavior for these specific items (important: the lenght of custom_ref_flags must match)
custom_ref_flags (list) -- Provide a matching list of flags to customize the movement behavior for specific items
setJoints
(robot_item_list, joints_list)¶Sets the current robot joints for a list of robot items and a list joints.
参见
setJoints()
(item),Joints()
(item),Joints()
setParam
(param, value)¶Set a station parameter. If the parameters exists, it will be updated. Otherwise, it will be added to the station.
- 参数
param (str) -- name of the parameter
value (str) -- value of the parameter (value type can be str or bytes)
setPoses
(items, poses)¶Sets the relative positions (poses) of a list of items with respect to their parent. For example, the position of an object/frame/target with respect to its parent. Use this function instead of setPose() for faster speed.
参见
setPose()
(item),Pose()
(item),setPosesAbs()
setPosesAbs
(items, poses)¶Set the absolute positions (poses) of a list of items with respect to the station reference. For example, the position of an object/frame/target with respect to its parent. Use this function instead of setPose() for faster speed.
参见
setPoseAbs()
(item),PoseAbs()
(item),setPoses()
setRunMode
(run_mode=1)¶Set the run mode (behavior) of the script, for either simulation, offline programming or online programming. By default, robodk shows the path simulation for movement instructions (run_mode=RUNMODE_SIMULATE).
RUNMODE_SIMULATE=1 # performs the simulation moving the robot (default) RUNMODE_QUICKVALIDATE=2 # performs a quick check to validate the robot movements RUNMODE_MAKE_ROBOTPROG=3 # makes the robot program RUNMODE_MAKE_ROBOTPROG_AND_UPLOAD=4 # makes the robot program and updates it to the robot RUNMODE_MAKE_ROBOTPROG_AND_START=5 # makes the robot program and starts it on the robot (independently from the PC) RUNMODE_RUN_ROBOT=6 # moves the real robot from the PC (PC is the client, the robot behaves like a server)
The following calls will alter the current run mode:
1-
Connect()
automatically sets RUNMODE_RUN_ROBOT. So it will use the robot driver together with the simulation.2-
ProgramStart()
automatically sets the mode to RUNMODE_MAKE_ROBOTPROG. So it will generate the program
setSelection
(list_items=[])¶Set the selection in the tree
- 参数
list_items (list) -- List of items to set as selected
setSimulationSpeed
(speed)¶Set the simulation speed. A simulation speed of 5 (default) means that 1 second of simulation time equals to 5 seconds in a real application. The slowest speed ratio allowed is 0.001. Set a large simmulation ratio (>100) for fast simulation results.
- 参数
speed (float) -- simulation ratio
setViewPose
(pose)¶Set the pose of the wold reference frame with respect to the view (camera/screen)
- 参数
pose (
Mat
) -- pose of the item with respect to its parent
setWindowState
(windowstate=2)¶Set the state of the RoboDK window
- 参数
windowstate (int) -- state of the window (WINDOWSTATE_*)
WINDOWSTATE_HIDDEN = -1 # Hidden WINDOWSTATE_SHOW = 0 # Visible WINDOWSTATE_MINIMIZED = 1 # Minimize window WINDOWSTATE_NORMAL = 2 # Show normal window (last known state) WINDOWSTATE_MAXIMIZED = 3 # Show maximized window WINDOWSTATE_FULLSCREEN = 4 # Show fulscreen window WINDOWSTATE_CINEMA = 5 # Show maximized window without the toolbar and without the menu WINDOWSTATE_FULLSCREEN_CINEMA= 6 # Show fulscreen window without the toolbar and without the menu
robolink.
getPathRoboDK
()¶RoboDK's executable/binary file