Universal_Robots_SCRIPT.py
Go to the documentation of this file.
1 # Copyright 2017 - RoboDK Software S.L. - http://www.robodk.com/
2 # Licensed under the Apache License, Version 2.0 (the "License");
3 # you may not use this file except in compliance with the License.
4 # You may obtain a copy of the License at
5 # http://www.apache.org/licenses/LICENSE-2.0
6 # Unless required by applicable law or agreed to in writing, software
7 # distributed under the License is distributed on an "AS IS" BASIS,
8 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
9 # See the License for the specific language governing permissions and
10 # limitations under the License.
11 
12 # ----------------------------------------------------
13 # This file is a POST PROCESSOR for Robot Offline Programming to generate programs
14 # for a Universal Robot with RoboDK
15 #
16 # To edit/test this POST PROCESSOR script file:
17 # Select "Program"->"Add/Edit Post Processor", then select your post or create a new one.
18 # You can edit this file using any text editor or Python editor. Using a Python editor allows to quickly evaluate a sample program at the end of this file.
19 # Python should be automatically installed with RoboDK
20 #
21 # You can also edit the POST PROCESSOR manually:
22 # 1- Open the *.py file with Python IDLE (right click -> Edit with IDLE)
23 # 2- Make the necessary changes
24 # 3- Run the file to open Python Shell: Run -> Run module (F5 by default)
25 # 4- The "test_post()" function is called automatically
26 # Alternatively, you can edit this file using a text editor and run it with Python
27 #
28 # To use a POST PROCESSOR file you must place the *.py file in "C:/RoboDK/Posts/"
29 # To select one POST PROCESSOR for your robot in RoboDK you must follow these steps:
30 # 1- Open the robot panel (double click a robot)
31 # 2- Select "Parameters"
32 # 3- Select "Unlock advanced options"
33 # 4- Select your post as the file name in the "Robot brand" box
34 #
35 # To delete an existing POST PROCESSOR script, simply delete this file (.py file)
36 #
37 # ----------------------------------------------------
38 # More information about RoboDK Post Processors and Offline Programming here:
39 # http://www.robodk.com/help#PostProcessor
40 # http://www.robodk.com/doc/en/PythonAPI/postprocessor.html
41 # ----------------------------------------------------
42 
43 
44 SCRIPT_URP = '''<URProgram createdIn="3.0.0" lastSavedIn="3.0.0" name="%s" directory="/" installation="default">
45  <children>
46  <MainProgram runOnlyOnce="false" motionType="MoveJ" speed="1.0471975511965976" acceleration="1.3962634015954636" useActiveTCP="false">
47  <children>
48  <Script type="File">
49  <cachedContents>%s
50 </cachedContents>
51  <file resolves-to="file">%s</file>
52  </Script>
53  </children>
54  </MainProgram>
55  </children>
56 </URProgram>'''
57 
58 
59 def get_safe_name(progname):
60  """Get a safe program name"""
61  for c in r'-[]/\;,><&*:%=+@!#^()|?^':
62  progname = progname.replace(c,'')
63  if len(progname) <= 0:
64  progname = 'Program'
65  if progname[0].isdigit():
66  progname = 'P' + progname
67  return progname
68 
69 
70 # ----------------------------------------------------
71 # Import RoboDK tools
72 from robodk import *
73 
74 # ----------------------------------------------------
75 
76 def pose_2_ur(pose):
77  """Calculate the p[x,y,z,rx,ry,rz] position for a pose target"""
78  def saturate_1(value):
79  return min(max(value,-1.0),1.0)
80 
81  angle = acos( saturate_1((pose[0,0]+pose[1,1]+pose[2,2]-1)/2) )
82  rxyz = [pose[2,1]-pose[1,2], pose[0,2]-pose[2,0], pose[1,0]-pose[0,1]]
83 
84  if angle == 0:
85  rxyz = [0,0,0]
86  else:
87  rxyz = normalize3(rxyz)
88  rxyz = mult3(rxyz, angle)
89  return [pose[0,3], pose[1,3], pose[2,3], rxyz[0], rxyz[1], rxyz[2]]
90 
91 def pose_2_str(pose):
92  """Prints a pose target"""
93  [x,y,z,w,p,r] = pose_2_ur(pose)
94  MM_2_M = 0.001
95  return ('p[%.6f, %.6f, %.6f, %.6f, %.6f, %.6f]' % (x*MM_2_M,y*MM_2_M,z*MM_2_M,w,p,r))
96 
97 def angles_2_str(angles):
98  """Prints a joint target"""
99  njoints = len(angles)
100  d2r = pi/180.0
101  if njoints == 6:
102  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))
103  else:
104  return 'this post only supports 6 joints'
105 
106 # ----------------------------------------------------
107 # Object class that handles the robot instructions/syntax
108 class RobotPost(object):
109  """Robot post object"""
110  PROG_EXT = 'script' # set the program extension
111  SPEED_MS = 0.3 # default speed for linear moves in m/s
112  SPEED_RADS = 0.75 # default speed for joint moves in rad/s
113  ACCEL_MSS = 3 # default acceleration for lineaer moves in m/ss
114  ACCEL_RADSS = 1.2 # default acceleration for joint moves in rad/ss
115  BLEND_RADIUS_M = 0.001 # default blend radius in meters (corners smoothing)
116  REF_FRAME = eye(4) # default reference frame (the robot reference frame)
117  LAST_POS = None # last XYZ position
118 
119  # other variables
120  ROBOT_POST = 'unset'
121  ROBOT_NAME = 'generic'
122  PROG_FILES = []
123  MAIN_PROGNAME = 'unknown'
124 
125  nPROGS = 0
126  PROG = []
127  SUBPROG = []
128  TAB = ''
129  LOG = ''
130 
131  def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
132  self.ROBOT_POST = robotpost
133  self.ROBOT_NAME = robotname
134 
135  def ProgStart(self, progname):
136  progname = get_safe_name(progname)
137  self.nPROGS = self.nPROGS + 1
138  if self.nPROGS <= 1:
139  self.TAB = ' '
140  self.MAIN_PROGNAME = progname
141  else:
142  self.addline(' # Subprogram %s' % progname)
143  self.addline(' def %s():' % progname)
144  self.TAB = ' '
145 
146  def ProgFinish(self, progname):
147  progname = get_safe_name(progname)
148  self.TAB = ''
149  if self.nPROGS <= 1:
150  self.addline(' # End of main program')
151  self.addline('end')
152  else:
153  self.addline(' end')
154 
155  self.addline('')
156 
157  def ProgSave(self, folder, progname, ask_user = False, show_result = False):
158  progname = get_safe_name(progname)
159  self.PROG.append('%s()' % self.MAIN_PROGNAME)
160  progname = progname + '.' + self.PROG_EXT
161  if ask_user or not DirExists(folder):
162  filesave = getSaveFile(folder, progname, 'Save program as...')
163  if filesave is not None:
164  filesave = filesave.name
165  else:
166  return
167  else:
168  filesave = folder + '/' + progname
169 
170  fid = open(filesave, "w")
171  fid.write('def %s():\n' % self.MAIN_PROGNAME)
172  fid.write(' # Default parameters:\n')
173  fid.write(' global speed_ms = %.3f\n' % self.SPEED_MS)
174  fid.write(' global speed_rads = %.3f\n' % self.SPEED_RADS)
175  fid.write(' global accel_mss = %.3f\n' % self.ACCEL_MSS)
176  fid.write(' global accel_radss = %.3f\n' % self.ACCEL_RADSS)
177  fid.write(' global blend_radius_m = %.3f\n' % self.BLEND_RADIUS_M)
178  fid.write(' \n')
179  fid.write(' # Add any suprograms here\n')
180  for line in self.SUBPROG:
181  fid.write(line)
182 
183  fid.write(' # Main program:\n')
184  for line in self.PROG:
185  fid.write(line)
186 
187  fid.close()
188  print('SAVED: %s\n' % filesave) # tell RoboDK the path of the saved file
189  self.PROG_FILES = filesave
190 
191  #---------------------------- SAVE URP (GZIP compressed XML file)-------------------------
192  #filesave_urp = filesave[:-8]+'.urp'
193  #fid = open(filesave, "r")
194  #prog_final = fid.read()
195  #fid.close()
196  #self.PROG_XML = SCRIPT_URP % (self.MAIN_PROGNAME, prog_final, self.MAIN_PROGNAME+'.script')
197  #
198 
207 
208  # open file with default application
209  if show_result:
210  if type(show_result) is str:
211  # Open file with provided application
212  import subprocess
213  p = subprocess.Popen([show_result, filesave])
214  elif type(show_result) is list:
215  import subprocess
216  p = subprocess.Popen(show_result + [filesave])
217  else:
218  # open file with default application
219  import os
220  os.startfile(filesave)
221  if len(self.LOG) > 0:
222  mbox('Program generation LOG:\n\n' + self.LOG)
223 
224  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
225  """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".
226  The connection parameters must be provided in the robot connection menu of RoboDK"""
227  #UploadFTP(self.PROG_FILES, robot_ip, remote_path, ftp_user, ftp_pass)
228  #return
229 
230  with open(self.PROG_FILES, 'rb') as progfile:
231  import socket
232  print("POPUP: Connecting to robot...")
233  sys.stdout.flush()
234  robot_socket = socket.create_connection((robot_ip, 30002))
235  print("POPUP: Sending program")
236  sys.stdout.flush()
237  robot_socket.send(progfile.read())
238  print("POPUP: Sending program...")
239  sys.stdout.flush()
240  pause(1)
241  received = robot_socket.recv(4096)
242  robot_socket.close()
243 
244  if received:
245  #print("POPUP: Program running")
246  print(str(received))
247  sys.stdout.flush()
248  idx_error = -1
249  try:
250  idx_error = received.index(b'error')
251  except:
252  pass
253  if idx_error >= 0:
254  idx_error_end = min(idx_error + 20, len(received))
255  try:
256  idx_error_end = received.index(b'\0',idx_error)
257  except:
258  pass
259  print("POPUP: Robot response: <strong>" + received[idx_error:idx_error_end].decode("utf-8") + "</strong>")
260  sys.stdout.flush()
261  pause(5)
262  else:
263  print("POPUP: Program sent. The program should be running on the robot.")
264  sys.stdout.flush()
265  else:
266  print("POPUP: Problems running program...")
267  sys.stdout.flush()
268 
269  pause(2)
270 
271  def blend_radius_check(self, pose):
272  # check that the blend radius covers 40% of the move (at most)
273  blend_radius = 'blend_radius_m';
274  current_pos = pose.Pos()
275  if self.LAST_POS is None:
276  blend_radius = '0'
277  else:
278  distance = norm(subs3(self.LAST_POS, current_pos)) # in mm
279  if 0.4*distance < self.BLEND_RADIUS_M*1000:
280  blend_radius = '%.3f' % (max(0.4*distance*0.001, 0.001))
281  self.LAST_POS = current_pos
282  return blend_radius
283 
284  def MoveJ(self, pose, joints, conf_RLF=None):
285  """Add a joint movement"""
286  if pose is None:
287  blend_radius = "0"
288  self.LAST_POS = None
289  else:
290  blend_radius = self.blend_radius_check(pose)
291  self.addline('movej(%s,accel_radss,speed_rads,0,%s)' % (angles_2_str(joints), blend_radius))
292 
293  def MoveL(self, pose, joints, conf_RLF=None):
294  """Add a linear movement"""
295  # Movement in joint space or Cartesian space should give the same result:
296  # pose_wrt_base = self.REF_FRAME*pose
297  # self.addline('movel(%s,accel_mss,speed_ms,0,blend_radius_m)' % (pose_2_str(pose_wrt_base)))
298  if pose is None:
299  blend_radius = "0"
300  self.LAST_POS = None
301  target = angles_2_str(joints)
302  else:
303  blend_radius = self.blend_radius_check(pose)
304  target = pose_2_str(self.REF_FRAME*pose)
305  #self.addline('movel(%s,accel_mss,speed_ms,0,%s)' % (angles_2_str(joints), blend_radius))
306  self.addline('movel(%s,accel_mss,speed_ms,0,%s)' % (target, blend_radius))
307 
308 
309  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
310  """Add a circular movement"""
311  def circle_radius(p0,p1,p2):
312  a = norm(subs3(p0,p1))
313  b = norm(subs3(p1,p2))
314  c = norm(subs3(p2,p0))
315  radius = a*b*c/sqrt(pow(a*a+b*b+c*c,2)-2*(pow(a,4)+pow(b,4)+pow(c,4)))
316  return radius
317 
318  def distance_p1_p02(p0,p1,p2):
319  v01 = subs3(p1, p0)
320  v02 = subs3(p2, p0)
321  return dot(v02,v01)/dot(v02,v02)
322 
323  p0 = self.LAST_POS
324  p1 = pose1.Pos()
325  p2 = pose2.Pos()
326  if p0 is None:
327  self.MoveL(pose2, joints2, conf_RLF_2)
328  return
329 
330  radius = circle_radius(p0, p1, p2)
331  if radius < 1 or radius > 100000:
332  self.MoveL(pose2, joints2, conf_RLF_2)
333  return
334 
335  d_p1_p02 = distance_p1_p02(p0, p1, p2)
336  if d_p1_p02 < 1:
337  self.MoveL(pose2, joints2, conf_RLF_2)
338  return
339 
340  blend_radius = self.blend_radius_check(pose1)
341  self.LAST_POS = pose2.Pos()
342  #self.addline('movec(%s,%s,accel_mss,speed_ms,%s)' % (angles_2_str(joints1),angles_2_str(joints2), blend_radius))
343  self.addline('movec(%s,%s,accel_mss,speed_ms,%s)' % (pose_2_str(self.REF_FRAME*pose1),pose_2_str(self.REF_FRAME*pose2), blend_radius))
344 
345  def setFrame(self, pose, frame_id=None, frame_name=None):
346  """Change the robot reference frame"""
347  # the reference frame is not needed if we use joint space for joint and linear movements
348  # the reference frame is also not needed if we use cartesian moves with respect to the robot base frame
349  # the cartesian targets must be pre-multiplied by the active reference frame
350  self.REF_FRAME = pose
351  self.addline('# set_reference(%s)' % pose_2_str(pose))
352 
353  def setTool(self, pose, tool_id=None, tool_name=None):
354  """Change the robot TCP"""
355  self.addline('set_tcp(%s)' % pose_2_str(pose))
356 
357  def Pause(self, time_ms):
358  """Pause the robot program"""
359  if time_ms <= 0:
360  self.addline('halt() # reimplement this function to force stop')
361  else:
362  self.addline('sleep(%.3f)' % (time_ms*0.001))
363 
364  def setSpeed(self, speed_mms):
365  """Changes the robot speed (in mm/s)"""
366  self.SPEED_MS = speed_mms/1000.0
367  self.addline('speed_ms = %.3f' % self.SPEED_MS)
368 
369  def setAcceleration(self, accel_mmss):
370  """Changes the robot acceleration (in mm/s2)"""
371  self.ACCEL_MSS = accel_mmss/1000.0
372  self.addline('accel_mss = %.3f' % self.ACCEL_MSS)
373 
374  def setSpeedJoints(self, speed_degs):
375  """Changes the robot joint speed (in deg/s)"""
376  self.SPEED_RADS = speed_degs*pi/180
377  self.addline('speed_rads = %.3f' % self.SPEED_RADS)
378 
379  def setAccelerationJoints(self, accel_degss):
380  """Changes the robot joint acceleration (in deg/s2)"""
381  self.ACCEL_RADSS = accel_degss*pi/180
382  self.addline('accel_radss = %.3f' % self.ACCEL_RADSS)
383 
384  def setZoneData(self, zone_mm):
385  """Changes the zone data approach (makes the movement more smooth)"""
386  if zone_mm < 0:
387  zone_mm = 0
388  self.BLEND_RADIUS_M = zone_mm / 1000.0
389  self.addline('blend_radius_m = %.3f' % self.BLEND_RADIUS_M)
390 
391  def setDO(self, io_var, io_value):
392  """Sets a variable (output) to a given value"""
393  if type(io_value) != str: # set default variable value if io_value is a number
394  if io_value > 0:
395  io_value = 'True'
396  else:
397  io_value = 'False'
398 
399  if type(io_var) != str: # set default variable name if io_var is a number
400  newline = 'set_standard_digital_out(%s, %s)' % (str(io_var), io_value)
401  else:
402  newline = '%s = %s' % (io_var, io_value)
403 
404  self.addline(newline)
405 
406  def waitDI(self, io_var, io_value, timeout_ms=-1):
407  """Waits for an input io_var to attain a given value io_value. Optionally, a timeout can be provided."""
408  if type(io_var) != str: # set default variable name if io_var is a number
409  io_var = 'get_standard_digital_in(%s)' % str(io_var)
410  if type(io_value) != str: # set default variable value if io_value is a number
411  if io_value > 0:
412  io_value = 'True'
413  else:
414  io_value = 'False'
415 
416  # at this point, io_var and io_value must be string values
417  #if timeout_ms < 0:
418  self.addline('while (%s != %s):' % (io_var, io_value))
419  self.addline(' sync()')
420  self.addline('end')
421 
422  def RunCode(self, code, is_function_call = False):
423  """Adds code or a function call"""
424  if is_function_call:
425  code.replace(' ','_')
426  if not code.endswith(')'):
427  code = code + '()'
428  self.addline(code)
429  else:
430  #self.addline(code)
431  self.addline('# ' + code) #generate custom code as a comment
432 
433  def RunMessage(self, message, iscomment = False):
434  """Show a message on the controller screen"""
435  if iscomment:
436  self.addline('# ' + message)
437  else:
438  self.addline('popup("%s","Message",False,False,blocking=True)' % message)
439 
440 # ------------------ private ----------------------
441  def addline(self, newline):
442  """Add a program line"""
443  if self.nPROGS <= 1:
444  self.PROG.append(self.TAB + newline + '\n')
445  else:
446  self.SUBPROG.append(self.TAB + newline + '\n')
447 
448  def addlog(self, newline):
449  """Add a log message"""
450  self.LOG = self.LOG + newline + '\n'
451 
452 # -------------------------------------------------
453 # ------------ For testing purposes ---------------
454 def Pose(xyzrpw):
455  [x,y,z,r,p,w] = xyzrpw
456  a = r*math.pi/180
457  b = p*math.pi/180
458  c = w*math.pi/180
459  ca = math.cos(a)
460  sa = math.sin(a)
461  cb = math.cos(b)
462  sb = math.sin(b)
463  cc = math.cos(c)
464  sc = math.sin(c)
465  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]])
466 
467 def test_post():
468  """Test the post with a basic program"""
469 
470  robot = RobotPost('Universal Robotics', 'Generic UR robot')
471 
472  robot.ProgStart("Program")
473  robot.RunMessage("Program generated by RoboDK", True)
474  robot.setFrame(Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
475  robot.setTool(Pose([62.5, -108.253175, 100, -60, 90, 0]))
476  robot.setSpeed(100) # set speed to 100 mm/s
477  robot.setAcceleration(3000) # set speed to 3000 mm/ss
478  robot.MoveJ(Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
479  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
480  robot.MoveL(Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
481  robot.RunMessage("Setting air valve 1 on")
482  robot.RunCode("TCP_On", True)
483  robot.Pause(1000)
484  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
485  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
486  robot.MoveL(Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
487  robot.RunMessage("Setting air valve off")
488  robot.RunCode("TCP_Off", True)
489  robot.Pause(1000)
490  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
491  robot.MoveL(Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
492  robot.MoveL(Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
493  robot.ProgFinish("Program")
494  # robot.ProgSave(".","Program",True)
495  for line in robot.PROG:
496  print(line[:-1])
497  if len(robot.LOG) > 0:
498  mbox('Program generation LOG:\n\n' + robot.LOG)
499 
500  input("Press Enter to close...")
501 
502 if __name__ == "__main__":
503  """Function to call when the module is executed by itself: test"""
504  test_post()
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
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 mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
Definition: robodk.py:1458
def setFrame(self, pose, frame_id=None, frame_name=None)
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
Definition: robodk.py:1354


ros_robodk_post_processors
Author(s): Victor Lamoine - Institut Maupertuis
autogenerated on Sun Jun 7 2020 03:50:22