Universal_Robots_URP.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 DEFAULT_HEADER_SCRIPT = """
44  #--------------------------
45  # Add any default subprograms here
46  # For example, to drive a gripper as a program call:
47  # def Gripper_Open():
48  # ...
49  # end
50  #
51  # Example to drive a spray gun:
52  def SprayOn(value):
53  # use the value as an output:
54  DO_SPRAY = 5
55  if value == 0:
56  set_standard_digital_out(DO_SPRAY, False)
57  else:
58  set_standard_digital_out(DO_SPRAY, True)
59  end
60  end
61 
62  # Example to synchronize 2
63  def Synchronize():
64  # Use the following digital output to signal the state of the robot:
65  DO_SYNC = 1
66 
67  # Use the following digital input to get the state of another robot:
68  DI_SYNC = 1
69 
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)))
72  sleep(0.1)
73  thread Thread_wait_1():
74  while (True):
75  sleep(0.01)
76  end
77  end
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)):
81  sync()
82  end
83  kill thread_handler_1
84  end
85  else:
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)))
88  end
89  end
90  end
91 
92  #
93  # Example to move an external axis
94  def MoveAxis(value):
95  # use the value as an output:
96  DO_AXIS_1 = 1
97  DI_AXIS_1 = 1
98  if value <= 0:
99  set_standard_digital_out(DO_AXIS_1, False)
100 
101  # Wait for digital input to change state
102  #while (get_standard_digital_in(DI_AXIS_1) != False):
103  # sync()
104  #end
105  else:
106  set_standard_digital_out(DO_AXIS_1, True)
107 
108  # Wait for digital input to change state
109  #while (get_standard_digital_in(DI_AXIS_1) != True):
110  # sync()
111  #end
112  end
113  end
114  #--------------------------
115 """
116 
117 #SCRIPT_URP = '''<URProgram name="%s">
118 # <children>
119 # <MainProgram runOnlyOnce="false" motionType="MoveJ" speed="1.0471975511965976" acceleration="1.3962634015954636" useActiveTCP="false">
120 # <children>
121 # <Script type="File">
122 # <cachedContents>%s
123 #</cachedContents>
124 # <file resolves-to="file">%s</file>
125 # </Script>
126 # </children>
127 # </MainProgram>
128 # </children>
129 #</URProgram>'''
130 
131 #SCRIPT_URP = '''<URProgram createdIn="3.0.0" lastSavedIn="3.0.0" name="%s" directory="/" installation="default">
132 # <children>
133 # <MainProgram runOnlyOnce="true" motionType="MoveJ" speed="1.0471975511965976" acceleration="1.3962634015954636" useActiveTCP="false">
134 # <children>
135 # <Script type="File">
136 # <cachedContents>%s
137 #</cachedContents>
138 # <file resolves-to="file">%s</file>
139 # </Script>
140 # </children>
141 # </MainProgram>
142 # </children>
143 #</URProgram>'''
144 
145 #<URProgram createdIn="3.4.3.361" lastSavedIn="3.4.3.361" name="%s" directory="." installation="default">
146 SCRIPT_URP = '''<URProgram createdIn="3.0.0" lastSavedIn="3.0.0" name="%s" directory="." installation="default">
147  <children>
148  <MainProgram runOnlyOnce="true" motionType="MoveJ" speed="1.0471975511965976" acceleration="1.3962634015954636" useActiveTCP="false">
149  <children>
150 %s </children>
151  </MainProgram>
152 %s </children>
153 </URProgram>'''
154 
155 def get_safe_name(progname):
156  """Get a safe program name"""
157  for c in r'-[]/\;,><&*:%=+@!#^|?^':
158  progname = progname.replace(c,'')
159  if len(progname) <= 0:
160  progname = 'Program'
161  if progname[0].isdigit():
162  progname = 'P' + progname
163  return progname
164 
165 # ----------------------------------------------------
166 # Import RoboDK tools
167 from robodk import *
168 
169 # ----------------------------------------------------
170 import socket
171 import struct
172 # UR information for real time control and monitoring
173 # Byte shifts for the real time packet:
174 UR_GET_RUNTIME_MODE = 132*8-4
175 
176 RUNTIME_CANCELLED = 0
177 RUNTIME_READY = 1
178 RUNTIME_BUSY = 2
179 
180 RUNTIME_MODE_MSG = []
181 RUNTIME_MODE_MSG.append("Operation cancelled") #0
182 RUNTIME_MODE_MSG.append("Ready") #1
183 RUNTIME_MODE_MSG.append("Running") #2 # Running or Jogging
184 
185 # Get packet size according to the byte array
186 def UR_packet_size(buf):
187  if len(buf) < 4:
188  return 0
189  return struct.unpack_from("!i", buf, 0)[0]
190 
191 # Check if a packet is complete
193  msg_sz = UR_packet_size(buf)
194  if len(buf) < msg_sz:
195  print("Incorrect packet size %i vs %i" % (msg_sz, len(buf)))
196  return False
197 
198  return True
199 
200 # Get specific information from a packet
201 def UR_packet_value(buf, offset, nval=6):
202  if len(buf) < offset+nval:
203  print("Not available offset (maybe older Polyscope version?): %i - %i" % (len(buf), offset))
204  return None
205  format = '!'
206  for i in range(nval):
207  format+='d'
208  return list(struct.unpack_from(format, buf, offset)) #return list(struct.unpack_from("!dddddd", buf, offset))
209 
210 
211 ROBOT_PROGRAM_ERROR = -1
212 ROBOT_NOT_CONNECTED = 0
213 ROBOT_OK = 1
214 
215 def UR_SendProgramRobot(robot_ip, data):
216  print("POPUP: Connecting to robot...")
217  sys.stdout.flush()
218  robot_socket = socket.create_connection((robot_ip, 30002))
219  print("POPUP: Sending program..")
220  sys.stdout.flush()
221  robot_socket.send(data)
222  print("POPUP: Sending program...")
223  sys.stdout.flush()
224  pause(1)
225  received = robot_socket.recv(4096)
226  robot_socket.close()
227 
228  if received:
229  #print("POPUP: Program running")
230  #print(str(received))
231  sys.stdout.flush()
232  idx_error = -1
233  try:
234  idx_error = received.index(b'error')
235  except:
236  pass
237 
238  if idx_error >= 0:
239  idx_error_end = min(idx_error + 20, len(received))
240  try:
241  idx_error_end = received.index(b'\0',idx_error)
242  except:
243  pass
244  print("POPUP: Robot response: <strong>" + received[idx_error:idx_error_end].decode("utf-8") + "</strong>")
245  sys.stdout.flush()
246  pause(5)
247  return ROBOT_PROGRAM_ERROR
248  else:
249  print("POPUP: Program sent. The program should be running on the robot.")
250  sys.stdout.flush()
251  return ROBOT_OK
252  else:
253  print("POPUP: Robot connection problems...")
254  sys.stdout.flush()
255  pause(2)
256  return ROBOT_NOT_CONNECTED
257 
258 # Monitor thread to retrieve information from the robot
259 def UR_Wait_Ready(robot_ip, percent_cmpl):
260  RUNTIME_MODE_LAST = -1
261  while True:
262  print("Connecting to robot %s:%i" % (robot_ip, 30003))
263  rt_socket = socket.create_connection((robot_ip, 30003))
264  print("Connected")
265  buf = b''
266  while True:
267  more = rt_socket.recv(4096)
268  if more:
269  buf = buf + more
270  if UR_packet_check(buf):
271  packet_len = UR_packet_size(buf)
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)
278  sys.stdout.flush()
279  else:
280  print("POPUP: Robot Status Unknown (%.i)" % RUNTIME_MODE + " (transfer %.1f%% completed)" % percent_cmpl)
281  sys.stdout.flush()
282 
283  if RUNTIME_MODE == RUNTIME_READY:
284  rt_socket.close()
285  return True
286 
287  rt_socket.close()
288  return False
289 
290 
291 UR_MoveJ = 1
292 UR_MoveL = 2
293 UR_MoveP = 3
294 UR_MoveC = 4
295 
296 def pose_2_ur(pose):
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)
300 
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]]
303 
304  if angle == 0:
305  rxyz = [0,0,0]
306  else:
307  rxyz = normalize3(rxyz)
308  rxyz = mult3(rxyz, angle)
309  return [pose[0,3], pose[1,3], pose[2,3], rxyz[0], rxyz[1], rxyz[2]]
310 
311 def pose_2_str(pose):
312  """Prints a pose target"""
313  [x,y,z,w,p,r] = pose_2_ur(pose)
314  MM_2_M = 0.001
315  return ('p[%.6f, %.6f, %.6f, %.6f, %.6f, %.6f]' % (x*MM_2_M,y*MM_2_M,z*MM_2_M,w,p,r))
316 
317 def angles_2_str(angles):
318  """Prints a joint target"""
319  njoints = len(angles)
320  d2r = pi/180.0
321  if njoints == 6:
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))
323  else:
324  return 'this post only supports 6 joints'
325 
326 def circle_radius(p0,p1,p2):
327  a = norm(subs3(p0,p1))
328  b = norm(subs3(p1,p2))
329  c = norm(subs3(p2,p0))
330  radius = a*b*c/sqrt(pow(a*a+b*b+c*c,2)-2*(pow(a,4)+pow(b,4)+pow(c,4)))
331  return radius
332 
333 try:
334  from html import escape # python 3.x
335 except ImportError:
336  from cgi import escape # python 2.x
337 
338 #def distance_p1_p02(p0,p1,p2):
339 # v01 = subs3(p1, p0)
340 # v02 = subs3(p2, p0)
341 # return dot(v02,v01)/dot(v02,v02)
342 
343 # ----------------------------------------------------
344 # Object class that handles the robot instructions/syntax
345 class RobotPost(object):
346  """Robot post object"""
347  MAX_LINES_X_PROG = 5000 # Maximum number of lines per program. If the number of lines is exceeded, the program will be executed step by step by RoboDK
348  UPLOAD_SFTP = False # If True, it will attempt to upload using SFTP. It requires PYSFTP (pip install pysftp. Important: It requires Visual Studio Community C++ 10.0)
349  PROG_EXT = 'script' # set the program extension
350  SPEED_MS = 0.250 # default speed for linear moves in m/s
351  SPEED_RADS = 0.75 # default speed for joint moves in rad/s
352  ACCEL_MSS = 1.2 # default acceleration for lineaer moves in m/ss
353  ACCEL_RADSS = 1.2 # default acceleration for joint moves in rad/ss
354  BLEND_RADIUS_M = 0.001 # default blend radius in meters (corners smoothing)
355  MOVEC_MIN_RADIUS = 1 # minimum circle radius to output (in mm). It does not take into account the Blend radius
356  MOVEC_MAX_RADIUS = 10000 # maximum circle radius to output (in mm). It does not take into account the Blend radius
357  USE_MOVEP = True # Set to True to use MoveP, set to False to use MoveL
358  #--------------------------------
359  REF_FRAME = eye(4) # default reference frame (the robot reference frame)
360  TOOL_FRAME = eye(4)
361  TOOL_FRAME_INV = eye(4)
362  LAST_POS_ABS = None # last XYZ position
363 
364  # other variables
365  ROBOT_POST = 'unset'
366  ROBOT_NAME = 'generic'
367  PROG_FILES = []
368  MAIN_PROGNAME = 'unknown'
369 
370  nPROGS = 0
371  PROG = []
372  PROG_LIST = []
373  PROG_URP = []
374  FOOTER_URP = ''
375  SubProgCount = 0
376  SubProgNames = []
377  LAST_MOVETYPE = None
378  WaypointCount = 0
379  MotionParameters = '<motionParameters/>'
380 
381  PROG_LIST_URP = []
382  VARS = []
383  VARS_LIST = []
384  SUBPROG = []
385  SUBPROG_URP = []
386  TAB = ''
387  TAB_URP = '' # 2 tabs for URP XML are added by default in the main contents
388  LOG = ''
389 
390  def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
391  self.ROBOT_POST = robotpost
392  self.ROBOT_NAME = robotname
393  for k,v in kwargs.items():
394  if k == 'lines_x_prog':
396 
397  def ProgStart(self, progname):
398  progname = get_safe_name(progname)
399  self.nPROGS = self.nPROGS + 1
400  self.SubProgCount = 0
401  self.SubProgNames = []
402  if self.nPROGS <= 1:
403  self.TAB = ''
404  # Create global variables:
405  self.vars_update()
406  self.MAIN_PROGNAME = progname
407  else:
408  self.addline('# Subprogram %s' % progname)
409  self.addline('def %s():' % progname)
410  self.TAB = ' '
411 
412  def ProgFinish(self, progname):
413  self.urp_move_close()
414  progname = get_safe_name(progname)
415  self.TAB = ''
416  if self.nPROGS <= 1:
417  self.addline('# End of main program')
418  else:
419  self.addline('end')
420  self.addline('')
421 
422  def ProgSave(self, folder, progname, ask_user = False, show_result = False):
423  progname = get_safe_name(progname)
424  progname = progname + '.script'# + self.PROG_EXT
425  if ask_user or not DirExists(folder):
426  filesave = getSaveFile(folder, progname, 'Save program as...')
427  if filesave is not None:
428  filesave = filesave.name
429  else:
430  return
431  else:
432  filesave = folder + '/' + progname
433 
434  self.prog_2_list()
435 
436  fid = open(filesave, "w")
437  # Create main program call:
438  fid.write('def %s():\n' % self.MAIN_PROGNAME)
439 
440  # Add global parameters:
441  fid.write(' # Global parameters:\n')
442  for line in self.VARS_LIST[0]:
443  fid.write(' ' + line+ '\n')
444  #fid.write(' \n')
445  fid.write(' ')
446 
447  # Add a custom header if desired:
448  fid.write(DEFAULT_HEADER_SCRIPT)
449  fid.write(' \n')
450 
451  # Add the suprograms that are being used in RoboDK
452  for line in self.SUBPROG:
453  fid.write(' ' + line + '\n')
454  fid.write(' \n')
455 
456  # Add the main code:
457  fid.write(' # Main program:\n')
458  for prog in self.PROG_LIST:
459  for line in prog:
460  fid.write(' ' + line + '\n')
461 
462  fid.write('end\n\n')
463  fid.write('%s()\n' % self.MAIN_PROGNAME)
464 
465  fid.close()
466 
467  print('SAVED: %s\n' % filesave) # tell RoboDK the path of the saved file
468  self.PROG_FILES = filesave
469 
470  #---------------------------- SAVE URP (GZIP compressed XML file)-------------------------
471  filesave_urp = filesave[:-7] #+'.urp'
472  urpxml = ''
473  # Add the suprograms that are being used in RoboDK
474  #for line in self.SUBPROG_URP:
475  # urpxml += (' ' + line + '\n')
476 
477  # Add the main code:
478  for line in self.PROG_URP:
479  urpxml += (' ' + line + '\n')
480  self.PROG_XML = SCRIPT_URP % (self.MAIN_PROGNAME, urpxml, self.FOOTER_URP)
481  # Comment next line to force transfer of the SCRIPT file
482  #self.PROG_FILES = filesave_urp
483 
484  import gzip
485  import os
486  with gzip.open(filesave_urp, 'wb') as fid_gz:
487  fid_gz.write(self.PROG_XML.encode('utf-8'))
488 
489  try:
490  os.remove(filesave_urp+'.urp')
491  except OSError:
492  pass
493 
494  os.rename(filesave_urp, filesave_urp+'.urp')
495 
496  #print('SAVED: %s\n' % filesave_urp) # tell RoboDK the path of the saved file
497  #------------------------------------------------------------------------------------------
498 
499  # open file with default application
500  if show_result:
501  if type(show_result) is str:
502  # Open file with provided application
503  import subprocess
504  p = subprocess.Popen([show_result, filesave])
505  elif type(show_result) is list:
506  import subprocess
507  p = subprocess.Popen(show_result + [filesave])
508  else:
509  # open file with default application
510  os.startfile(filesave)
511  if len(self.LOG) > 0:
512  mbox('Program generation LOG:\n\n' + self.LOG)
513 
514  #if len(self.PROG_LIST) > 1:
515  # mbox("Warning! The program " + progname + " is too long and directly running it on the robot controller might be slow. It is better to run it form RoboDK.")
516 
517 
518  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
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"""
521  #UploadFTP(self.PROG_FILES, robot_ip, remote_path, ftp_user, ftp_pass)
522  #return
523  if self.UPLOAD_SFTP:
524  import pysftp
525  with pysftp.Connection(robot_ip, username=ftp_user, password=ftp_pass) as sftp:
526  with sftp.cd(remote_path): # temporarily chdir to public
527  if type(self.PROG_FILES) is str:
528  sftp.put(self.PROG_FILES) # upload file to public/ on remote
529  else:
530  for file in self.PROG_FILES:
531  sftp.put(file) # upload file to public/ on remote
532  #sftp.get('remote_file') # get a remote file
533 
534  else:
535  nprogs = len(self.PROG_LIST)
536  for i in range(nprogs):
537  # Prepare next program execution:
538  send_str = ''
539  send_str += ('def %s():\n' % self.MAIN_PROGNAME)
540 
541  # Add global parameters:
542  send_str += (' # Global parameters:\n')
543  for line in self.VARS_LIST[i]:
544  send_str += (' ' + line + '\n')
545  send_str += (' \n')
546 
547  # Add a custom header if desired:
548  send_str += (DEFAULT_HEADER_SCRIPT)
549  send_str += (' \n')
550 
551  for line in self.SUBPROG:
552  send_str += ' ' + line+ '\n'
553  send_str += (' \n')
554 
555  # Add the main code:
556  send_str += (' # Main program:\n')
557 
558  for line in self.PROG_LIST[i]:
559  send_str += ' ' + line
560  send_str += '\n'
561 
562  send_str += 'end\n\n'
563  send_str += '%s()\n' % self.MAIN_PROGNAME
564 
565  send_bytes = str.encode(send_str)
566 
567  # Wait until the robot is ready:
568  while i > 0 and not UR_Wait_Ready(robot_ip, i*100.0/nprogs):
569  print("POPUP: Connect robot to run the program program...")
570  sys.stdout.flush()
571  pause(2)
572 
573  # Send script to the robot:
574  #print(send_str)
575  #input("POPUP: Enter to continue")
576  while ROBOT_NOT_CONNECTED == UR_SendProgramRobot(robot_ip, send_bytes):
577  print("POPUP: Connect robot to transfer program...")
578  sys.stdout.flush()
579  pause(2)
580 
581  def blend_radius_check(self, pose_abs, ratio_check=0.5):
582  # check that the blend radius covers 40% of the move (at most)
583  blend_radius = self.BLEND_RADIUS_M;
584  #return blend_radius
585  current_pos = pose_abs.Pos()
586  if self.LAST_POS_ABS is None:
587  blend_radius = 0
588  else:
589  distance = norm(subs3(self.LAST_POS_ABS, current_pos)) # in mm
590  if ratio_check*distance < self.BLEND_RADIUS_M*1000:
591  blend_radius = round(ratio_check*distance*0.001,3)
592  #self.LAST_POS_ABS = current_pos
593  return blend_radius
594 
595  def MoveJ(self, pose, joints, conf_RLF=None):
596  """Add a joint movement"""
597  if pose is None:
598  blend_radius = 0
599  self.LAST_POS_ABS = None
600  else:
601  pose_abs = self.REF_FRAME*pose
602  blend_radius = self.blend_radius_check(pose_abs)
603  self.LAST_POS_ABS = pose_abs.Pos()
604 
605  if len(joints) < 6:
606  self.RunMessage('Move axes to: ' + angles_2_str(joints))
607  #else:
608  # self.addline('movej(%s,accel_radss,speed_rads,0,%s)' % (angles_2_str(joints), blend_radius))
609 
610  # Optionally, use absolute joint movements (move axes, not pose)
611  if pose is None:
612  self.RunCode('movej(%s)' % angles_2_str(joints))
613  else:
614  self.RunCode('#movej(%s)' % angles_2_str(joints))
615  self.add_urp_move(UR_MoveJ, pose, joints, conf_RLF, blend_radius)
616 
617 
618  def MoveL(self, pose, joints, conf_RLF=None):
619  """Add a linear movement"""
620  # Movement in joint space or Cartesian space should give the same result:
621  # pose_wrt_base = self.REF_FRAME*pose
622  # self.addline('movel(%s,accel_mss,speed_ms,0,blend_radius_m)' % (pose_2_str(pose_wrt_base)))
623  if pose is None:
624  blend_radius = 0
625  self.LAST_POS = None
626  target = angles_2_str(joints)
627  else:
628  pose_abs = self.REF_FRAME*pose
629  blend_radius = self.blend_radius_check(pose_abs)
630  target = pose_2_str(pose_abs)
631  self.LAST_POS_ABS = pose_abs.Pos()
632 
633  if self.USE_MOVEP:
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)
636  else:
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)
639 
640  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
641  """Add a circular movement"""
642  pose1_abs = self.REF_FRAME*pose1
643  pose2_abs = self.REF_FRAME*pose2
644  p0 = self.LAST_POS_ABS
645  p1 = pose1_abs.Pos()
646  p2 = pose2_abs.Pos()
647  if p0 is None:
648  self.MoveL(pose2, joints2, conf_RLF_2)
649  return
650 
651  radius = circle_radius(p0, p1, p2)
652  print("MoveC Radius: " + str(radius) + " mm")
653  if radius < self.MOVEC_MIN_RADIUS or radius > self.MOVEC_MAX_RADIUS:
654  self.MoveL(pose2, joints2, conf_RLF_2)
655  return
656 
657  blend_radius = self.blend_radius_check(pose1_abs, 0.2)
658  #blend_radius = '%.3f' % (0.001*radius) #'0'
659  #blend_radius = '0'
660  self.LAST_POS_ABS = pose2_abs.Pos()
661 
662  self.RunMessage('Circular move (R%.1f mm)' % radius, True)
663  self.RunCode('movec(%s,%s)' % (pose_2_str(pose1_abs),pose_2_str(pose2_abs)))
664  #self.add_urp_move(UR_MoveL, pose1, joints1, conf_RLF1)
665  #self.add_urp_move(UR_MoveL, pose2, joints2, conf_RLF2)
666 
667  # RunCode will add the movement line
668  #self.addline('movec(%s,%s,accel_mss,speed_ms,%s)' % (angles_2_str(joints1),angles_2_str(joints2), blend_radius))
669  #self.addline('movec(%s,%s,accel_mss,speed_ms,%s)' % (pose_2_str(pose1_abs),pose_2_str(pose2_abs), blend_radius))
670 
671  def setFrame(self, pose, frame_id=None, frame_name=None):
672  """Change the robot reference frame"""
673  # the reference frame is not needed if we use joint space for joint and linear movements
674  # the reference frame is also not needed if we use cartesian moves with respect to the robot base frame
675  # the cartesian targets must be pre-multiplied by the active reference frame
676  self.REF_FRAME = pose
677  ref_pose = pose_2_str(pose)
678 
679  self.urp_move_close()
680  self.RunMessage('Using Ref. %s: %s' % (frame_name, ref_pose), True)
681  self.addline('# set_reference(%s)' % ref_pose)
682 
683  def setTool(self, pose, tool_id=None, tool_name=None):
684  """Change the robot TCP"""
685  self.TOOL_FRAME = pose
686  self.TOOL_FRAME_INV = invH(pose)
687  tcp_pose = pose_2_str(pose)
688 
689  # Important: RunCode will output SCRIPT and URP
690  #self.addline('set_tcp(%s)' % tcp_pose)
691  #self.addline('set_payload(1.4, [-0.1181, -0.1181, 0.03])')
692  #self.addline('set_gravity([0.0, 0.0, 9.82]))')
693 
694  # Add URP
695  # self.urp_move_close()
696 
697  # Add a comment
698  self.RunMessage('Using TCP %s: %s' % (tool_name, tcp_pose), True)
699 
700  # Add the script to run
701  self.RunCode('set_tcp(%s)' % tcp_pose)
702  #self.add_urp('<Set type="NoAction">')
703  #self.add_urp(' <tcp referencedName="TCP"/>')
704  #self.add_urp('</Set>')
705 
706  def Pause(self, time_ms):
707  """Pause the robot program"""
708  if time_ms <= 0:
709  self.addline('halt() # reimplement this function to force stop')
710 
711  self.urp_move_close()
712  self.add_urp('<Halt/>')
713  else:
714  self.addline('sleep(%.3f)' % (time_ms*0.001))
715 
716  self.urp_move_close()
717  self.add_urp('<Wait type="Sleep">')
718  self.add_urp(' <waitTime>%.3f</waitTime>' % (time_ms*0.001))
719  self.add_urp('</Wait>')
720 
721  def setSpeed(self, speed_mms):
722  """Changes the robot speed (in mm/s)"""
723  #if speed_mms < 999.9:
724  # self.USE_MOVEP = True
725  #else:
726  # self.USE_MOVEP = False
727  self.SPEED_MS = speed_mms/1000.0
728  self.addline('speed_ms = %.3f' % self.SPEED_MS)
729  self.urp_move_close()
731 
732  def setAcceleration(self, accel_mmss):
733  """Changes the robot acceleration (in mm/s2)"""
734  self.ACCEL_MSS = accel_mmss/1000.0
735  self.addline('accel_mss = %.3f' % self.ACCEL_MSS)
737 
738  def setSpeedJoints(self, speed_degs):
739  """Changes the robot joint speed (in deg/s)"""
740  self.SPEED_RADS = speed_degs*pi/180
741  self.addline('speed_rads = %.3f' % self.SPEED_RADS)
743 
744  def setAccelerationJoints(self, accel_degss):
745  """Changes the robot joint acceleration (in deg/s2)"""
746  self.ACCEL_RADSS = accel_degss*pi/180
747  self.addline('accel_radss = %.3f' % self.ACCEL_RADSS)
749 
750  def setZoneData(self, zone_mm):
751  """Changes the zone data approach (makes the movement more smooth)"""
752  if zone_mm < 0:
753  zone_mm = 0
754  self.BLEND_RADIUS_M = zone_mm / 1000.0
755  self.addline('blend_radius_m = %.3f' % self.BLEND_RADIUS_M)
756 
757  def setDO(self, io_var, io_value):
758  """Sets a variable (output) to a given value"""
759  io_var_urp = io_var
760  io_value_urp = io_value
761 
762  if type(io_value) != str: # set default variable value if io_value is a number
763  if io_value > 0:
764  io_value = 'True'
765  io_value_urp = '1'
766  else:
767  io_value = 'False'
768  io_value_urp = '0'
769 
770  if type(io_var) != str: # set default variable name if io_var is a number
771  io_var_urp = 'digital_out[%s]' % str(io_var)
772  newline = 'set_standard_digital_out(%s, %s)' % (str(io_var), io_value)
773  else:
774  newline = '%s = %s' % (io_var, io_value)
775 
776  self.addline(newline)
777 
778  self.urp_move_close()
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)
782  self.add_urp('</Set>')
783 
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."""
786  io_var_urp = io_var
787  io_value_urp = io_value
788 
789  if type(io_var) != str: # set default variable name if io_var is a number
790  io_var = 'get_standard_digital_in(%s)' % str(io_var)
791  io_var_urp = 'digital_in[%s]' % str(io_var)
792 
793  if type(io_value) != str: # set default variable value if io_value is a number
794  if io_value > 0:
795  io_value = 'True'
796  io_value_urp = '1'
797  else:
798  io_value = 'False'
799  io_value_urp = '0'
800 
801  # at this point, io_var and io_value must be string values
802  #if timeout_ms < 0:
803  self.addline('while (%s != %s):' % (io_var, io_value))
804  self.addline(' sync()')
805  self.addline('end')
806 
807  self.urp_move_close()
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)
811  self.add_urp('</Wait>')
812 
813  def RunCode(self, code, is_function_call = False):
814  """Adds code or a function call"""
815  if is_function_call:
816  code = get_safe_name(code)
817  if code.lower() == "usemovel":
818  self.setZoneData(0)
819  self.USE_MOVEP = False
820  return
821  elif code.lower() == "usemovep":
822  self.USE_MOVEP = True
823  return
824 
825  if not code.endswith(')'):
826  code = code + '()'
827 
828  self.addline(code)
829 
830  progname = code.split('(')[0]
831  self.urp_move_close()
832 
833  self.SubProgCount += 1
834  if not progname in self.SubProgNames:
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)
838  self.add_urp(' <children>')
839  self.add_urp(' </children>')
840  self.add_urp(' </subprogram>')
841  self.add_urp('</CallSubProgram>')
842 
843  self.SubProgNames.append(progname)
844  str_count = ''
845  if self.SubProgCount > 1:
846  str_count = '[%i]' % self.SubProgCount
847 
848  self.FOOTER_URP += ' <SubProgram reference="../MainProgram/children/CallSubProgram%s/subprogram"/>\n' % str_count
849  # <SubProgram reference="../MainProgram/children/CallSubProgram/subprogram"/>
850  # <SubProgram reference="../MainProgram/children/CallSubProgram[2]/subprogram"/>
851  else:
852  id_subprog = self.SubProgNames.index(progname) + 1
853  str_subprog = ''
854  if id_subprog > 1:
855  str_subprog = '[%i]' % (id_subprog)
856 
857  print('ID: ' + str(id_subprog))
858  print(self.SubProgNames)
859 
860  self.add_urp('<CallSubProgram>')
861  self.add_urp(' <subprogram reference="../../CallSubProgram%s/subprogram"/>' % str_subprog)
862  self.add_urp('</CallSubProgram>')
863 
864  else:
865  self.addline(code)
866  #self.addline('# ' + code) #generate custom code as a comment
867 
868  self.urp_move_close()
869  self.add_urp('<Script type="Line">')
870  self.add_urp(' <expression>')
871  for c in code:
872  self.add_urp(' <ExpressionChar character="%s"/>' % escape(c))
873  self.add_urp(' </expression>')
874  self.add_urp('</Script>')
875 
876  def RunMessage(self, message, iscomment = False):
877  """Show a message on the controller screen"""
878  if iscomment:
879  self.addline('# ' + message)
880 
881  self.urp_move_close()
882  self.add_urp('<Comment comment="%s"/>' % escape(message))
883  else:
884  self.addline('popup("%s","Message",False,False,blocking=True)' % message)
885 
886  self.urp_move_close()
887  self.add_urp('<Popup type="Message" haltProgram="false" message="%s"/>' % escape(message))
888 
889 # ------------------ private ----------------------
890  def vars_update(self):
891  # Generate global variables for this program
892  self.VARS = []
893  self.VARS.append('global speed_ms = %.3f' % self.SPEED_MS)
894  self.VARS.append('global speed_rads = %.3f' % self.SPEED_RADS)
895  self.VARS.append('global accel_mss = %.3f' % self.ACCEL_MSS)
896  self.VARS.append('global accel_radss = %.3f' % self.ACCEL_RADSS)
897  self.VARS.append('global blend_radius_m = %.3f' % self.BLEND_RADIUS_M)
898 
899  def prog_2_list(self):
900  if len(self.PROG) > 1:
901  self.PROG_LIST.append(self.PROG)
902  self.PROG = []
903  self.VARS_LIST.append(self.VARS)
904  self.VARS = []
905  self.vars_update()
906 
907  def addline(self, newline):
908  """Add a program line"""
909  if self.nPROGS <= 1:
910  if len(self.PROG) > self.MAX_LINES_X_PROG:
911  self.prog_2_list()
912 
913  self.PROG.append(self.TAB + newline)
914  else:
915  self.SUBPROG.append(self.TAB + newline)
916 
917  def add_urp(self, newline):
918  """Add a program line"""
919  if self.nPROGS <= 1:
920  self.PROG_URP.append(self.TAB_URP + newline)
921  else:
922  self.SUBPROG_URP.append(self.TAB_URP + newline)
923 
925  self.MotionParameters = '<motionParameters'
926  if self.BLEND_RADIUS_M is not None:
927  self.MotionParameters += ' blendRadius="%s"' % self.BLEND_RADIUS_M
928  if self.SPEED_RADS is not None:
929  self.MotionParameters += ' jointSpeed="%s"' % self.SPEED_RADS
930  if self.ACCEL_RADSS is not None:
931  self.MotionParameters += ' jointAcceleration="%s"' % self.ACCEL_RADSS
932  if self.SPEED_MS is not None:
933  self.MotionParameters += ' cartesianSpeed="%s"' % self.SPEED_MS
934  if self.ACCEL_MSS is not None:
935  self.MotionParameters += ' cartesianAcceleration="%s"' % self.ACCEL_MSS
936  self.MotionParameters += '/>'
937 
938  def add_urp_move(self, movetype, pose, joints, conf_RLF, blend_radius):
939  if movetype != self.LAST_MOVETYPE:
940  self.urp_move_close()
941 
942  if self.LAST_MOVETYPE is None:
943  if movetype == UR_MoveJ:
944  self.add_urp('<Move motionType="MoveJ" speed="%.3f" acceleration="%.3f" useActiveTCP="false">' % (self.SPEED_RADS, self.ACCEL_RADSS))
945  self.MotionParameters = None
946  elif movetype == UR_MoveL:
947  self.add_urp('<Move motionType="MoveL" speed="%.3f" acceleration="%.3f" useActiveTCP="false">' % (self.SPEED_MS, self.ACCEL_MSS))
948  self.MotionParameters = None
949  elif movetype == UR_MoveP:
950  self.add_urp('<Move motionType="MoveP" speed="%.3f" acceleration="%.3f" blendRadius="%.3f" useActiveTCP="false">' % (self.SPEED_MS, self.ACCEL_MSS, self.BLEND_RADIUS_M))
951  self.MotionParameters = None
952 
953  #<Move motionType="MoveL" speed="0.25" acceleration="1.2" useActiveTCP="false">
954  #<tcp reference="../../Set/tcp"/>
955  #<feature class="GeomFeatureReference" referencedName="Joint_0_name"/>
956 
957  self.add_urp(' <children>')
958 
959  self.LAST_MOVETYPE = movetype
960 
961  self.WaypointCount += 1
962  #self.add_urp(' <Waypoint type="Fixed" name="Waypoint_%i" kinematicsFlags="4">' % self.WaypointCount)
963  self.add_urp(' <Waypoint type="Fixed" name="Waypoint_%i">' % self.WaypointCount)
964  if self.MotionParameters is not None:
965  self.add_urp(' %s' % self.MotionParameters)
966  elif movetype == UR_MoveL and self.BLEND_RADIUS_M > 0.0:
967  # Important: Blend radius needs to be provided for each linear movement (otherwise, "stop" is taken into account)
968  self.add_urp(' <motionParameters blendRadius="%.3f"/>' % self.BLEND_RADIUS_M)
969 
970  # self.MotionParameters = '<motionParameters/>' # once applied, do not alter
971  if pose is None:
972  # Warning!! Current URCaps 3.4 does not support absolute joint movement. Use script instead
973  self.add_urp(' <position joints="%s"/>' % (angles_2_str(joints)[1:-1]))
974  else:
975  poseabs = self.REF_FRAME*pose
976  poseabsflange = poseabs*self.TOOL_FRAME_INV
977  pose_str = pose_2_str(pose)[2:-1]
978  poseabs_str = pose_2_str(poseabs)[2:-1]
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)
983  self.add_urp(' </Waypoint>')
984 
985  def urp_move_close(self):
986  if self.LAST_MOVETYPE is not None:
987  self.add_urp(' </children>')
988  self.add_urp('</Move>')
989  self.LAST_MOVETYPE = None
990 
991  def addlog(self, newline):
992  """Add a log message"""
993  self.LOG = self.LOG + newline + '\n'
994 
995 # -------------------------------------------------
996 # ------------ For testing purposes ---------------
997 def Pose(xyzrpw):
998  [x,y,z,r,p,w] = xyzrpw
999  a = r*math.pi/180
1000  b = p*math.pi/180
1001  c = w*math.pi/180
1002  ca = math.cos(a)
1003  sa = math.sin(a)
1004  cb = math.cos(b)
1005  sb = math.sin(b)
1006  cc = math.cos(c)
1007  sc = math.sin(c)
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]])
1009 
1011  """Test the post with a basic program"""
1012 
1013  robot = RobotPost('Universal Robotics', 'Generic UR robot')
1014 
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]))
1019  robot.setSpeed(100) # set speed to 100 mm/s
1020  robot.setAcceleration(3000) # set speed to 3000 mm/ss
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)
1026  robot.Pause(1000)
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)
1032  robot.Pause(1000)
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")
1037  # robot.ProgSave(".","Program",True)
1038  for line in robot.PROG:
1039  print(line)
1040 
1041  print("")
1042  print("")
1043  print("")
1044  for line in robot.PROG_URP:
1045  print(line)
1046  if len(robot.LOG) > 0:
1047  mbox('Program generation LOG:\n\n' + robot.LOG)
1048 
1049  input("Press Enter to close...")
1050 
1051 if __name__ == "__main__":
1052  """Function to call when the module is executed by itself: test"""
1053  test_post()
def setFrame(self, pose, frame_id=None, frame_name=None)
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
def setTool(self, pose, tool_id=None, tool_name=None)
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)
Definition: robodk.py:1458
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 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