Universal_Robots.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 drive an extruder:
63  def Extruder(value):
64  # use the value as an output:
65  if value < 0:
66  # stop extruder
67  else:
68  # start extruder
69  end
70  end
71 
72  # Example to move an external axis
73  def MoveAxis(value):
74  # use the value as an output:
75  DO_AXIS_1 = 1
76  DI_AXIS_1 = 1
77  if value <= 0:
78  set_standard_digital_out(DO_AXIS_1, False)
79 
80  # Wait for digital input to change state
81  #while (get_standard_digital_in(DI_AXIS_1) != False):
82  # sync()
83  #end
84  else:
85  set_standard_digital_out(DO_AXIS_1, True)
86 
87  # Wait for digital input to change state
88  #while (get_standard_digital_in(DI_AXIS_1) != True):
89  # sync()
90  #end
91  end
92  end
93  #--------------------------
94 """
95 
96 #SCRIPT_URP = '''<URProgram name="%s">
97 # <children>
98 # <MainProgram runOnlyOnce="false" motionType="MoveJ" speed="1.0471975511965976" acceleration="1.3962634015954636" useActiveTCP="false">
99 # <children>
100 # <Script type="File">
101 # <cachedContents>%s
102 #</cachedContents>
103 # <file resolves-to="file">%s</file>
104 # </Script>
105 # </children>
106 # </MainProgram>
107 # </children>
108 #</URProgram>'''
109 
110 #SCRIPT_URP = '''<URProgram createdIn="3.0.0" lastSavedIn="3.0.0" name="%s" directory="/" installation="default">
111 # <children>
112 # <MainProgram runOnlyOnce="true" motionType="MoveJ" speed="1.0471975511965976" acceleration="1.3962634015954636" useActiveTCP="false">
113 # <children>
114 # <Script type="File">
115 # <cachedContents>%s
116 #</cachedContents>
117 # <file resolves-to="file">%s</file>
118 # </Script>
119 # </children>
120 # </MainProgram>
121 # </children>
122 #</URProgram>'''
123 
124 #<URProgram createdIn="3.4.3.361" lastSavedIn="3.4.3.361" name="%s" directory="." installation="default">
125 SCRIPT_URP = '''<URProgram createdIn="3.0.0" lastSavedIn="3.0.0" name="%s" directory="." installation="default">
126  <children>
127  <MainProgram runOnlyOnce="true" motionType="MoveJ" speed="1.0471975511965976" acceleration="1.3962634015954636" useActiveTCP="false">
128  <children>
129  <Script type="File">
130  <cachedContents>%s
131 </cachedContents>
132  <file>%s</file>
133  </Script>
134  </children>
135  </MainProgram>
136  </children>
137 </URProgram>'''
138 
139 def get_safe_name(progname):
140  """Get a safe program name"""
141  for c in r'-[]/\;,><&*:%=+@!#^|?^':
142  progname = progname.replace(c,'')
143  if len(progname) <= 0:
144  progname = 'Program'
145  if progname[0].isdigit():
146  progname = 'P' + progname
147  return progname
148 
149 # ----------------------------------------------------
150 # Import RoboDK tools
151 from robodk import *
152 
153 # ----------------------------------------------------
154 import socket
155 import struct
156 # UR information for real time control and monitoring
157 # Byte shifts for the real time packet:
158 UR_GET_RUNTIME_MODE = 132*8-4
159 
160 RUNTIME_CANCELLED = 0
161 RUNTIME_READY = 1
162 RUNTIME_BUSY = 2
163 
164 RUNTIME_MODE_MSG = []
165 RUNTIME_MODE_MSG.append("Operation cancelled") #0
166 RUNTIME_MODE_MSG.append("Ready") #1
167 RUNTIME_MODE_MSG.append("Running") #2 # Running or Jogging
168 
169 # Get packet size according to the byte array
170 def UR_packet_size(buf):
171  if len(buf) < 4:
172  return 0
173  return struct.unpack_from("!i", buf, 0)[0]
174 
175 # Check if a packet is complete
177  msg_sz = UR_packet_size(buf)
178  if len(buf) < msg_sz:
179  print("Incorrect packet size %i vs %i" % (msg_sz, len(buf)))
180  return False
181 
182  return True
183 
184 # Get specific information from a packet
185 def UR_packet_value(buf, offset, nval=6):
186  if len(buf) < offset+nval:
187  print("Not available offset (maybe older Polyscope version?): %i - %i" % (len(buf), offset))
188  return None
189  format = '!'
190  for i in range(nval):
191  format+='d'
192  return list(struct.unpack_from(format, buf, offset)) #return list(struct.unpack_from("!dddddd", buf, offset))
193 
194 
195 ROBOT_PROGRAM_ERROR = -1
196 ROBOT_NOT_CONNECTED = 0
197 ROBOT_OK = 1
198 
199 def GetErrorMsg(rec_bytes):
200  idx_error = -1
201  try:
202  idx_error = rec_bytes.index(b'error')
203  except:
204  return None
205 
206  if idx_error >= 0:
207  idx_error_end = min(idx_error + 20, len(rec_bytes))
208  try:
209  idx_error_end = rec_bytes.index(b'\0',idx_error)
210  except:
211  return "Unknown error"
212  return rec_bytes[idx_error:idx_error_end].decode("utf-8")
213 
214 def UR_SendProgramRobot(robot_ip, data):
215  print("POPUP: Connecting to robot...")
216  sys.stdout.flush()
217  robot_socket = socket.create_connection((robot_ip, 30002))
218  print("POPUP: Sending program..")
219  sys.stdout.flush()
220  robot_socket.send(data)
221  print("POPUP: Sending program...")
222  sys.stdout.flush()
223  pause(1)
224  received = robot_socket.recv(4096)
225  robot_socket.close()
226 
227  if received:
228  #print("POPUP: Program running")
229  #print(str(received))
230  sys.stdout.flush()
231  error_msg = GetErrorMsg(received)
232  if error_msg:
233  print("POPUP: Robot response: <strong>" + error_msg + "</strong>")
234  sys.stdout.flush()
235  pause(5)
236  return ROBOT_PROGRAM_ERROR
237  else:
238  print("POPUP: Program sent. The program should be running on the robot.")
239  sys.stdout.flush()
240  return ROBOT_OK
241  else:
242  print("POPUP: Robot connection problems...")
243  sys.stdout.flush()
244  pause(2)
245  return ROBOT_NOT_CONNECTED
246 
247 # Monitor thread to retrieve information from the robot
248 def UR_Wait_Ready(robot_ip, percent_cmpl):
249  RUNTIME_MODE_LAST = -1
250  while True:
251  print("Connecting to robot %s:%i" % (robot_ip, 30003))
252  rt_socket = socket.create_connection((robot_ip, 30003))
253  print("Connected")
254  buf = b''
255  while True:
256  more = rt_socket.recv(4096)
257  if more:
258  buf = buf + more
259  if UR_packet_check(buf):
260  packet_len = UR_packet_size(buf)
261  packet, buf = buf[:packet_len], buf[packet_len:]
262  RUNTIME_MODE = round(UR_packet_value(packet, UR_GET_RUNTIME_MODE, 1)[0])
263  if RUNTIME_MODE_LAST != RUNTIME_MODE:
264  RUNTIME_MODE_LAST = RUNTIME_MODE
265  if RUNTIME_MODE < len(RUNTIME_MODE_MSG):
266  print("POPUP: Robot " + RUNTIME_MODE_MSG[RUNTIME_MODE] + " (transfer in progress, %.1f%% completed)" % percent_cmpl)
267  sys.stdout.flush()
268  else:
269  print("POPUP: Robot Status Unknown (%.i)" % RUNTIME_MODE + " (transfer %.1f%% completed)" % percent_cmpl)
270  sys.stdout.flush()
271 
272  if RUNTIME_MODE == RUNTIME_READY:
273  rt_socket.close()
274  return True
275 
276  rt_socket.close()
277  return False
278 
279 
280 
281 
282 def pose_2_ur(pose):
283  """Calculate the p[x,y,z,rx,ry,rz] position for a pose target"""
284  def saturate_1(value):
285  return min(max(value,-1.0),1.0)
286 
287  angle = acos( saturate_1((pose[0,0]+pose[1,1]+pose[2,2]-1)/2) )
288  rxyz = [pose[2,1]-pose[1,2], pose[0,2]-pose[2,0], pose[1,0]-pose[0,1]]
289 
290  if angle == 0:
291  rxyz = [0,0,0]
292  else:
293  rxyz = normalize3(rxyz)
294  rxyz = mult3(rxyz, angle)
295  return [pose[0,3], pose[1,3], pose[2,3], rxyz[0], rxyz[1], rxyz[2]]
296 
297 def pose_2_str(pose):
298  """Prints a pose target"""
299  [x,y,z,w,p,r] = pose_2_ur(pose)
300  MM_2_M = 0.001
301  return ('p[%.6f, %.6f, %.6f, %.6f, %.6f, %.6f]' % (x*MM_2_M,y*MM_2_M,z*MM_2_M,w,p,r))
302 
303 def angles_2_str(angles):
304  """Prints a joint target"""
305  njoints = len(angles)
306  d2r = pi/180.0
307  if njoints == 6:
308  return ('[%.6f, %.6f, %.6f, %.6f, %.6f, %.6f]' % (angles[0]*d2r, angles[1]*d2r, angles[2]*d2r, angles[3]*d2r, angles[4]*d2r, angles[5]*d2r))
309  else:
310  return 'this post only supports 6 joints'
311 
312 def circle_radius(p0,p1,p2):
313  a = norm(subs3(p0,p1))
314  b = norm(subs3(p1,p2))
315  c = norm(subs3(p2,p0))
316  radius = a*b*c/sqrt(pow(a*a+b*b+c*c,2)-2*(pow(a,4)+pow(b,4)+pow(c,4)))
317  return radius
318 
319 #def distance_p1_p02(p0,p1,p2):
320 # v01 = subs3(p1, p0)
321 # v02 = subs3(p2, p0)
322 # return dot(v02,v01)/dot(v02,v02)
323 
324 # ----------------------------------------------------
325 # Object class that handles the robot instructions/syntax
326 class RobotPost(object):
327  """Robot post object"""
328  MAX_LINES_X_PROG = 250 # Maximum number of lines per program. If the number of lines is exceeded, the program will be executed step by step by RoboDK
329  PROG_EXT = 'script' # set the program extension
330  SPEED_MS = 0.3 # default speed for linear moves in m/s
331  SPEED_RADS = 0.75 # default speed for joint moves in rad/s
332  ACCEL_MSS = 3 # default acceleration for lineaer moves in m/ss
333  ACCEL_RADSS = 1.2 # default acceleration for joint moves in rad/ss
334  BLEND_RADIUS_M = 0.001 # default blend radius in meters (corners smoothing)
335  MOVEC_MIN_RADIUS = 1 # minimum circle radius to output (in mm). It does not take into account the Blend radius
336  MOVEC_MAX_RADIUS = 10000 # maximum circle radius to output (in mm). It does not take into account the Blend radius
337  USE_MOVEP = False
338  #--------------------------------
339  REF_FRAME = eye(4) # default reference frame (the robot reference frame)
340  LAST_POS_ABS = None # last XYZ position
341 
342  # other variables
343  ROBOT_POST = 'unset'
344  ROBOT_NAME = 'generic'
345  PROG_FILES = []
346  MAIN_PROGNAME = 'unknown'
347 
348  nPROGS = 0
349  PROG = []
350  PROG_LIST = []
351  VARS = []
352  VARS_LIST = []
353  SUBPROG = []
354  TAB = ''
355  LOG = ''
356 
357  def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
358  self.ROBOT_POST = robotpost
359  self.ROBOT_NAME = robotname
360  for k,v in kwargs.items():
361  if k == 'lines_x_prog':
363 
364  def ProgStart(self, progname):
365  progname = get_safe_name(progname)
366  self.nPROGS = self.nPROGS + 1
367  if self.nPROGS <= 1:
368  self.TAB = ''
369  # Create global variables:
370  self.vars_update()
371  self.MAIN_PROGNAME = progname
372  else:
373  self.addline('# Subprogram %s' % progname)
374  self.addline('def %s():' % progname)
375  self.TAB = ' '
376 
377  def ProgFinish(self, progname):
378  progname = get_safe_name(progname)
379  self.TAB = ''
380  if self.nPROGS <= 1:
381  self.addline('# End of main program')
382  else:
383  self.addline('end')
384  self.addline('')
385 
386  def ProgSave(self, folder, progname, ask_user = False, show_result = False):
387  progname = get_safe_name(progname)
388  progname = progname + '.script'# + self.PROG_EXT
389  if ask_user or not DirExists(folder):
390  filesave = getSaveFile(folder, progname, 'Save program as...')
391  if filesave is not None:
392  filesave = filesave.name
393  else:
394  return
395  else:
396  filesave = folder + '/' + progname
397 
398  self.prog_2_list()
399 
400  fid = open(filesave, "w")
401  # Create main program call:
402  fid.write('def %s():\n' % self.MAIN_PROGNAME)
403 
404  # Add global parameters:
405  fid.write(' # Global parameters:\n')
406  for line in self.VARS_LIST[0]:
407  fid.write(' ' + line+ '\n')
408  #fid.write(' \n')
409  fid.write(' ')
410 
411  # Add a custom header if desired:
412  fid.write(DEFAULT_HEADER_SCRIPT)
413  fid.write(' \n')
414 
415  # Add the suprograms that are being used in RoboDK
416  for line in self.SUBPROG:
417  fid.write(' ' + line + '\n')
418  fid.write(' \n')
419 
420  # Add the main code:
421  fid.write(' # Main program:\n')
422  for prog in self.PROG_LIST:
423  for line in prog:
424  fid.write(' ' + line + '\n')
425 
426  fid.write('end\n\n')
427  fid.write('%s()\n' % self.MAIN_PROGNAME)
428 
429  fid.close()
430 
431  print('SAVED: %s\n' % filesave) # tell RoboDK the path of the saved file
432  self.PROG_FILES = filesave
433 
434  #---------------------------- SAVE URP (GZIP compressed XML file)-------------------------
435  filesave_urp = filesave[:-7] #+'.urp'
436  fid = open(filesave, "r")
437  prog_final = fid.read()
438  fid.close()
439 
440  try:
441  from html import escape # python 3.x
442  except ImportError:
443  from cgi import escape # python 2.x
444 
445  prog_final_ok = escape(prog_final)
446  self.PROG_XML = SCRIPT_URP % (self.MAIN_PROGNAME, prog_final_ok, self.MAIN_PROGNAME+'.script')
447 
448  # Comment next line to force transfer of the SCRIPT file
449  #self.PROG_FILES = filesave_urp
450 
451  import gzip
452  import os
453  with gzip.open(filesave_urp, 'wb') as fid_gz:
454  fid_gz.write(self.PROG_XML.encode('utf-8'))
455 
456  try:
457  os.remove(filesave_urp+'.urp')
458  except OSError:
459  pass
460 
461  os.rename(filesave_urp, filesave_urp+'.urp')
462 
463  #print('SAVED: %s\n' % filesave_urp) # tell RoboDK the path of the saved file
464  #------------------------------------------------------------------------------------------
465 
466  # open file with default application
467  if show_result:
468  if type(show_result) is str:
469  # Open file with provided application
470  import subprocess
471  p = subprocess.Popen([show_result, filesave])
472  elif type(show_result) is list:
473  import subprocess
474  p = subprocess.Popen(show_result + [filesave])
475  else:
476  # open file with default application
477  os.startfile(filesave)
478  if len(self.LOG) > 0:
479  mbox('Program generation LOG:\n\n' + self.LOG)
480 
481  #if len(self.PROG_LIST) > 1:
482  # 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.")
483 
484 
485  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
486  """Send a program to the robot using the provided parameters. This method is executed right after ProgSave if we selected the option "Send Program to Robot".
487  The connection parameters must be provided in the robot connection menu of RoboDK"""
488  #UploadFTP(self.PROG_FILES, robot_ip, remote_path, ftp_user, ftp_pass)
489  #return
490 
491  nprogs = len(self.PROG_LIST)
492  for i in range(nprogs):
493  # Prepare next program execution:
494  send_str = ''
495  send_str += ('def %s():\n' % self.MAIN_PROGNAME)
496 
497  # Add global parameters:
498  send_str += (' # Global parameters:\n')
499  for line in self.VARS_LIST[i]:
500  send_str += (' ' + line + '\n')
501  send_str += (' \n')
502 
503  # Add a custom header if desired:
504  send_str += (DEFAULT_HEADER_SCRIPT)
505  send_str += (' \n')
506 
507  for line in self.SUBPROG:
508  send_str += ' ' + line+ '\n'
509  send_str += (' \n')
510 
511  # Add the main code:
512  send_str += (' # Main program:\n')
513 
514  for line in self.PROG_LIST[i]:
515  send_str += ' ' + line
516  send_str += '\n'
517 
518  send_str += 'end\n\n'
519  send_str += '%s()\n' % self.MAIN_PROGNAME
520 
521  send_bytes = str.encode(send_str)
522 
523  # Wait until the robot is ready:
524  while i > 0 and not UR_Wait_Ready(robot_ip, i*100.0/nprogs):
525  print("POPUP: Connect robot to run the program program...")
526  sys.stdout.flush()
527  pause(2)
528 
529  # Send script to the robot:
530  #print(send_str)
531  #input("POPUP: Enter to continue")
532  status = UR_SendProgramRobot(robot_ip, send_bytes)
533  while ROBOT_NOT_CONNECTED == status:
534  print("POPUP: Connect robot to transfer program...")
535  sys.stdout.flush()
536  pause(2)
537  status = UR_SendProgramRobot(robot_ip, send_bytes)
538 
539  if status == ROBOT_PROGRAM_ERROR:
540  print("POPUP: Program Error. Running program from the computer Aborted.")
541  sys.stdout.flush()
542  pause(2)
543  return
544 
545 
546  def blend_radius_check(self, pose_abs, ratio_check=0.4):
547  # check that the blend radius covers 40% of the move (at most)
548  blend_radius = 'blend_radius_m';
549  #return blend_radius
550  current_pos = pose_abs.Pos()
551  if self.LAST_POS_ABS is None:
552  blend_radius = '0'
553  else:
554  distance = norm(subs3(self.LAST_POS_ABS, current_pos)) # in mm
555  if ratio_check*distance < self.BLEND_RADIUS_M*1000:
556  blend_radius = '%.3f' % (round(ratio_check*distance*0.001,3))
557  #self.LAST_POS_ABS = current_pos
558  return blend_radius
559 
560  def MoveJ(self, pose, joints, conf_RLF=None):
561  """Add a joint movement"""
562  if pose is None:
563  blend_radius = "0"
564  self.LAST_POS_ABS = None
565  else:
566  pose_abs = self.REF_FRAME*pose
567  blend_radius = self.blend_radius_check(pose_abs)
568  self.LAST_POS_ABS = pose_abs.Pos()
569 
570  if len(joints) < 6:
571  self.RunMessage('Move axes to: ' + angles_2_str(joints))
572  else:
573  self.addline('movej(%s,accel_radss,speed_rads,0,%s)' % (angles_2_str(joints), blend_radius))
574 
575  def MoveL(self, pose, joints, conf_RLF=None):
576  """Add a linear movement"""
577  # Movement in joint space or Cartesian space should give the same result:
578  # pose_wrt_base = self.REF_FRAME*pose
579  # self.addline('movel(%s,accel_mss,speed_ms,0,blend_radius_m)' % (pose_2_str(pose_wrt_base)))
580  if pose is None:
581  blend_radius = "0"
582  self.LAST_POS = None
583  target = angles_2_str(joints)
584  else:
585  pose_abs = self.REF_FRAME*pose
586  blend_radius = self.blend_radius_check(pose_abs)
587  target = pose_2_str(pose_abs)
588  self.LAST_POS_ABS = pose_abs.Pos()
589 
590  if self.USE_MOVEP:
591  self.addline('movep(%s,accel_mss,speed_ms,%s)' % (target, blend_radius))
592  else:
593  self.addline('movel(%s,accel_mss,speed_ms,0,%s)' % (target, blend_radius))
594 
595 
596  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
597  """Add a circular movement"""
598  pose1_abs = self.REF_FRAME*pose1
599  pose2_abs = self.REF_FRAME*pose2
600  p0 = self.LAST_POS_ABS
601  p1 = pose1_abs.Pos()
602  p2 = pose2_abs.Pos()
603  if p0 is None:
604  self.MoveL(pose2, joints2, conf_RLF_2)
605  return
606 
607  radius = circle_radius(p0, p1, p2)
608  print("MoveC Radius: " + str(radius) + " mm")
609  if radius < self.MOVEC_MIN_RADIUS or radius > self.MOVEC_MAX_RADIUS:
610  self.MoveL(pose2, joints2, conf_RLF_2)
611  return
612 
613  blend_radius = self.blend_radius_check(pose1_abs, 0.2)
614  #blend_radius = '%.3f' % (0.001*radius) #'0'
615  #blend_radius = '0'
616  self.LAST_POS_ABS = pose2_abs.Pos()
617  #self.addline('movec(%s,%s,accel_mss,speed_ms,%s)' % (angles_2_str(joints1),angles_2_str(joints2), blend_radius))
618  self.addline('movec(%s,%s,accel_mss,speed_ms,%s)' % (pose_2_str(pose1_abs),pose_2_str(pose2_abs), blend_radius))
619 
620  def setFrame(self, pose, frame_id=None, frame_name=None):
621  """Change the robot reference frame"""
622  # the reference frame is not needed if we use joint space for joint and linear movements
623  # the reference frame is also not needed if we use cartesian moves with respect to the robot base frame
624  # the cartesian targets must be pre-multiplied by the active reference frame
625  self.REF_FRAME = pose
626  self.addline('# set_reference(%s)' % pose_2_str(pose))
627 
628  def setTool(self, pose, tool_id=None, tool_name=None):
629  """Change the robot TCP"""
630  self.addline('set_tcp(%s)' % pose_2_str(pose))
631  #self.addline('set_payload(1.4, [-0.1181, -0.1181, 0.03])')
632  #self.addline('set_gravity([0.0, 0.0, 9.82]))')
633 
634  def Pause(self, time_ms):
635  """Pause the robot program"""
636  if time_ms <= 0:
637  self.addline('halt() # reimplement this function to force stop')
638  else:
639  self.addline('sleep(%.3f)' % (time_ms*0.001))
640 
641  def setSpeed(self, speed_mms):
642  """Changes the robot speed (in mm/s)"""
643  #if speed_mms < 999.9:
644  # self.USE_MOVEP = True
645  #else:
646  # self.USE_MOVEP = False
647  self.SPEED_MS = speed_mms/1000.0
648  self.addline('speed_ms = %.3f' % self.SPEED_MS)
649 
650  def setAcceleration(self, accel_mmss):
651  """Changes the robot acceleration (in mm/s2)"""
652  self.ACCEL_MSS = accel_mmss/1000.0
653  self.addline('accel_mss = %.3f' % self.ACCEL_MSS)
654 
655  def setSpeedJoints(self, speed_degs):
656  """Changes the robot joint speed (in deg/s)"""
657  self.SPEED_RADS = speed_degs*pi/180
658  self.addline('speed_rads = %.3f' % self.SPEED_RADS)
659 
660  def setAccelerationJoints(self, accel_degss):
661  """Changes the robot joint acceleration (in deg/s2)"""
662  self.ACCEL_RADSS = accel_degss*pi/180
663  self.addline('accel_radss = %.3f' % self.ACCEL_RADSS)
664 
665  def setZoneData(self, zone_mm):
666  """Changes the zone data approach (makes the movement more smooth)"""
667  if zone_mm < 0:
668  zone_mm = 0
669  self.BLEND_RADIUS_M = zone_mm / 1000.0
670  self.addline('blend_radius_m = %.3f' % self.BLEND_RADIUS_M)
671 
672  def setDO(self, io_var, io_value):
673  """Sets a variable (output) to a given value"""
674  if type(io_value) != str: # set default variable value if io_value is a number
675  if io_value > 0:
676  io_value = 'True'
677  else:
678  io_value = 'False'
679 
680  if type(io_var) != str: # set default variable name if io_var is a number
681  newline = 'set_standard_digital_out(%s, %s)' % (str(io_var), io_value)
682  else:
683  newline = '%s = %s' % (io_var, io_value)
684 
685  self.addline(newline)
686 
687  def waitDI(self, io_var, io_value, timeout_ms=-1):
688  """Waits for an input io_var to attain a given value io_value. Optionally, a timeout can be provided."""
689  if type(io_var) != str: # set default variable name if io_var is a number
690  io_var = 'get_standard_digital_in(%s)' % str(io_var)
691  if type(io_value) != str: # set default variable value if io_value is a number
692  if io_value > 0:
693  io_value = 'True'
694  else:
695  io_value = 'False'
696 
697  # at this point, io_var and io_value must be string values
698  #if timeout_ms < 0:
699  self.addline('while (%s != %s):' % (io_var, io_value))
700  self.addline(' sync()')
701  self.addline('end')
702 
703  def RunCode(self, code, is_function_call = False):
704  """Adds code or a function call"""
705  if is_function_call:
706  code = get_safe_name(code)
707  if code.lower() == "usemovel":
708  self.USE_MOVEP = False
709  return
710  elif code.lower() == "usemovep":
711  self.USE_MOVEP = False
712  return
713 
714  if not code.endswith(')'):
715  code = code + '()'
716  self.addline(code)
717  else:
718  #self.addline(code)
719  self.addline('# ' + code) #generate custom code as a comment
720 
721  def RunMessage(self, message, iscomment = False):
722  """Show a message on the controller screen"""
723  if iscomment:
724  self.addline('# ' + message)
725  else:
726  self.addline('popup("%s","Message",False,False,blocking=True)' % message)
727 
728 # ------------------ private ----------------------
729  def vars_update(self):
730  # Generate global variables for this program
731  self.VARS = []
732  self.VARS.append('global speed_ms = %.3f' % self.SPEED_MS)
733  self.VARS.append('global speed_rads = %.3f' % self.SPEED_RADS)
734  self.VARS.append('global accel_mss = %.3f' % self.ACCEL_MSS)
735  self.VARS.append('global accel_radss = %.3f' % self.ACCEL_RADSS)
736  self.VARS.append('global blend_radius_m = %.3f' % self.BLEND_RADIUS_M)
737 
738  def prog_2_list(self):
739  if len(self.PROG) > 1:
740  self.PROG_LIST.append(self.PROG)
741  self.PROG = []
742  self.VARS_LIST.append(self.VARS)
743  self.VARS = []
744  self.vars_update()
745 
746  def addline(self, newline):
747  """Add a program line"""
748  if self.nPROGS <= 1:
749  if len(self.PROG) > self.MAX_LINES_X_PROG:
750  self.prog_2_list()
751 
752  self.PROG.append(self.TAB + newline)
753  else:
754  self.SUBPROG.append(self.TAB + newline)
755 
756  def addlog(self, newline):
757  """Add a log message"""
758  self.LOG = self.LOG + newline + '\n'
759 
760 # -------------------------------------------------
761 # ------------ For testing purposes ---------------
762 def Pose(xyzrpw):
763  [x,y,z,r,p,w] = xyzrpw
764  a = r*math.pi/180
765  b = p*math.pi/180
766  c = w*math.pi/180
767  ca = math.cos(a)
768  sa = math.sin(a)
769  cb = math.cos(b)
770  sb = math.sin(b)
771  cc = math.cos(c)
772  sc = math.sin(c)
773  return Mat([[cb*ca, ca*sc*sb - cc*sa, sc*sa + cc*ca*sb, x],[cb*sa, cc*ca + sc*sb*sa, cc*sb*sa - ca*sc, y],[-sb, cb*sc, cc*cb, z],[0,0,0,1]])
774 
775 def test_post():
776  """Test the post with a basic program"""
777 
778  robot = RobotPost('Universal Robotics', 'Generic UR robot')
779 
780  robot.ProgStart("Program")
781  robot.RunMessage("Program generated by RoboDK", True)
782  robot.setFrame(Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
783  robot.setTool(Pose([62.5, -108.253175, 100, -60, 90, 0]))
784  robot.setSpeed(100) # set speed to 100 mm/s
785  robot.setAcceleration(3000) # set speed to 3000 mm/ss
786  robot.MoveJ(Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
787  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
788  robot.MoveL(Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
789  robot.RunMessage("Setting air valve 1 on")
790  robot.RunCode("TCP_On", True)
791  robot.Pause(1000)
792  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
793  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
794  robot.MoveL(Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
795  robot.RunMessage("Setting air valve off")
796  robot.RunCode("TCP_Off", True)
797  robot.Pause(1000)
798  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
799  robot.MoveL(Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
800  robot.MoveL(Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
801  robot.ProgFinish("Program")
802  # robot.ProgSave(".","Program",True)
803  for line in robot.PROG:
804  print(line)
805  if len(robot.LOG) > 0:
806  mbox('Program generation LOG:\n\n' + robot.LOG)
807 
808  input("Press Enter to close...")
809 
810 if __name__ == "__main__":
811  """Function to call when the module is executed by itself: test"""
812  test_post()
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 setFrame(self, pose, frame_id=None, frame_name=None)
def RunCode(self, code, is_function_call=False)
def setTool(self, pose, tool_id=None, tool_name=None)
def waitDI(self, io_var, io_value, timeout_ms=-1)
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
Definition: robodk.py:1458
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
def blend_radius_check(self, pose_abs, ratio_check=0.4)
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
Definition: robodk.py:1354
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)


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