43 DEFAULT_HEADER_SCRIPT =
""" 44 #-------------------------- 45 # Add any default subprograms here 46 # For example, to drive a gripper as a program call: 51 # Example to drive a spray gun: 53 # use the value as an output: 56 set_standard_digital_out(DO_SPRAY, False) 58 set_standard_digital_out(DO_SPRAY, True) 62 # Example to drive an extruder: 64 # use the value as an output: 72 # Example to move an external axis 74 # use the value as an output: 78 set_standard_digital_out(DO_AXIS_1, False) 80 # Wait for digital input to change state 81 #while (get_standard_digital_in(DI_AXIS_1) != False): 85 set_standard_digital_out(DO_AXIS_1, True) 87 # Wait for digital input to change state 88 #while (get_standard_digital_in(DI_AXIS_1) != True): 93 #-------------------------- 125 SCRIPT_URP =
'''<URProgram createdIn="3.0.0" lastSavedIn="3.0.0" name="%s" directory="." installation="default"> 127 <MainProgram runOnlyOnce="true" motionType="MoveJ" speed="1.0471975511965976" acceleration="1.3962634015954636" useActiveTCP="false"> 140 """Get a safe program name""" 141 for c
in r'-[]/\;,><&*:%=+@!#^|?^':
142 progname = progname.replace(c,
'')
143 if len(progname) <= 0:
145 if progname[0].isdigit():
146 progname =
'P' + progname
158 UR_GET_RUNTIME_MODE = 132*8-4
160 RUNTIME_CANCELLED = 0
164 RUNTIME_MODE_MSG = []
165 RUNTIME_MODE_MSG.append(
"Operation cancelled")
166 RUNTIME_MODE_MSG.append(
"Ready")
167 RUNTIME_MODE_MSG.append(
"Running")
173 return struct.unpack_from(
"!i", buf, 0)[0]
178 if len(buf) < msg_sz:
179 print(
"Incorrect packet size %i vs %i" % (msg_sz, len(buf)))
186 if len(buf) < offset+nval:
187 print(
"Not available offset (maybe older Polyscope version?): %i - %i" % (len(buf), offset))
190 for i
in range(nval):
192 return list(struct.unpack_from(format, buf, offset))
195 ROBOT_PROGRAM_ERROR = -1
196 ROBOT_NOT_CONNECTED = 0
202 idx_error = rec_bytes.index(b
'error')
207 idx_error_end = min(idx_error + 20, len(rec_bytes))
209 idx_error_end = rec_bytes.index(b
'\0',idx_error)
211 return "Unknown error" 212 return rec_bytes[idx_error:idx_error_end].decode(
"utf-8")
215 print(
"POPUP: Connecting to robot...")
217 robot_socket = socket.create_connection((robot_ip, 30002))
218 print(
"POPUP: Sending program..")
220 robot_socket.send(data)
221 print(
"POPUP: Sending program...")
224 received = robot_socket.recv(4096)
233 print(
"POPUP: Robot response: <strong>" + error_msg +
"</strong>")
236 return ROBOT_PROGRAM_ERROR
238 print(
"POPUP: Program sent. The program should be running on the robot.")
242 print(
"POPUP: Robot connection problems...")
245 return ROBOT_NOT_CONNECTED
249 RUNTIME_MODE_LAST = -1
251 print(
"Connecting to robot %s:%i" % (robot_ip, 30003))
252 rt_socket = socket.create_connection((robot_ip, 30003))
256 more = rt_socket.recv(4096)
261 packet, buf = buf[:packet_len], buf[packet_len:]
262 RUNTIME_MODE = round(
UR_packet_value(packet, UR_GET_RUNTIME_MODE, 1)[0])
263 if RUNTIME_MODE_LAST != RUNTIME_MODE:
264 RUNTIME_MODE_LAST = RUNTIME_MODE
265 if RUNTIME_MODE < len(RUNTIME_MODE_MSG):
266 print(
"POPUP: Robot " + RUNTIME_MODE_MSG[RUNTIME_MODE] +
" (transfer in progress, %.1f%% completed)" % percent_cmpl)
269 print(
"POPUP: Robot Status Unknown (%.i)" % RUNTIME_MODE +
" (transfer %.1f%% completed)" % percent_cmpl)
272 if RUNTIME_MODE == RUNTIME_READY:
283 """Calculate the p[x,y,z,rx,ry,rz] position for a pose target""" 284 def saturate_1(value):
285 return min(max(value,-1.0),1.0)
287 angle =
acos( saturate_1((pose[0,0]+pose[1,1]+pose[2,2]-1)/2) )
288 rxyz = [pose[2,1]-pose[1,2], pose[0,2]-pose[2,0], pose[1,0]-pose[0,1]]
294 rxyz =
mult3(rxyz, angle)
295 return [pose[0,3], pose[1,3], pose[2,3], rxyz[0], rxyz[1], rxyz[2]]
298 """Prints a pose target""" 301 return (
'p[%.6f, %.6f, %.6f, %.6f, %.6f, %.6f]' % (x*MM_2_M,y*MM_2_M,z*MM_2_M,w,p,r))
304 """Prints a joint target""" 305 njoints = len(angles)
308 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))
310 return 'this post only supports 6 joints' 316 radius = a*b*c/
sqrt(pow(a*a+b*b+c*c,2)-2*(pow(a,4)+pow(b,4)+pow(c,4)))
327 """Robot post object""" 328 MAX_LINES_X_PROG = 250
334 BLEND_RADIUS_M = 0.001
336 MOVEC_MAX_RADIUS = 10000
344 ROBOT_NAME =
'generic' 346 MAIN_PROGNAME =
'unknown' 357 def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
360 for k,v
in kwargs.items():
361 if k ==
'lines_x_prog':
373 self.
addline(
'# Subprogram %s' % progname)
374 self.
addline(
'def %s():' % progname)
381 self.
addline(
'# End of main program')
386 def ProgSave(self, folder, progname, ask_user = False, show_result = False):
388 progname = progname +
'.script' 390 filesave =
getSaveFile(folder, progname,
'Save program as...')
391 if filesave
is not None:
392 filesave = filesave.name
396 filesave = folder +
'/' + progname
400 fid = open(filesave,
"w")
405 fid.write(
' # Global parameters:\n')
407 fid.write(
' ' + line+
'\n')
412 fid.write(DEFAULT_HEADER_SCRIPT)
417 fid.write(
' ' + line +
'\n')
421 fid.write(
' # Main program:\n')
424 fid.write(
' ' + line +
'\n')
431 print(
'SAVED: %s\n' % filesave)
435 filesave_urp = filesave[:-7]
436 fid = open(filesave,
"r") 437 prog_final = fid.read() 441 from html
import escape
443 from cgi
import escape
445 prog_final_ok = escape(prog_final)
453 with gzip.open(filesave_urp,
'wb')
as fid_gz:
454 fid_gz.write(self.
PROG_XML.encode(
'utf-8'))
457 os.remove(filesave_urp+
'.urp')
461 os.rename(filesave_urp, filesave_urp+
'.urp')
468 if type(show_result)
is str:
471 p = subprocess.Popen([show_result, filesave])
472 elif type(show_result)
is list:
474 p = subprocess.Popen(show_result + [filesave])
477 os.startfile(filesave)
478 if len(self.
LOG) > 0:
479 mbox(
'Program generation LOG:\n\n' + self.
LOG)
486 """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". 487 The connection parameters must be provided in the robot connection menu of RoboDK""" 492 for i
in range(nprogs):
498 send_str += (
' # Global parameters:\n')
500 send_str += (
' ' + line +
'\n')
504 send_str += (DEFAULT_HEADER_SCRIPT)
508 send_str +=
' ' + line+
'\n' 512 send_str += (
' # Main program:\n')
515 send_str +=
' ' + line
518 send_str +=
'end\n\n' 521 send_bytes = str.encode(send_str)
525 print(
"POPUP: Connect robot to run the program program...")
533 while ROBOT_NOT_CONNECTED == status:
534 print(
"POPUP: Connect robot to transfer program...")
539 if status == ROBOT_PROGRAM_ERROR:
540 print(
"POPUP: Program Error. Running program from the computer Aborted.")
548 blend_radius =
'blend_radius_m';
550 current_pos = pose_abs.Pos()
556 blend_radius =
'%.3f' % (round(ratio_check*distance*0.001,3))
560 def MoveJ(self, pose, joints, conf_RLF=None):
561 """Add a joint movement""" 573 self.
addline(
'movej(%s,accel_radss,speed_rads,0,%s)' % (
angles_2_str(joints), blend_radius))
575 def MoveL(self, pose, joints, conf_RLF=None):
576 """Add a linear movement""" 591 self.
addline(
'movep(%s,accel_mss,speed_ms,%s)' % (target, blend_radius))
593 self.
addline(
'movel(%s,accel_mss,speed_ms,0,%s)' % (target, blend_radius))
596 def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
597 """Add a circular movement""" 604 self.
MoveL(pose2, joints2, conf_RLF_2)
608 print(
"MoveC Radius: " + str(radius) +
" mm")
610 self.
MoveL(pose2, joints2, conf_RLF_2)
620 def setFrame(self, pose, frame_id=None, frame_name=None):
621 """Change the robot reference frame""" 628 def setTool(self, pose, tool_id=None, tool_name=None):
629 """Change the robot TCP""" 635 """Pause the robot program""" 637 self.
addline(
'halt() # reimplement this function to force stop')
639 self.
addline(
'sleep(%.3f)' % (time_ms*0.001))
642 """Changes the robot speed (in mm/s)""" 651 """Changes the robot acceleration (in mm/s2)""" 656 """Changes the robot joint speed (in deg/s)""" 661 """Changes the robot joint acceleration (in deg/s2)""" 666 """Changes the zone data approach (makes the movement more smooth)""" 673 """Sets a variable (output) to a given value""" 674 if type(io_value) != str:
680 if type(io_var) != str:
681 newline =
'set_standard_digital_out(%s, %s)' % (str(io_var), io_value)
683 newline =
'%s = %s' % (io_var, io_value)
687 def waitDI(self, io_var, io_value, timeout_ms=-1):
688 """Waits for an input io_var to attain a given value io_value. Optionally, a timeout can be provided.""" 689 if type(io_var) != str:
690 io_var =
'get_standard_digital_in(%s)' % str(io_var)
691 if type(io_value) != str:
699 self.
addline(
'while (%s != %s):' % (io_var, io_value))
703 def RunCode(self, code, is_function_call = False):
704 """Adds code or a function call""" 707 if code.lower() ==
"usemovel":
710 elif code.lower() ==
"usemovep":
714 if not code.endswith(
')'):
722 """Show a message on the controller screen""" 726 self.
addline(
'popup("%s","Message",False,False,blocking=True)' % message)
732 self.
VARS.append(
'global speed_ms = %.3f' % self.
SPEED_MS)
739 if len(self.
PROG) > 1:
747 """Add a program line""" 752 self.
PROG.append(self.
TAB + newline)
757 """Add a log message""" 763 [x,y,z,r,p,w] = xyzrpw
773 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]])
776 """Test the post with a basic program""" 778 robot =
RobotPost(
'Universal Robotics',
'Generic UR robot')
780 robot.ProgStart(
"Program")
781 robot.RunMessage(
"Program generated by RoboDK",
True)
782 robot.setFrame(
Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
783 robot.setTool(
Pose([62.5, -108.253175, 100, -60, 90, 0]))
785 robot.setAcceleration(3000)
786 robot.MoveJ(
Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
787 robot.MoveL(
Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
788 robot.MoveL(
Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
789 robot.RunMessage(
"Setting air valve 1 on")
790 robot.RunCode(
"TCP_On",
True)
792 robot.MoveL(
Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
793 robot.MoveL(
Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
794 robot.MoveL(
Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
795 robot.RunMessage(
"Setting air valve off")
796 robot.RunCode(
"TCP_Off",
True)
798 robot.MoveL(
Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
799 robot.MoveL(
Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
800 robot.MoveL(
Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
801 robot.ProgFinish(
"Program")
803 for line
in robot.PROG:
805 if len(robot.LOG) > 0:
806 mbox(
'Program generation LOG:\n\n' + robot.LOG)
808 input(
"Press Enter to close...")
810 if __name__ ==
"__main__":
811 """Function to call when the module is executed by itself: test"""
def setAccelerationJoints(self, accel_degss)
def setZoneData(self, zone_mm)
def addline(self, newline)
def setSpeedJoints(self, speed_degs)
def UR_packet_value(buf, offset, nval=6)
def ProgFinish(self, progname)
def addlog(self, newline)
def get_safe_name(progname)
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
def MoveL(self, pose, joints, conf_RLF=None)
def setAcceleration(self, accel_mmss)
def ProgStart(self, progname)
def setFrame(self, pose, frame_id=None, frame_name=None)
def RunCode(self, code, is_function_call=False)
def setTool(self, pose, tool_id=None, tool_name=None)
def waitDI(self, io_var, io_value, timeout_ms=-1)
def UR_SendProgramRobot(robot_ip, data)
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
def GetErrorMsg(rec_bytes)
def MoveJ(self, pose, joints, conf_RLF=None)
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
def blend_radius_check(self, pose_abs, ratio_check=0.4)
def setSpeed(self, speed_mms)
def UR_Wait_Ready(robot_ip, percent_cmpl)
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
def RunMessage(self, message, iscomment=False)
def circle_radius(p0, p1, p2)
def setDO(self, io_var, io_value)
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)