AUBO.py
Go to the documentation of this file.
1 # Copyright 2018 - 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 an AUBO 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/PythonAPI/postprocessor.html
41 # ----------------------------------------------------
42 
43 
44 # ----------------------------------------------------
45 # Import RoboDK tools
46 from robodk import *
47 
48 XML_HEADER = '''<?xml version="1.0" encoding="UTF-8"?>
49 <ProcedureProgram>
50  <Condition ConditionType="Procedure_Program" ConditionAlias="Procedure_Program" ConditionUuid="%s">
51  <Attribute/>
52 '''
53 
54 XML_CLOSING = ''' </Condition>
55 </ProcedureProgram>
56 '''
57 
58 XML_MOVEJ = ''' <Condition ConditionType="Move" ConditionAlias="HOME" ConditionUuid="%s">
59  <Attribute>
60  <MoveConditionMode>MoveJoint</MoveConditionMode>
61  <ArrivalAheadThreshold>0</ArrivalAheadThreshold>
62  <ArrivalAheadType>None</ArrivalAheadType>
63  <EnableArrivalAhead>false</EnableArrivalAhead>
64  <EnableOffset>false</EnableOffset>
65  <JointAcc>%s,%s,%s,%s,%s,%s</JointAcc>
66  <JointSpeed>%s,%s,%s,%s,%s,%s</JointSpeed>
67  <OffsetCoordName></OffsetCoordName>
68  <OffsetX></OffsetX>
69  <OffsetY></OffsetY>
70  <OffsetZ></OffsetZ>
71  </Attribute>
72  <Condition ConditionType="Waypoint" ConditionAlias="Waypoint" ConditionUuid="%s">
73  <Attribute>
74  <WaypointConditionMode>FixedPoint</WaypointConditionMode>
75  <FixedPoint>%s</FixedPoint>
76  </Attribute>
77  </Condition>
78  </Condition>'''
79 
80 XML_MOVEL = ''' <Condition ConditionType="Move" ConditionAlias="Move" ConditionUuid="%s">
81  <Attribute>
82  <MoveConditionMode>MoveJoint</MoveConditionMode>
83  <ArrivalAheadThreshold>0</ArrivalAheadThreshold>
84  <ArrivalAheadType>None</ArrivalAheadType>
85  <EnableArrivalAhead>false</EnableArrivalAhead>
86  <EnableOffset>false</EnableOffset>
87  <JointAcc>%s,%s,%s,%s,%s,%s</JointAcc>
88  <JointSpeed>%s,%s,%s,%s,%s,%s</JointSpeed>
89  <OffsetCoordName></OffsetCoordName>
90  <OffsetX></OffsetX>
91  <OffsetY></OffsetY>
92  <OffsetZ></OffsetZ>
93  </Attribute>
94  <Condition ConditionType="Waypoint" ConditionAlias="Waypoint" ConditionUuid="%s">
95  <Attribute>
96  <WaypointConditionMode>FixedPoint</WaypointConditionMode>
97  <FixedPoint>%s</FixedPoint>
98  </Attribute>
99  </Condition>
100  </Condition>'''
101 
102 def new_uuid():
103  import uuid
104  return str(uuid.uuid4()).replace('-','')
105 
106 # ----------------------------------------------------
107 
108 def pose_2_ur(pose):
109  """Calculate the p[x,y,z,rx,ry,rz] position for a pose target"""
110  def saturate_1(value):
111  return min(max(value,-1.0),1.0)
112 
113  angle = acos( saturate_1((pose[0,0]+pose[1,1]+pose[2,2]-1)/2) )
114  rxyz = [pose[2,1]-pose[1,2], pose[0,2]-pose[2,0], pose[1,0]-pose[0,1]]
115 
116  if angle == 0:
117  rxyz = [0,0,0]
118  else:
119  rxyz = normalize3(rxyz)
120  rxyz = mult3(rxyz, angle)
121  return [pose[0,3], pose[1,3], pose[2,3], rxyz[0], rxyz[1], rxyz[2]]
122 
123 def pose_2_str(pose):
124  """Prints a pose target"""
125  [x,y,z,w,p,r] = pose_2_ur(pose)
126  M_2_MM = 0.001
127  return ('p[%.6f, %.6f, %.6f, %.6f, %.6f, %.6f]' % (x*M_2_MM,y*M_2_MM,z*M_2_MM,w,p,r))
128 
129 def joints_2_str(angles):
130  """Prints a joint target"""
131  njoints = len(angles)
132  d2r = pi/180.0
133  if njoints == 6:
134  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))
135  else:
136  return 'this post only supports 6 joints'
137 
138 # ----------------------------------------------------
139 # Object class that handles the robot instructions/syntax
140 class RobotPost(object):
141  """Robot post object"""
142  PROG_EXT = 'aubo' # set the program extension
143  SPEED_MS = 0.25 # default speed for linear moves in m/s
144  SPEED_RADS = 0.3 # default speed for joint moves in rad/s
145  ACCEL_MSS = 0.25 # default acceleration for lineaer moves in m/ss
146  ACCEL_RADSS = 1.1 # default acceleration for joint moves in rad/ss
147 
148  SPEED_MS_CURR = SPEED_MS # current speed set by user
149  SPEED_RADS_CURR = SPEED_RADS # current speed set by user
150  ACCEL_MSS_CURR = ACCEL_MSS # current acceleration set by user
151  ACCEL_RADSS_CURR = ACCEL_RADSS # current acceleration set by user
152 
153  BLEND_RADIUS_M = 0.001 # default blend radius in meters (corners smoothing)
154  REF_FRAME = eye(4) # default reference frame (the robot reference frame)
155  LAST_POS = None # last XYZ position
156 
157  # other variables
158  ROBOT_POST = 'unset'
159  ROBOT_NAME = 'generic'
160  PROG_FILES = []
161  MAIN_PROGNAME = 'unknown'
162 
163  XML_UUID_MAIN = None
164  XML_TARGETS = ''
165 
166  nPROGS = 0
167  PROG = []
168  PROG_XML = []
169  SUBPROG = []
170  TAB = ''
171  LOG = ''
172 
173  def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
174  self.ROBOT_POST = robotpost
175  self.ROBOT_NAME = robotname
176 
177  def ProgStart(self, progname):
178  self.nPROGS = self.nPROGS + 1
179  if self.nPROGS <= 1:
180  self.TAB = ' '
181  self.MAIN_PROGNAME = progname
182  else:
183  self.addline(' # Subprogram %s' % progname)
184  self.addline(' def %s():' % progname)
185  self.TAB = ' '
186 
187  def ProgFinish(self, progname):
188  self.TAB = ''
189  if self.nPROGS <= 1:
190  self.addline('--End of main program')
191  else:
192  self.addline('--End of main program')
193 
194  self.addline('')
195 
196  def ProgSave(self, folder, progname, ask_user = False, show_result = False):
197  self.PROG.append('%s()' % self.MAIN_PROGNAME)
198  progname = progname + '.' + self.PROG_EXT
199  if ask_user or not DirExists(folder):
200  filesave = getSaveFile(folder, progname, 'Save program as...')
201  if filesave is not None:
202  filesave = filesave.name
203  else:
204  return
205  else:
206  filesave = folder + '/' + progname
207 
208  fid = open(filesave, "w")
209  #for line in self.SUBPROG:
210  # fid.write(line)
211 
212  fid.write('--Main program:\n')
213  for line in self.PROG:
214  fid.write(line)
215 
216  fid.close()
217  print('SAVED: %s\n' % filesave) # tell RoboDK the path of the saved file
218 
219  filesave_xml = filesave[:-4] + 'xml'
220  fid2 = open(filesave_xml, "w")
221  fid2.write(XML_HEADER)
222  for block in self.PROG_XML:
223  fid2.write(block)
224 
225  fid2.close()
226  #print('SAVED: %s\n' % filesave_xml) # tell RoboDK the path of the saved file
227 
228  self.PROG_FILES = [filesave, filesave_xml]
229 
230  # open file with default application
231  if show_result:
232  if type(show_result) is str:
233  # Open file with provided application
234  import subprocess
235  p = subprocess.Popen([show_result, filesave, filesave_xml])
236  else:
237  # open file with default application
238  import os
239  os.startfile(filesave)
240  if len(self.LOG) > 0:
241  mbox('Program generation LOG:\n\n' + self.LOG)
242 
243  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
244  """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".
245  The connection parameters must be provided in the robot connection menu of RoboDK"""
246  UploadFTP(self.PROG_FILES, robot_ip, remote_path, ftp_user, ftp_pass)
247  return
248 
249  with open(self.PROG_FILES, 'rb') as progfile:
250  import socket
251  print("POPUP: Connecting to robot...")
252  sys.stdout.flush()
253  robot_socket = socket.create_connection((robot_ip, 30002))
254  file_str = progfile.read()
255  print("POPUP: Sending program...")
256  sys.stdout.flush()
257  robot_socket.send(file_str)
258  received = robot_socket.recv(4096)
259  robot_socket.close()
260  print("POPUP: Program sent. The program should be running on the robot.")
261  sys.stdout.flush()
262  if received:
263  print("POPUP: Program running")
264  sys.stdout.flush()
265  else:
266  print("POPUP: Problems running program...")
267  sys.stdout.flush()
268 
269  pause(2)
270 
271  def MoveJ(self, pose, joints, conf_RLF=None):
272  """Add a joint movement"""
273  if pose is None:
274  self.LAST_POS = None
275 
276  randid = new_uuid() # Instruction
277  randid2 = new_uuid() # waypoint
278 
279  aj = round(self.ACCEL_RADSS_CURR/17.296*100)
280  sj = round(self.SPEED_RADS_CURR/2.618*100)
281  self.addxml(XML_MOVEJ % (randid, aj, aj, aj, aj, aj, aj, sj, sj, sj, sj, sj, sj, randid2, joints_2_str(joints)))
282 
283  self.addline('--(Logic tree item : Move) Move')
284  self.addline('init_global_move_profile()')
285  j_vel = self.SPEED_RADS_CURR
286  j_acc = self.ACCEL_RADSS_CURR
287  self.addline('set_joint_maxvelc({%f,%f,%f,%f,%f,%f})' % (j_vel,j_vel,j_vel,j_vel*121/101,j_vel*121/101,j_vel*121/101))
288  self.addline('set_joint_maxacc({%f,%f,%f,%f,%f,%f})' % (j_acc,j_acc,j_acc,j_acc*121/101,j_acc*121/101,j_acc*121/101))
289  self.addline(' --(Logic tree item : Waypoint) Waypoint')
290  self.addline(' set_current_logic_tree_item("%s")' % randid2)
291  self.addline(' move_joint({%s}, true)' % joints_2_str(joints))
292  self.addline(' set_step_breakpoint()')
293 
294 
295  def MoveL(self, pose, joints, conf_RLF=None):
296  """Add a linear movement"""
297  # Movement in joint space or Cartesian space should give the same result:
298  # pose_wrt_base = self.REF_FRAME*pose
299 
300  randid = new_uuid() # Instruction
301  randid2 = new_uuid() # waypoint
302 
303  if pose is None:
304  self.LAST_POS = None
305  target = joints_2_str(joints)
306  else:
307  target = pose_2_str(self.REF_FRAME*pose)
308  al = round(self.ACCEL_MSS_CURR/2*100)
309  sl = round(self.SPEED_MS_CURR/2*100)
310  self.addxml(XML_MOVEL % (randid, al, al, al, al, al, al, sl, sl, sl, sl, sl, sl, randid2, joints_2_str(joints)))
311 
312  self.addline('--(Logic tree item : Move) Move')
313  self.addline('init_global_move_profile()')
314  l_vel = self.SPEED_MS_CURR
315  l_acc = self.ACCEL_MSS_CURR
316  self.addline('set_end_maxvelc(%s)' % l_vel)
317  self.addline('set_end_maxacc(%s)' % l_acc)
318  self.addline(' set_current_logic_tree_item("%s")' % randid2)
319  self.addline(' move_line({%s}, true)' % joints_2_str(joints))
320  self.addline(' set_step_breakpoint()')
321 
322 
323  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
324  """Add a circular movement"""
325  def circle_radius(p0,p1,p2):
326  a = norm(subs3(p0,p1))
327  b = norm(subs3(p1,p2))
328  c = norm(subs3(p2,p0))
329  radius = a*b*c/sqrt(pow(a*a+b*b+c*c,2)-2*(pow(a,4)+pow(b,4)+pow(c,4)))
330  return radius
331 
332  def distance_p1_p02(p0,p1,p2):
333  v01 = subs3(p1, p0)
334  v02 = subs3(p2, p0)
335  return dot(v02,v01)/dot(v02,v02)
336 
337  p0 = self.LAST_POS
338  p1 = pose1.Pos()
339  p2 = pose2.Pos()
340  if p0 is None:
341  self.MoveL(pose2, joints2, conf_RLF_2)
342  return
343 
344  radius = circle_radius(p0, p1, p2)
345  if radius < 1 or radius > 100000:
346  self.MoveL(pose2, joints2, conf_RLF_2)
347  return
348 
349  d_p1_p02 = distance_p1_p02(p0, p1, p2)
350  if d_p1_p02 < 1:
351  self.MoveL(pose2, joints2, conf_RLF_2)
352  return
353 
354  self.LAST_POS = pose2.Pos()
355  self.addline('movec(%s,%s,accel_mss,speed_ms,%s)' % (pose_2_str(self.REF_FRAME*pose1),pose_2_str(self.REF_FRAME*pose2), blend_radius))
356 
357  def setFrame(self, pose, frame_id=None, frame_name=None):
358  """Change the robot reference frame"""
359  # the reference frame is not needed if we use joint space for joint and linear movements
360  # the reference frame is also not needed if we use cartesian moves with respect to the robot base frame
361  # the cartesian targets must be pre-multiplied by the active reference frame
362  self.REF_FRAME = pose
363  #self.addline('# set_reference(%s)' % pose_2_str(pose))
364 
365  def setTool(self, pose, tool_id=None, tool_name=None):
366  """Change the robot TCP"""
367  self.addline('set_tcp(%s)' % pose_2_str(pose))
368 
369  def Pause(self, time_ms):
370  """Pause the robot program"""
371  if time_ms <= 0:
372  self.addline('halt() # reimplement this function to force stop')
373  else:
374  self.addline('--(Logic tree item : Wait) Wait')
375  self.addline('set_current_logic_tree_item("")')
376  self.addline('sleep(%.3f)' % (time_ms*0.001))
377  self.addline('set_step_breakpoint()')
378 
379  def setSpeed(self, speed_mms):
380  """Changes the robot speed (in mm/s)"""
381  if speed_mms >= 2000:
382  speed_mms = 2000
383  self.SPEED_MS_CURR = speed_mms/1000.0
384 
385  def setAcceleration(self, accel_mmss):
386  """Changes the robot acceleration (in mm/s2)"""
387  if accel_mmss >= 2000:
388  accel_mmss = 2000
389  self.ACCEL_MSS_CURR = accel_mmss/1000.0
390 
391  def setSpeedJoints(self, speed_degs):
392  """Changes the robot joint speed (in deg/s)"""
393  if speed_degs >= 150:
394  speed_degs = 150
395  self.SPEED_RADS_CURR = speed_degs*pi/180
396 
397  def setAccelerationJoints(self, accel_degss):
398  """Changes the robot joint acceleration (in deg/s2)"""
399  if accel_degss >= 991:
400  accel_degss = 991
401  self.ACCEL_RADSS_CURR = accel_degss*pi/180
402 
403  def setZoneData(self, zone_mm):
404  """Changes the zone data approach (makes the movement more smooth)"""
405  if zone_mm < 0:
406  zone_mm = 0
407  self.BLEND_RADIUS_M = zone_mm / 1000.0
408 
409  def RunCode(self, code, is_function_call = False):
410  """Adds code or a function call"""
411  if is_function_call:
412  code.replace(' ','_')
413  if not code.endswith(')'):
414  code = code + '()'
415  self.addline(code)
416  else:
417  #self.addline(code)
418  self.addline('# ' + code) #generate custom code as a comment
419 
420  def RunMessage(self, message, iscomment = False):
421  """Show a message on the controller screen"""
422  if iscomment:
423  self.addline('# ' + message)
424  else:
425  self.addline('popup("%s","Message",False,False,blocking=True)' % message)
426 
427 # ------------------ private ----------------------
428  def addline(self, newline):
429  """Add a program line"""
430  if self.nPROGS <= 1:
431  self.PROG.append(self.TAB + newline + '\n')
432  else:
433  self.SUBPROG.append(self.TAB + newline + '\n')
434 
435  def addxml(self, newblock):
436  """Add a program line"""
437  if self.nPROGS <= 1:
438  self.PROG_XML.append(newblock + '\n')
439  else:
440  raise Exception("This post does not support automatic program splitting")
441 
442  def addlog(self, newline):
443  """Add a log message"""
444  self.LOG = self.LOG + newline + '\n'
445 
446 # -------------------------------------------------
447 # ------------ For testing purposes ---------------
448 def Pose(xyzrpw):
449  [x,y,z,r,p,w] = xyzrpw
450  a = r*math.pi/180
451  b = p*math.pi/180
452  c = w*math.pi/180
453  ca = math.cos(a)
454  sa = math.sin(a)
455  cb = math.cos(b)
456  sb = math.sin(b)
457  cc = math.cos(c)
458  sc = math.sin(c)
459  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]])
460 
461 def test_post():
462  """Test the post with a basic program"""
463 
464  robot = RobotPost('Universal Robotics', 'Generic UR robot')
465 
466  robot.ProgStart("Program")
467  robot.RunMessage("Program generated by RoboDK", True)
468  robot.setFrame(Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
469  robot.setTool(Pose([62.5, -108.253175, 100, -60, 90, 0]))
470  robot.setSpeed(100) # set speed to 100 mm/s
471  robot.setAcceleration(3000) # set speed to 3000 mm/ss
472  robot.MoveJ(Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
473  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
474  robot.MoveL(Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
475  robot.RunMessage("Setting air valve 1 on")
476  robot.RunCode("TCP_On", True)
477  robot.Pause(1000)
478  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
479  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
480  robot.MoveL(Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
481  robot.RunMessage("Setting air valve off")
482  robot.RunCode("TCP_Off", True)
483  robot.Pause(1000)
484  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
485  robot.MoveL(Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
486  robot.MoveL(Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
487  robot.ProgFinish("Program")
488  # robot.ProgSave(".","Program",True)
489  for line in robot.PROG:
490  print(line[:-1])
491  if len(robot.LOG) > 0:
492  mbox('Program generation LOG:\n\n' + robot.LOG)
493 
494  input("Press Enter to close...")
495 
496 if __name__ == "__main__":
497  """Function to call when the module is executed by itself: test"""
498  test_post()
def MoveJ(self, pose, joints, conf_RLF=None)
Definition: AUBO.py:271
def MoveL(self, pose, joints, conf_RLF=None)
Definition: AUBO.py:295
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
Definition: AUBO.py:173
def setFrame(self, pose, frame_id=None, frame_name=None)
Definition: AUBO.py:357
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
Definition: AUBO.py:323
def UploadFTP(program, robot_ip, remote_path, ftp_user, ftp_pass)
Definition: robodk.py:1312
def RunMessage(self, message, iscomment=False)
Definition: AUBO.py:420
def setAccelerationJoints(self, accel_degss)
Definition: AUBO.py:397
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
Definition: robodk.py:1458
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
Definition: AUBO.py:196
def setSpeedJoints(self, speed_degs)
Definition: AUBO.py:391
def setAcceleration(self, accel_mmss)
Definition: AUBO.py:385
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
Definition: robodk.py:1354
def RunCode(self, code, is_function_call=False)
Definition: AUBO.py:409
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
Definition: AUBO.py:243
def setTool(self, pose, tool_id=None, tool_name=None)
Definition: AUBO.py:365


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