48 XML_HEADER =
'''<?xml version="1.0" encoding="UTF-8"?> 50 <Condition ConditionType="Procedure_Program" ConditionAlias="Procedure_Program" ConditionUuid="%s"> 54 XML_CLOSING =
''' </Condition> 58 XML_MOVEJ =
''' <Condition ConditionType="Move" ConditionAlias="HOME" ConditionUuid="%s"> 60 <MoveConditionMode>MoveJoint</MoveConditionMode> 61 <ArrivalAheadThreshold>0</ArrivalAheadThreshold> 62 <ArrivalAheadType>None</ArrivalAheadType> 63 <EnableArrivalAhead>false</EnableArrivalAhead> 64 <EnableOffset>false</EnableOffset> 65 <JointAcc>%s,%s,%s,%s,%s,%s</JointAcc> 66 <JointSpeed>%s,%s,%s,%s,%s,%s</JointSpeed> 67 <OffsetCoordName></OffsetCoordName> 72 <Condition ConditionType="Waypoint" ConditionAlias="Waypoint" ConditionUuid="%s"> 74 <WaypointConditionMode>FixedPoint</WaypointConditionMode> 75 <FixedPoint>%s</FixedPoint> 80 XML_MOVEL =
''' <Condition ConditionType="Move" ConditionAlias="Move" ConditionUuid="%s"> 82 <MoveConditionMode>MoveJoint</MoveConditionMode> 83 <ArrivalAheadThreshold>0</ArrivalAheadThreshold> 84 <ArrivalAheadType>None</ArrivalAheadType> 85 <EnableArrivalAhead>false</EnableArrivalAhead> 86 <EnableOffset>false</EnableOffset> 87 <JointAcc>%s,%s,%s,%s,%s,%s</JointAcc> 88 <JointSpeed>%s,%s,%s,%s,%s,%s</JointSpeed> 89 <OffsetCoordName></OffsetCoordName> 94 <Condition ConditionType="Waypoint" ConditionAlias="Waypoint" ConditionUuid="%s"> 96 <WaypointConditionMode>FixedPoint</WaypointConditionMode> 97 <FixedPoint>%s</FixedPoint> 104 return str(uuid.uuid4()).replace(
'-',
'')
109 """Calculate the p[x,y,z,rx,ry,rz] position for a pose target""" 110 def saturate_1(value):
111 return min(max(value,-1.0),1.0)
113 angle =
acos( saturate_1((pose[0,0]+pose[1,1]+pose[2,2]-1)/2) )
114 rxyz = [pose[2,1]-pose[1,2], pose[0,2]-pose[2,0], pose[1,0]-pose[0,1]]
120 rxyz =
mult3(rxyz, angle)
121 return [pose[0,3], pose[1,3], pose[2,3], rxyz[0], rxyz[1], rxyz[2]]
124 """Prints a pose target""" 127 return (
'p[%.6f, %.6f, %.6f, %.6f, %.6f, %.6f]' % (x*M_2_MM,y*M_2_MM,z*M_2_MM,w,p,r))
130 """Prints a joint target""" 131 njoints = len(angles)
134 return (
'%.6f, %.6f, %.6f, %.6f, %.6f, %.6f' % (angles[0]*d2r, angles[1]*d2r, angles[2]*d2r, angles[3]*d2r, angles[4]*d2r, angles[5]*d2r))
136 return 'this post only supports 6 joints' 141 """Robot post object""" 148 SPEED_MS_CURR = SPEED_MS
149 SPEED_RADS_CURR = SPEED_RADS
150 ACCEL_MSS_CURR = ACCEL_MSS
151 ACCEL_RADSS_CURR = ACCEL_RADSS
153 BLEND_RADIUS_M = 0.001
159 ROBOT_NAME =
'generic' 161 MAIN_PROGNAME =
'unknown' 173 def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
183 self.
addline(
' # Subprogram %s' % progname)
184 self.
addline(
' def %s():' % progname)
190 self.
addline(
'--End of main program')
192 self.
addline(
'--End of main program')
196 def ProgSave(self, folder, progname, ask_user = False, show_result = False):
198 progname = progname +
'.' + self.
PROG_EXT 200 filesave =
getSaveFile(folder, progname,
'Save program as...')
201 if filesave
is not None:
202 filesave = filesave.name
206 filesave = folder +
'/' + progname
208 fid = open(filesave,
"w")
212 fid.write(
'--Main program:\n')
213 for line
in self.
PROG:
217 print(
'SAVED: %s\n' % filesave)
219 filesave_xml = filesave[:-4] +
'xml' 220 fid2 = open(filesave_xml,
"w")
221 fid2.write(XML_HEADER)
232 if type(show_result)
is str:
235 p = subprocess.Popen([show_result, filesave, filesave_xml])
239 os.startfile(filesave)
240 if len(self.
LOG) > 0:
241 mbox(
'Program generation LOG:\n\n' + self.
LOG)
244 """Send a program to the robot using the provided parameters. This method is executed right after ProgSave if we selected the option "Send Program to Robot". 245 The connection parameters must be provided in the robot connection menu of RoboDK""" 251 print(
"POPUP: Connecting to robot...")
253 robot_socket = socket.create_connection((robot_ip, 30002))
254 file_str = progfile.read()
255 print(
"POPUP: Sending program...")
257 robot_socket.send(file_str)
258 received = robot_socket.recv(4096)
260 print(
"POPUP: Program sent. The program should be running on the robot.")
263 print(
"POPUP: Program running")
266 print(
"POPUP: Problems running program...")
271 def MoveJ(self, pose, joints, conf_RLF=None):
272 """Add a joint movement""" 281 self.
addxml(XML_MOVEJ % (randid, aj, aj, aj, aj, aj, aj, sj, sj, sj, sj, sj, sj, randid2,
joints_2_str(joints)))
283 self.
addline(
'--(Logic tree item : Move) Move')
284 self.
addline(
'init_global_move_profile()')
287 self.
addline(
'set_joint_maxvelc({%f,%f,%f,%f,%f,%f})' % (j_vel,j_vel,j_vel,j_vel*121/101,j_vel*121/101,j_vel*121/101))
288 self.
addline(
'set_joint_maxacc({%f,%f,%f,%f,%f,%f})' % (j_acc,j_acc,j_acc,j_acc*121/101,j_acc*121/101,j_acc*121/101))
289 self.
addline(
' --(Logic tree item : Waypoint) Waypoint')
290 self.
addline(
' set_current_logic_tree_item("%s")' % randid2)
292 self.
addline(
' set_step_breakpoint()')
295 def MoveL(self, pose, joints, conf_RLF=None):
296 """Add a linear movement""" 310 self.
addxml(XML_MOVEL % (randid, al, al, al, al, al, al, sl, sl, sl, sl, sl, sl, randid2,
joints_2_str(joints)))
312 self.
addline(
'--(Logic tree item : Move) Move')
313 self.
addline(
'init_global_move_profile()')
316 self.
addline(
'set_end_maxvelc(%s)' % l_vel)
317 self.
addline(
'set_end_maxacc(%s)' % l_acc)
318 self.
addline(
' set_current_logic_tree_item("%s")' % randid2)
320 self.
addline(
' set_step_breakpoint()')
323 def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
324 """Add a circular movement""" 329 radius = a*b*c/
sqrt(pow(a*a+b*b+c*c,2)-2*(pow(a,4)+pow(b,4)+pow(c,4)))
332 def distance_p1_p02(p0,p1,p2):
335 return dot(v02,v01)/
dot(v02,v02)
341 self.
MoveL(pose2, joints2, conf_RLF_2)
345 if radius < 1
or radius > 100000:
346 self.
MoveL(pose2, joints2, conf_RLF_2)
349 d_p1_p02 = distance_p1_p02(p0, p1, p2)
351 self.
MoveL(pose2, joints2, conf_RLF_2)
357 def setFrame(self, pose, frame_id=None, frame_name=None):
358 """Change the robot reference frame""" 365 def setTool(self, pose, tool_id=None, tool_name=None):
366 """Change the robot TCP""" 370 """Pause the robot program""" 372 self.
addline(
'halt() # reimplement this function to force stop')
374 self.
addline(
'--(Logic tree item : Wait) Wait')
375 self.
addline(
'set_current_logic_tree_item("")')
376 self.
addline(
'sleep(%.3f)' % (time_ms*0.001))
377 self.
addline(
'set_step_breakpoint()')
380 """Changes the robot speed (in mm/s)""" 381 if speed_mms >= 2000:
386 """Changes the robot acceleration (in mm/s2)""" 387 if accel_mmss >= 2000:
392 """Changes the robot joint speed (in deg/s)""" 393 if speed_degs >= 150:
398 """Changes the robot joint acceleration (in deg/s2)""" 399 if accel_degss >= 991:
404 """Changes the zone data approach (makes the movement more smooth)""" 409 def RunCode(self, code, is_function_call = False):
410 """Adds code or a function call""" 412 code.replace(
' ',
'_')
413 if not code.endswith(
')'):
421 """Show a message on the controller screen""" 425 self.
addline(
'popup("%s","Message",False,False,blocking=True)' % message)
429 """Add a program line""" 431 self.
PROG.append(self.
TAB + newline +
'\n')
433 self.
SUBPROG.append(self.
TAB + newline +
'\n')
436 """Add a program line""" 438 self.
PROG_XML.append(newblock +
'\n')
440 raise Exception(
"This post does not support automatic program splitting")
443 """Add a log message""" 449 [x,y,z,r,p,w] = xyzrpw
459 return Mat([[cb*ca, ca*sc*sb - cc*sa, sc*sa + cc*ca*sb, x],[cb*sa, cc*ca + sc*sb*sa, cc*sb*sa - ca*sc, y],[-sb, cb*sc, cc*cb, z],[0,0,0,1]])
462 """Test the post with a basic program""" 464 robot =
RobotPost(
'Universal Robotics',
'Generic UR robot')
466 robot.ProgStart(
"Program")
467 robot.RunMessage(
"Program generated by RoboDK",
True)
468 robot.setFrame(
Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
469 robot.setTool(
Pose([62.5, -108.253175, 100, -60, 90, 0]))
471 robot.setAcceleration(3000)
472 robot.MoveJ(
Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
473 robot.MoveL(
Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
474 robot.MoveL(
Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
475 robot.RunMessage(
"Setting air valve 1 on")
476 robot.RunCode(
"TCP_On",
True)
478 robot.MoveL(
Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
479 robot.MoveL(
Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
480 robot.MoveL(
Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
481 robot.RunMessage(
"Setting air valve off")
482 robot.RunCode(
"TCP_Off",
True)
484 robot.MoveL(
Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
485 robot.MoveL(
Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
486 robot.MoveL(
Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
487 robot.ProgFinish(
"Program")
489 for line
in robot.PROG:
491 if len(robot.LOG) > 0:
492 mbox(
'Program generation LOG:\n\n' + robot.LOG)
494 input(
"Press Enter to close...")
496 if __name__ ==
"__main__":
497 """Function to call when the module is executed by itself: test"""
def MoveJ(self, pose, joints, conf_RLF=None)
def MoveL(self, pose, joints, conf_RLF=None)
def setSpeed(self, speed_mms)
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
def setFrame(self, pose, frame_id=None, frame_name=None)
def addline(self, newline)
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
def UploadFTP(program, robot_ip, remote_path, ftp_user, ftp_pass)
def ProgStart(self, progname)
def ProgFinish(self, progname)
def addlog(self, newline)
def RunMessage(self, message, iscomment=False)
def setAccelerationJoints(self, accel_degss)
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
def setSpeedJoints(self, speed_degs)
def addxml(self, newblock)
def setAcceleration(self, accel_mmss)
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
def setZoneData(self, zone_mm)
def RunCode(self, code, is_function_call=False)
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
def circle_radius(p0, p1, p2)
def setTool(self, pose, tool_id=None, tool_name=None)