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 synchronize motion with another robot:    55     # Use the following digital output to signal the state of the robot:    58     # Use the following digital input to get the state of another robot:    61     if (get_standard_digital_out(DO_SYNC) == get_standard_digital_in(DI_SYNC)):    62       set_standard_digital_out(DO_SYNC, not (get_standard_digital_out(DI_SYNC)))    64       thread Thread_wait_1():    69       if (get_standard_digital_out(DO_SYNC) != get_standard_digital_in(DI_SYNC)):    70         global thread_handler_1=run Thread_wait_1()    71         while (get_standard_digital_out(DO_SYNC) != get_standard_digital_in(DI_SYNC)):    77       if (get_standard_digital_out(DO_SYNC) != get_standard_digital_in(DI_SYNC)):    78         set_standard_digital_out(DO_SYNC, not (get_standard_digital_out(DO_SYNC)))    83   # Example to drive a spray gun:    85     # use the value as an output:    88       set_standard_digital_out(DO_SPRAY, False)    90       set_standard_digital_out(DO_SPRAY, True)    94   # Example to move an external axis    96     # use the value as an output:   100       set_standard_digital_out(DO_AXIS_1, False)   102       # Wait for digital input to change state   103       #while (get_standard_digital_in(DI_AXIS_1) != False):   107       set_standard_digital_out(DO_AXIS_1, True)   109       # Wait for digital input to change state   110       #while (get_standard_digital_in(DI_AXIS_1) != True):   115   #--------------------------   132 SCRIPT_URP = 
'''<URProgram createdIn="3.0.0" lastSavedIn="3.0.0" name="%s" directory="/" installation="default">   134     <MainProgram runOnlyOnce="true" motionType="MoveJ" speed="1.0471975511965976" acceleration="1.3962634015954636" useActiveTCP="false">   139           <file resolves-to="file">%s</file>   148     """Get a safe program name"""   149     for c 
in r'-[]/\;,><&*:%=+@!#^()|?^':
   150         progname = progname.replace(c,
'')
   151     if len(progname) <= 0:
   153     if progname[0].isdigit():
   154         progname = 
'P' + progname    
   166 UR_GET_RUNTIME_MODE = 132*8-4
   168 RUNTIME_CANCELLED = 0
   172 RUNTIME_MODE_MSG = []
   173 RUNTIME_MODE_MSG.append(
"Operation cancelled") 
   174 RUNTIME_MODE_MSG.append(
"Ready") 
   175 RUNTIME_MODE_MSG.append(
"Running") 
   181     return struct.unpack_from(
"!i", buf, 0)[0]
   186     if len(buf) < msg_sz:
   187         print(
"Incorrect packet size %i vs %i" % (msg_sz, len(buf)))
   194     if len(buf) < offset+nval:
   195         print(
"Not available offset (maybe older Polyscope version?): %i - %i" % (len(buf), offset))
   198     for i 
in range(nval):
   200     return list(struct.unpack_from(format, buf, offset))    
   203 ROBOT_PROGRAM_ERROR = -1
   204 ROBOT_NOT_CONNECTED = 0
   208     print(
"POPUP: Connecting to robot...")
   210     robot_socket = socket.create_connection((robot_ip, 30002))
   211     print(
"POPUP: Sending program..")
   213     robot_socket.send(data)
   214     print(
"POPUP: Sending program...")
   217     received = robot_socket.recv(4096)
   226             idx_error = received.index(b
'error')
   231             idx_error_end = min(idx_error + 20, len(received))
   233                 idx_error_end = received.index(b
'\0',idx_error)
   236             print(
"POPUP: Robot response: <strong>" + received[idx_error:idx_error_end].decode(
"utf-8") + 
"</strong>")
   239             return ROBOT_PROGRAM_ERROR
   241             print(
"POPUP: Program sent. The program should be running on the robot.")
   245         print(
"POPUP: Robot connection problems...")
   248         return ROBOT_NOT_CONNECTED        
   252     RUNTIME_MODE_LAST = -1
   254         print(
"Connecting to robot %s:%i" % (robot_ip, 30003))
   255         rt_socket = socket.create_connection((robot_ip, 30003))
   259             more = rt_socket.recv(4096)
   264                     packet, buf = buf[:packet_len], buf[packet_len:]
   265                     RUNTIME_MODE = round(
UR_packet_value(packet, UR_GET_RUNTIME_MODE, 1)[0])
   266                     if RUNTIME_MODE_LAST != RUNTIME_MODE:
   267                         RUNTIME_MODE_LAST = RUNTIME_MODE
   268                         if RUNTIME_MODE < len(RUNTIME_MODE_MSG):
   269                             print(
"POPUP: Robot " + RUNTIME_MODE_MSG[RUNTIME_MODE] + 
" (transfer %.1f%% completed)" % percent_cmpl)
   272                             print(
"POPUP: Robot Status Unknown (%.i)" % RUNTIME_MODE + 
" (transfer %.1f%% completed)" % percent_cmpl)
   275                         if RUNTIME_MODE == RUNTIME_READY:
   286     """Calculate the p[x,y,z,rx,ry,rz] position for a pose target"""   287     def saturate_1(value):
   288         return min(max(value,-1.0),1.0)
   290     angle = 
acos(  saturate_1((pose[0,0]+pose[1,1]+pose[2,2]-1)/2)   )    
   291     rxyz = [pose[2,1]-pose[1,2], pose[0,2]-pose[2,0], pose[1,0]-pose[0,1]]
   297         rxyz = 
mult3(rxyz, angle)
   298     return [pose[0,3], pose[1,3], pose[2,3], rxyz[0], rxyz[1], rxyz[2]]
   301     """Prints a pose target"""   304     return (
'p[%.6f, %.6f, %.6f, %.6f, %.6f, %.6f]' % (x*MM_2_M,y*MM_2_M,z*MM_2_M,w,p,r))
   307     """Prints a joint target"""   308     njoints = len(angles)
   311         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))
   313         return 'this post only supports 6 joints'   319     radius = a*b*c/
sqrt(pow(a*a+b*b+c*c,2)-2*(pow(a,4)+pow(b,4)+pow(c,4)))            
   330     """Robot post object"""   331     MAX_LINES_X_PROG = 1000    
   337     BLEND_RADIUS_M = 0.001  
   339     MOVEC_MAX_RADIUS = 10000  
   347     ROBOT_NAME = 
'generic'   349     MAIN_PROGNAME = 
'unknown'   360     def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
   363         for k,v 
in kwargs.items():
   364             if k == 
'lines_x_prog':
   376             self.
addline(
'# Subprogram %s' % progname)   
   377             self.
addline(
'def %s():' % progname)
   384             self.
addline(
'# End of main program')
   389     def ProgSave(self, folder, progname, ask_user = False, show_result = False):
   391         progname = progname + 
'.script'   393             filesave = 
getSaveFile(folder, progname, 
'Save program as...')
   394             if filesave 
is not None:
   395                 filesave = filesave.name
   399             filesave = folder + 
'/' + progname
   403         fid = open(filesave, 
"w")
   408         fid.write(
'  # Global parameters:\n')
   410             fid.write(
'  ' + line+ 
'\n')            
   415         fid.write(DEFAULT_HEADER_SCRIPT)        
   420             fid.write(
'  ' + line + 
'\n')            
   424         fid.write(
'  # Main program:\n')
   427                 fid.write(
'  ' + line + 
'\n')
   434         print(
'SAVED: %s\n' % filesave) 
   438         filesave_urp = filesave[:-8]+
'.urp'   439         fid = open(filesave, 
"r")           440         prog_final = fid.read()   448         with gzip.open(filesave_urp, 
'wb') 
as fid_gz:
   449             fid_gz.write(self.
PROG_XML.encode(
'utf-8'))
   456             if type(show_result) 
is str:
   459                 p = subprocess.Popen([show_result, filesave])
   460             elif type(show_result) 
is list:
   462                 p = subprocess.Popen(show_result + [filesave])   
   466                 os.startfile(filesave)
   467             if len(self.
LOG) > 0:
   468                 mbox(
'Program generation LOG:\n\n' + self.
LOG)
   475         """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".   476         The connection parameters must be provided in the robot connection menu of RoboDK"""   481         for i 
in range(nprogs):
   487             send_str += (
'  # Global parameters:\n')
   489                 send_str += (
'  ' + line + 
'\n')            
   493             send_str += (DEFAULT_HEADER_SCRIPT)        
   497                 send_str += 
'  ' + line+ 
'\n'   501             send_str += (
'  # Main program:\n')
   504                 send_str += 
'  ' + line
   507             send_str += 
'end\n\n'   510             send_bytes = str.encode(send_str)
   514                 print(
"POPUP: Connect robot to run the program program...")
   522                 print(
"POPUP: Connect robot to transfer program...")
   528         blend_radius = 
'blend_radius_m';
   530         current_pos = pose_abs.Pos()
   536                 blend_radius = 
'%.3f' % (round(ratio_check*distance*0.001,3))
   540     def MoveJ(self, pose, joints, conf_RLF=None):
   541         """Add a joint movement"""   553             self.
addline(
'movej(%s,accel_radss,speed_rads,0,%s)' % (
angles_2_str(joints), blend_radius))
   555     def MoveL(self, pose, joints, conf_RLF=None):
   556         """Add a linear movement"""   571             self.
addline(
'movep(%s,accel_mss,speed_ms,%s)' % (target, blend_radius))
   576     def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
   577         """Add a circular movement"""               584             self.
MoveL(pose2, joints2, conf_RLF_2)
   588         print(
"MoveC Radius: " + str(radius) + 
" mm")           
   590             self.
MoveL(pose2, joints2, conf_RLF_2)
   594         blend_radius = 
'%.3f' % (0.001*radius) 
   600     def setFrame(self, pose, frame_id=None, frame_name=None):
   601         """Change the robot reference frame"""   608     def setTool(self, pose, tool_id=None, tool_name=None):
   609         """Change the robot TCP"""   615         """Pause the robot program"""   617             self.
addline(
'halt() # reimplement this function to force stop')
   619             self.
addline(
'sleep(%.3f)' % (time_ms*0.001))
   622         """Changes the robot speed (in mm/s)"""   623         if speed_mms < 999.9:
   631         """Changes the robot acceleration (in mm/s2)"""       636         """Changes the robot joint speed (in deg/s)"""   641         """Changes the robot joint acceleration (in deg/s2)"""   646         """Changes the zone data approach (makes the movement more smooth)"""   653         """Sets a variable (output) to a given value"""   654         if type(io_value) != str: 
   660         if type(io_var) != str:  
   661             newline = 
'set_standard_digital_out(%s, %s)' % (str(io_var), io_value)
   663             newline = 
'%s = %s' % (io_var, io_value)
   667     def waitDI(self, io_var, io_value, timeout_ms=-1):
   668         """Waits for an input io_var to attain a given value io_value. Optionally, a timeout can be provided."""   669         if type(io_var) != str:  
   670             io_var = 
'get_standard_digital_in(%s)' % str(io_var)        
   671         if type(io_value) != str: 
   679         self.
addline(
'while (%s != %s):' % (io_var, io_value))
   683     def RunCode(self, code, is_function_call = False):
   684         """Adds code or a function call"""   687             if code.lower() == 
"usemovel":
   691             elif code.lower() == 
"usemovep":
   695             elif code.lower().startswith(
"sync"):
   697                 code = 
"Synchronize()"   701             if not code.endswith(
')'):
   709         """Show a message on the controller screen"""   713             self.
addline(
'popup("%s","Message",False,False,blocking=True)' % message)
   719         self.
VARS.append(
'global speed_ms    = %.3f' % self.
SPEED_MS)
   726         if len(self.
PROG) > 1:
   734         """Add a program line"""   739             self.
PROG.append(self.
TAB + newline)
   744         """Add a log message"""   750     [x,y,z,r,p,w] = xyzrpw
   760     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]])
   763     """Test the post with a basic program"""   765     robot = 
RobotPost(
'Universal Robotics', 
'Generic UR robot')
   767     robot.ProgStart(
"Program")
   768     robot.RunMessage(
"Program generated by RoboDK", 
True)
   769     robot.setFrame(
Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
   770     robot.setTool(
Pose([62.5, -108.253175, 100, -60, 90, 0]))
   772     robot.setAcceleration(3000) 
   773     robot.MoveJ(
Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
   774     robot.MoveL(
Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
   775     robot.MoveL(
Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
   776     robot.RunMessage(
"Setting air valve 1 on")
   777     robot.RunCode(
"TCP_On", 
True)
   779     robot.MoveL(
Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
   780     robot.MoveL(
Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
   781     robot.MoveL(
Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
   782     robot.RunMessage(
"Setting air valve off")
   783     robot.RunCode(
"TCP_Off", 
True)
   785     robot.MoveL(
Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
   786     robot.MoveL(
Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
   787     robot.MoveL(
Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
   788     robot.ProgFinish(
"Program")
   790     for line 
in robot.PROG:
   792     if len(robot.LOG) > 0:
   793         mbox(
'Program generation LOG:\n\n' + robot.LOG)
   795     input(
"Press Enter to close...")
   797 if __name__ == 
"__main__":
   798     """Function to call when the module is executed by itself: test""" def ProgStart(self, progname)
def setAccelerationJoints(self, accel_degss)
def setAcceleration(self, accel_mmss)
def RunMessage(self, message, iscomment=False)
def setSpeed(self, speed_mms)
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
def MoveL(self, pose, joints, conf_RLF=None)
def RunCode(self, code, is_function_call=False)
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
def addlog(self, newline)
def circle_radius(p0, p1, p2)
def setSpeedJoints(self, speed_degs)
def get_safe_name(progname)
def ProgFinish(self, progname)
def setZoneData(self, zone_mm)
def blend_radius_check(self, pose_abs, ratio_check=0.4)
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
def UR_SendProgramRobot(robot_ip, data)
def addline(self, newline)
def UR_packet_value(buf, offset, nval=6)
def setDO(self, io_var, io_value)
def setFrame(self, pose, frame_id=None, frame_name=None)
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
def waitDI(self, io_var, io_value, timeout_ms=-1)
def UR_Wait_Ready(robot_ip, percent_cmpl)
def setTool(self, pose, tool_id=None, tool_name=None)
def MoveJ(self, pose, joints, conf_RLF=None)