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


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