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 synchronize 2    64     # Use the following digital output to signal the state of the robot:    67     # Use the following digital input to get the state of another robot:    70     if (get_standard_digital_out(DO_SYNC) == get_standard_digital_in(DI_SYNC)):    71       set_standard_digital_out(DO_SYNC, not (get_standard_digital_out(DI_SYNC)))    73       thread Thread_wait_1():    78       if (get_standard_digital_out(DO_SYNC) != get_standard_digital_in(DI_SYNC)):    79         global thread_handler_1=run Thread_wait_1()    80         while (get_standard_digital_out(DO_SYNC) != get_standard_digital_in(DI_SYNC)):    86       if (get_standard_digital_out(DO_SYNC) != get_standard_digital_in(DI_SYNC)):    87         set_standard_digital_out(DO_SYNC, not (get_standard_digital_out(DO_SYNC)))    93   # Example to move an external axis    95     # use the value as an output:    99       set_standard_digital_out(DO_AXIS_1, False)   101       # Wait for digital input to change state   102       #while (get_standard_digital_in(DI_AXIS_1) != False):   106       set_standard_digital_out(DO_AXIS_1, True)   108       # Wait for digital input to change state   109       #while (get_standard_digital_in(DI_AXIS_1) != True):   114   #--------------------------   146 SCRIPT_URP = 
'''<URProgram createdIn="3.0.0" lastSavedIn="3.0.0" name="%s" directory="." installation="default">   148     <MainProgram runOnlyOnce="true" motionType="MoveJ" speed="1.0471975511965976" acceleration="1.3962634015954636" useActiveTCP="false">   156     """Get a safe program name"""   157     for c 
in r'-[]/\;,><&*:%=+@!#^|?^':
   158         progname = progname.replace(c,
'')
   159     if len(progname) <= 0:
   161     if progname[0].isdigit():
   162         progname = 
'P' + progname    
   174 UR_GET_RUNTIME_MODE = 132*8-4
   176 RUNTIME_CANCELLED = 0
   180 RUNTIME_MODE_MSG = []
   181 RUNTIME_MODE_MSG.append(
"Operation cancelled") 
   182 RUNTIME_MODE_MSG.append(
"Ready") 
   183 RUNTIME_MODE_MSG.append(
"Running") 
   189     return struct.unpack_from(
"!i", buf, 0)[0]
   194     if len(buf) < msg_sz:
   195         print(
"Incorrect packet size %i vs %i" % (msg_sz, len(buf)))
   202     if len(buf) < offset+nval:
   203         print(
"Not available offset (maybe older Polyscope version?): %i - %i" % (len(buf), offset))
   206     for i 
in range(nval):
   208     return list(struct.unpack_from(format, buf, offset))    
   211 ROBOT_PROGRAM_ERROR = -1
   212 ROBOT_NOT_CONNECTED = 0
   216     print(
"POPUP: Connecting to robot...")
   218     robot_socket = socket.create_connection((robot_ip, 30002))
   219     print(
"POPUP: Sending program..")
   221     robot_socket.send(data)
   222     print(
"POPUP: Sending program...")
   225     received = robot_socket.recv(4096)
   234             idx_error = received.index(b
'error')
   239             idx_error_end = min(idx_error + 20, len(received))
   241                 idx_error_end = received.index(b
'\0',idx_error)
   244             print(
"POPUP: Robot response: <strong>" + received[idx_error:idx_error_end].decode(
"utf-8") + 
"</strong>")
   247             return ROBOT_PROGRAM_ERROR
   249             print(
"POPUP: Program sent. The program should be running on the robot.")
   253         print(
"POPUP: Robot connection problems...")
   256         return ROBOT_NOT_CONNECTED        
   260     RUNTIME_MODE_LAST = -1
   262         print(
"Connecting to robot %s:%i" % (robot_ip, 30003))
   263         rt_socket = socket.create_connection((robot_ip, 30003))
   267             more = rt_socket.recv(4096)
   272                     packet, buf = buf[:packet_len], buf[packet_len:]
   273                     RUNTIME_MODE = round(
UR_packet_value(packet, UR_GET_RUNTIME_MODE, 1)[0])
   274                     if RUNTIME_MODE_LAST != RUNTIME_MODE:
   275                         RUNTIME_MODE_LAST = RUNTIME_MODE
   276                         if RUNTIME_MODE < len(RUNTIME_MODE_MSG):
   277                             print(
"POPUP: Robot " + RUNTIME_MODE_MSG[RUNTIME_MODE] + 
" (transfer %.1f%% completed)" % percent_cmpl)
   280                             print(
"POPUP: Robot Status Unknown (%.i)" % RUNTIME_MODE + 
" (transfer %.1f%% completed)" % percent_cmpl)
   283                         if RUNTIME_MODE == RUNTIME_READY:
   297     """Calculate the p[x,y,z,rx,ry,rz] position for a pose target"""   298     def saturate_1(value):
   299         return min(max(value,-1.0),1.0)
   301     angle = 
acos(  saturate_1((pose[0,0]+pose[1,1]+pose[2,2]-1)/2)   )    
   302     rxyz = [pose[2,1]-pose[1,2], pose[0,2]-pose[2,0], pose[1,0]-pose[0,1]]
   308         rxyz = 
mult3(rxyz, angle)
   309     return [pose[0,3], pose[1,3], pose[2,3], rxyz[0], rxyz[1], rxyz[2]]
   312     """Prints a pose target"""   315     return (
'p[%.6f, %.6f, %.6f, %.6f, %.6f, %.6f]' % (x*MM_2_M,y*MM_2_M,z*MM_2_M,w,p,r))
   318     """Prints a joint target"""   319     njoints = len(angles)
   322         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))
   324         return 'this post only supports 6 joints'   330     radius = a*b*c/
sqrt(pow(a*a+b*b+c*c,2)-2*(pow(a,4)+pow(b,4)+pow(c,4)))            
   334     from html 
import escape  
   336     from cgi 
import escape  
   346     """Robot post object"""   347     MAX_LINES_X_PROG = 5000    
   354     BLEND_RADIUS_M = 0.001  
   356     MOVEC_MAX_RADIUS = 10000  
   366     ROBOT_NAME = 
'generic'   368     MAIN_PROGNAME = 
'unknown'   379     MotionParameters = 
'<motionParameters/>'   390     def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
   393         for k,v 
in kwargs.items():
   394             if k == 
'lines_x_prog':
   408             self.
addline(
'# Subprogram %s' % progname)   
   409             self.
addline(
'def %s():' % progname)
   417             self.
addline(
'# End of main program')
   422     def ProgSave(self, folder, progname, ask_user = False, show_result = False):
   424         progname = progname + 
'.script'   426             filesave = 
getSaveFile(folder, progname, 
'Save program as...')
   427             if filesave 
is not None:
   428                 filesave = filesave.name
   432             filesave = folder + 
'/' + progname
   436         fid = open(filesave, 
"w")
   441         fid.write(
'  # Global parameters:\n')
   443             fid.write(
'  ' + line+ 
'\n')            
   448         fid.write(DEFAULT_HEADER_SCRIPT)        
   453             fid.write(
'  ' + line + 
'\n')            
   457         fid.write(
'  # Main program:\n')
   460                 fid.write(
'  ' + line + 
'\n')
   467         print(
'SAVED: %s\n' % filesave) 
   471         filesave_urp = filesave[:-7] 
   479             urpxml += (
'        ' + line + 
'\n') 
   486         with gzip.open(filesave_urp, 
'wb') 
as fid_gz:
   487             fid_gz.write(self.
PROG_XML.encode(
'utf-8'))
   490             os.remove(filesave_urp+
'.urp')
   494         os.rename(filesave_urp, filesave_urp+
'.urp')
   501             if type(show_result) 
is str:
   504                 p = subprocess.Popen([show_result, filesave])
   505             elif type(show_result) 
is list:
   507                 p = subprocess.Popen(show_result + [filesave])   
   510                 os.startfile(filesave)
   511             if len(self.
LOG) > 0:
   512                 mbox(
'Program generation LOG:\n\n' + self.
LOG)
   519         """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".   520         The connection parameters must be provided in the robot connection menu of RoboDK"""   525             with pysftp.Connection(robot_ip, username=ftp_user, password=ftp_pass) 
as sftp:
   526                 with sftp.cd(remote_path):             
   536             for i 
in range(nprogs):
   542                 send_str += (
'  # Global parameters:\n')
   544                     send_str += (
'  ' + line + 
'\n')            
   548                 send_str += (DEFAULT_HEADER_SCRIPT)        
   552                     send_str += 
'  ' + line+ 
'\n'   556                 send_str += (
'  # Main program:\n')
   559                     send_str += 
'  ' + line
   562                 send_str += 
'end\n\n'   565                 send_bytes = str.encode(send_str)
   569                     print(
"POPUP: Connect robot to run the program program...")
   577                     print(
"POPUP: Connect robot to transfer program...")
   585         current_pos = pose_abs.Pos()
   591                 blend_radius = round(ratio_check*distance*0.001,3)
   595     def MoveJ(self, pose, joints, conf_RLF=None):
   596         """Add a joint movement"""   615             self.
add_urp_move(UR_MoveJ, pose, joints, conf_RLF, blend_radius)
   618     def MoveL(self, pose, joints, conf_RLF=None):
   619         """Add a linear movement"""   634             self.
addline(
'movep(%s,accel_mss,speed_ms,%.3f)' % (target, blend_radius))
   635             self.
add_urp_move(UR_MoveP, pose, joints, conf_RLF, blend_radius)
   637             self.
addline(
'movel(%s,accel_mss,speed_ms,0,%.3f)' % (target, blend_radius))
   638             self.
add_urp_move(UR_MoveL, pose, joints, conf_RLF, blend_radius)
   640     def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
   641         """Add a circular movement"""               648             self.
MoveL(pose2, joints2, conf_RLF_2)
   652         print(
"MoveC Radius: " + str(radius) + 
" mm")           
   654             self.
MoveL(pose2, joints2, conf_RLF_2)
   662         self.
RunMessage(
'Circular move (R%.1f mm)' % radius, 
True)
   671     def setFrame(self, pose, frame_id=None, frame_name=None):
   672         """Change the robot reference frame"""   680         self.
RunMessage(
'Using Ref. %s: %s' % (frame_name, ref_pose), 
True)
   681         self.
addline(
'# set_reference(%s)' % ref_pose)
   683     def setTool(self, pose, tool_id=None, tool_name=None):
   684         """Change the robot TCP"""   698         self.
RunMessage(
'Using TCP %s: %s' % (tool_name, tcp_pose), 
True)
   701         self.
RunCode(
'set_tcp(%s)' % tcp_pose)
   707         """Pause the robot program"""   709             self.
addline(
'halt() # reimplement this function to force stop')
   714             self.
addline(
'sleep(%.3f)' % (time_ms*0.001))
   717             self.
add_urp(
'<Wait type="Sleep">')
   718             self.
add_urp(
'  <waitTime>%.3f</waitTime>' % (time_ms*0.001))
   722         """Changes the robot speed (in mm/s)"""   733         """Changes the robot acceleration (in mm/s2)"""       739         """Changes the robot joint speed (in deg/s)"""   745         """Changes the robot joint acceleration (in deg/s2)"""   751         """Changes the zone data approach (makes the movement more smooth)"""   758         """Sets a variable (output) to a given value"""   760         io_value_urp = io_value
   762         if type(io_value) != str: 
   770         if type(io_var) != str:  
   771             io_var_urp = 
'digital_out[%s]' % str(io_var)
   772             newline = 
'set_standard_digital_out(%s, %s)' % (str(io_var), io_value)
   774             newline = 
'%s = %s' % (io_var, io_value)
   779         self.
add_urp(
'<Set type="DigitalOutput">')
   780         self.
add_urp(
'  <pin referencedName="%s"/>' % io_var_urp)
   781         self.
add_urp(
'  <digitalValue>%s</digitalValue>' % io_value_urp)
   784     def waitDI(self, io_var, io_value, timeout_ms=-1):
   785         """Waits for an input io_var to attain a given value io_value. Optionally, a timeout can be provided."""   787         io_value_urp = io_value
   789         if type(io_var) != str:  
   790             io_var = 
'get_standard_digital_in(%s)' % str(io_var)    
   791             io_var_urp = 
'digital_in[%s]' % str(io_var)
   793         if type(io_value) != str: 
   803         self.
addline(
'while (%s != %s):' % (io_var, io_value))
   808         self.
add_urp(
'<Wait type="DigitalInput">')
   809         self.
add_urp(
'  <pin referencedName="%s"/>' % io_var_urp)
   810         self.
add_urp(
'  <digitalValue>%s</digitalValue>' % io_value_urp)
   813     def RunCode(self, code, is_function_call = False):
   814         """Adds code or a function call"""   817             if code.lower() == 
"usemovel":
   821             elif code.lower() == 
"usemovep":
   825             if not code.endswith(
')'):
   830             progname = code.split(
'(')[0]
   835                 self.
add_urp(
'<CallSubProgram>')
   836                 self.
add_urp(
'  <subprogram name="%s" keepHidden="true" keepSynchronizedWithDisk="true" trackProgramExecution="false">' % progname)
   837                 self.
add_urp(
'    <programFile resolves-to="file">../programs/%s.urp</programFile>' % progname)
   841                 self.
add_urp(
'</CallSubProgram>')
   848                 self.
FOOTER_URP += 
'  <SubProgram reference="../MainProgram/children/CallSubProgram%s/subprogram"/>\n' % str_count            
   855                     str_subprog = 
'[%i]' % (id_subprog)
   857                 print(
'ID: ' + str(id_subprog))
   860                 self.
add_urp(
'<CallSubProgram>')
   861                 self.
add_urp(
'  <subprogram reference="../../CallSubProgram%s/subprogram"/>' % str_subprog)
   862                 self.
add_urp(
'</CallSubProgram>')
   869             self.
add_urp(
'<Script type="Line">')
   872                 self.
add_urp(
'    <ExpressionChar character="%s"/>' % escape(c))
   877         """Show a message on the controller screen"""   882             self.
add_urp(
'<Comment comment="%s"/>' % escape(message))            
   884             self.
addline(
'popup("%s","Message",False,False,blocking=True)' % message)
   887             self.
add_urp(
'<Popup type="Message" haltProgram="false" message="%s"/>' % escape(message))
   893         self.
VARS.append(
'global speed_ms    = %.3f' % self.
SPEED_MS)
   900         if len(self.
PROG) > 1:
   908         """Add a program line"""   913             self.
PROG.append(self.
TAB + newline)
   918         """Add a program line"""   938     def add_urp_move(self, movetype, pose, joints, conf_RLF, blend_radius):
   943             if movetype == UR_MoveJ:
   946             elif movetype == UR_MoveL:
   947                 self.
add_urp(
'<Move motionType="MoveL" speed="%.3f" acceleration="%.3f" useActiveTCP="false">' % (self.
SPEED_MS, self.
ACCEL_MSS))
   949             elif movetype == UR_MoveP:
   979             poseabsflange_str = 
pose_2_str(poseabsflange)[2:-1]            
   980             self.
add_urp(
'      <position joints="%s" pose="%s"/>' % (
angles_2_str(joints)[1:-1], poseabs_str))
   981             self.
add_urp(
'      <poseInFeatureCoordinates pose="%s"/>' % poseabs_str)
   982             self.
add_urp(
'      <outputFlangePose pose="%s"/>' % poseabsflange_str)
   992         """Add a log message"""   998     [x,y,z,r,p,w] = xyzrpw
  1008     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]])
  1011     """Test the post with a basic program"""  1013     robot = 
RobotPost(
'Universal Robotics', 
'Generic UR robot')
  1015     robot.ProgStart(
"Program")
  1016     robot.RunMessage(
"Program generated by RoboDK", 
True)
  1017     robot.setFrame(
Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
  1018     robot.setTool(
Pose([62.5, -108.253175, 100, -60, 90, 0]))
  1020     robot.setAcceleration(3000) 
  1021     robot.MoveJ(
Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
  1022     robot.MoveL(
Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
  1023     robot.MoveL(
Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
  1024     robot.RunMessage(
"Setting air valve 1 on")
  1025     robot.RunCode(
"TCP_On", 
True)
  1027     robot.MoveL(
Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
  1028     robot.MoveL(
Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
  1029     robot.MoveL(
Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
  1030     robot.RunMessage(
"Setting air valve off")
  1031     robot.RunCode(
"TCP_Off", 
True)
  1033     robot.MoveL(
Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
  1034     robot.MoveL(
Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
  1035     robot.MoveL(
Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
  1036     robot.ProgFinish(
"Program")
  1038     for line 
in robot.PROG:
  1044     for line 
in robot.PROG_URP:
  1046     if len(robot.LOG) > 0:
  1047         mbox(
'Program generation LOG:\n\n' + robot.LOG)
  1049     input(
"Press Enter to close...")
  1051 if __name__ == 
"__main__":
  1052     """Function to call when the module is executed by itself: test""" 
def setSpeed(self, speed_mms)
def UR_SendProgramRobot(robot_ip, data)
def setFrame(self, pose, frame_id=None, frame_name=None)
def waitDI(self, io_var, io_value, timeout_ms=-1)
def update_MotionParameters(self)
def addline(self, newline)
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
def add_urp(self, newline)
def UR_packet_value(buf, offset, nval=6)
def UR_Wait_Ready(robot_ip, percent_cmpl)
def setAcceleration(self, accel_mmss)
def blend_radius_check(self, pose_abs, ratio_check=0.5)
def get_safe_name(progname)
def RunMessage(self, message, iscomment=False)
def setTool(self, pose, tool_id=None, tool_name=None)
def MoveJ(self, pose, joints, conf_RLF=None)
def addlog(self, newline)
def circle_radius(p0, p1, p2)
def add_urp_move(self, movetype, pose, joints, conf_RLF, blend_radius)
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
def setZoneData(self, zone_mm)
def setDO(self, io_var, io_value)
def ProgStart(self, progname)
def ProgFinish(self, progname)
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
def MoveL(self, pose, joints, conf_RLF=None)
def setSpeedJoints(self, speed_degs)
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
def setAccelerationJoints(self, accel_degss)
def RunCode(self, code, is_function_call=False)