ABB_RAPID_S4C.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 an ABB robot with RoboDK
15 #
16 # To edit/test this POST PROCESSOR script file:
17 # Select "Program"->"Add/Edit Post Processor", then select your post or create a new one.
18 # You can edit this file using any text editor or Python editor. Using a Python editor allows to quickly evaluate a sample program at the end of this file.
19 # Python should be automatically installed with RoboDK
20 #
21 # You can also edit the POST PROCESSOR manually:
22 # 1- Open the *.py file with Python IDLE (right click -> Edit with IDLE)
23 # 2- Make the necessary changes
24 # 3- Run the file to open Python Shell: Run -> Run module (F5 by default)
25 # 4- The "test_post()" function is called automatically
26 # Alternatively, you can edit this file using a text editor and run it with Python
27 #
28 # To use a POST PROCESSOR file you must place the *.py file in "C:/RoboDK/Posts/"
29 # To select one POST PROCESSOR for your robot in RoboDK you must follow these steps:
30 # 1- Open the robot panel (double click a robot)
31 # 2- Select "Parameters"
32 # 3- Select "Unlock advanced options"
33 # 4- Select your post as the file name in the "Robot brand" box
34 #
35 # To delete an existing POST PROCESSOR script, simply delete this file (.py file)
36 #
37 # ----------------------------------------------------
38 # More information about RoboDK Post Processors and Offline Programming here:
39 # http://www.robodk.com/help#PostProcessor
40 # http://www.robodk.com/doc/en/PythonAPI/postprocessor.html
41 # ----------------------------------------------------
42 
43 
44 # ----------------------------------------------------
45 # Import RoboDK tools
46 from robodk import *
47 
48 ONETAB = ' ' # one tab equals 2 spaces
49 
50 # Define a custom header (variable declaration)
51 CUSTOM_HEADER = '''
52  ! -------------------------------
53  ! Define your variables here
54  ! ...
55  '''
56 
57 # Define your custom programs (predefined functions, not altered by RoboDK):
58 CUSTOM_FUNCTIONS = '''
59  ! -------------------------------
60  ! Define your functions here
61  ! ...
62  '''
63 
64 # ----------------------------------------------------
65 def pose_2_str(pose):
66  """Prints a pose target"""
67  [x,y,z,q1,q2,q3,q4] = Pose_2_ABB(pose)
68  return ('[%.3f,%.3f,%.3f],[%.6f,%.6f,%.6f,%.6f]' % (x,y,z,q1,q2,q3,q4))
69 
70 def angles_2_str(angles):
71  """Prints a joint target"""
72  njoints = len(angles)
73  # extend the joint target if the robot has less than 6 degrees of freedom
74  if njoints < 6:
75  angles.extend([0]*(6-njoints))
76  # Generate a string like:
77  # [10,20,30,40,50,60]
78  # with up to 6 decimals
79  return '[%s]' % (','.join(format(ji, ".6f") for ji in angles[0:6]))
80 
81 def extaxes_2_str(angles):
82  """Prints the external axes, if any"""
83  # extend the joint target if the robot has less than 6 degrees of freedom
84  njoints = len(angles)
85  if njoints <= 6:
86  # should print 9E9 for unset external axes
87  # [9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]
88  return '[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]'
89  extaxes_str = (','.join(format(ji, ".6f") for ji in angles[6:njoints]))
90  if njoints < 12:
91  extaxes_str = extaxes_str + ',' + ','.join(['9E9']*(12-njoints))
92  # If angles is [j1,j2,j3,j4,j5,j6,10,20], it will generate a string like:
93  # [10,20,9E9,9E9,9E9,9E9]
94  # with up to 6 decimals
95  return '[%s]' % extaxes_str
96 
97 # ----------------------------------------------------
98 # Object class that handles the robot instructions/syntax
99 class RobotPost(object):
100  """Robot post object"""
101  PROG_EXT = 'prg' # set the program extension
102 
103  # other variables
104  ROBOT_POST = 'unset'
105  ROBOT_NAME = 'generic'
106  PROG_FILES = []
107 
108  nPROGS = 0
109  PROG = ''
110  TAB = ''
111  LOG = ''
112  FRAME_REF = eye(4)
113  TOOL_REF_FIRST = None
114  MOD_NAME = 'module'
115  ZONEDATA = 'fine'
116  SPEEDDATA = '[500,500,5000,1000]'
117  FRAME_NAME = 'rdkWObj'
118  TOOL_NAME = 'rdkTool'
119 
120  def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
121  self.ROBOT_POST = robotpost
122  self.ROBOT_NAME = robotname
123  self.PROG = ''
124  self.LOG = ''
125 
126  def ProgStart(self, progname):
127  self.nPROGS = self.nPROGS + 1
128  if self.nPROGS == 1:
129  self.MOD_NAME = progname
130  self.TAB = ONETAB
131  #self.addline('PROC main()')
132  self.addline('PROC %s()' % progname)
133  else:
134  self.TAB = ONETAB
135  self.addline('PROC %s()' % progname)
136  self.TAB = ONETAB + ONETAB # instructions need two tabs
137 
138  def ProgFinish(self, progname):
139  self.TAB = ONETAB
140  self.addline('ENDPROC')
141 
142  def ProgSave(self, folder, progname, ask_user = False, show_result = False):
143  self.addline('')
144  self.TAB = ''
145  self.addline('ENDMODULE')
146  progname = progname + '.' + self.PROG_EXT
147  if ask_user or not DirExists(folder):
148  filesave = getSaveFile(folder, progname, 'Save program as...')
149  if filesave is not None:
150  filesave = filesave.name
151  else:
152  return
153  else:
154  filesave = folder + '/' + progname
155  fid = open(filesave, "w")
156  fid.write('%%%\n')
157  fid.write(' VERSION:1\n')
158  fid.write(' LANGUAGE:ENGLISH\n')
159  fid.write('%%%\n')
160  fid.write('\n')
161  fid.write('MODULE MOD_%s\n' % self.MOD_NAME)
162  fid.write(' \n')
163  if self.TOOL_REF_FIRST is None:
164  self.TOOL_REF_FIRST = eye(4)
165  fid.write(' PERS tooldata rdkTool := [TRUE,[%s],[2,[0,0,15],[1,0,0,0],0,0,0.005]];\n' % pose_2_str(self.TOOL_REF_FIRST))
166  fid.write(' PERS wobjdata rdkWObj := [FALSE, TRUE, "", [[0,0,0],[1,0,0,0]],[[0,0,0],[1,0,0,0]]];\n')
167  #fid.write(CUSTOM_HEADER)
168  #fid.write(CUSTOM_FUNCTIONS)
169  fid.write(' \n')
170  fid.write(self.PROG)
171  fid.close()
172  print('SAVED: %s\n' % filesave) # tell RoboDK the path of the saved file
173  self.PROG_FILES = filesave
174 
175  # open file with default application
176  if show_result:
177  if type(show_result) is str:
178  # Open file with provided application
179  import subprocess
180  p = subprocess.Popen([show_result, filesave])
181  elif type(show_result) is list:
182  import subprocess
183  p = subprocess.Popen(show_result + [filesave])
184  else:
185  # open file with default application
186  import os
187  os.startfile(filesave)
188  if len(self.LOG) > 0:
189  mbox('Program generation LOG:\n\n' + self.LOG)
190 
191  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
192  """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".
193  The connection parameters must be provided in the robot connection menu of RoboDK"""
194  UploadFTP(self.PROG_FILES, robot_ip, remote_path, ftp_user, ftp_pass)
195 
196  def MoveJ(self, pose, joints, conf_RLF=None):
197  """Add a joint movement"""
198  #self.addline('MoveAbsJ [%s,%s],%s,%s,%s,\WObj:=%s;' % (angles_2_str(joints), extaxes_2_str(joints), self.SPEEDDATA, self.ZONEDATA, self.TOOL_NAME, self.FRAME_NAME))
199  self.addline('MoveAbsJ [%s,%s],%s,%s,%s,\WObj:=rdkWObj;' % (angles_2_str(joints), extaxes_2_str(joints), self.SPEEDDATA, self.ZONEDATA, self.TOOL_NAME))
200 
201  def MoveL(self, pose, joints, conf_RLF=None):
202  """Add a linear movement"""
203  #self.addline('MoveL [%s,[0,0,0,0],%s],%s,%s,%s,\WObj:=%s;' % (pose_2_str(pose), extaxes_2_str(joints), self.SPEEDDATA, self.ZONEDATA, self.TOOL_NAME, self.FRAME_NAME))
204  if conf_RLF is None:
205  conf_RLF = [0,0,0]
206  #self.addline('MoveL [%s,[0,0,0,0],%s],%s,%s,rdkTool,\WObj:=rdkWObj;' % (pose_2_str(pose), extaxes_2_str(joints), self.SPEEDDATA, self.ZONEDATA))
207  [REAR, LOWERARM, FLIP] = conf_RLF
208  cf1 = math.floor(joints[0]/90.0)
209  cf4 = math.floor(joints[3]/90.0)
210  cf6 = math.floor(joints[5]/90.0)
211  cfx = 4*REAR + 2*LOWERARM + FLIP
212  #self.addline('MoveL [%s,[%i,%i,%i,%i],%s],%s,%s,%s,\WObj:=%s;' % (pose_2_str(pose), extaxes_2_str(joints), self.SPEEDDATA, self.ZONEDATA, self.TOOL_NAME, self.FRAME_NAME))
213  #self.addline('MoveL [%s,[%i,%i,%i,%i],%s],%s,%s,%s,\WObj:=%s;' % (pose_2_str(pose), cf1, cf4, cf6,cfx, extaxes_2_str(joints), self.SPEEDDATA, self.ZONEDATA, self.TOOL_NAME, self.FRAME_NAME))
214  self.addline('MoveL [%s,[%i,%i,%i,%i],%s],%s,%s,%s,\WObj:=rdkWObj;' % (pose_2_str(self.FRAME_REF*pose), cf1, cf4, cf6,cfx, extaxes_2_str(joints), self.SPEEDDATA, self.ZONEDATA, self.TOOL_NAME))
215 
216 
217  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
218  """Add a circular movement"""
219  if conf_RLF_1 is None:
220  conf_RLF_1 = [0,0,0]
221  if conf_RLF_2 is None:
222  conf_RLF_2 = [0,0,0]
223 
224  cf1_1 = 0
225  cf4_1 = 0
226  cf6_1 = 0
227  if joints1 is not None:
228  cf1_1 = math.floor(joints1[0]/90.0)
229  cf4_1 = math.floor(joints1[3]/90.0)
230  cf6_1 = math.floor(joints1[5]/90.0)
231  [REAR, LOWERARM, FLIP] = conf_RLF_1
232  cfx_1 = 4*REAR + 2*LOWERARM + FLIP
233 
234  cf1_2 = 0
235  cf4_2 = 0
236  cf6_2 = 0
237  if joints2 is not None:
238  cf1_2 = math.floor(joints2[0]/90.0)
239  cf4_2 = math.floor(joints2[3]/90.0)
240  cf6_2 = math.floor(joints2[5]/90.0)
241  [REAR, LOWERARM, FLIP] = conf_RLF_2
242  cfx_2 = 4*REAR + 2*LOWERARM + FLIP
243  self.addline('MoveC [%s,[%i,%i,%i,%i],%s],[%s,[%i,%i,%i,%i],%s],%s,%s,rdkTool,\WObj:=rdkWObj;' % (pose_2_str(pose1), cf1_1, cf4_1, cf6_1,cfx_1, extaxes_2_str(joints1), pose_2_str(pose2), cf1_2, cf4_2, cf6_2,cfx_2, extaxes_2_str(joints2), self.SPEEDDATA, self.ZONEDATA))
244 
245 
246  def setFrame(self, pose, frame_id=None, frame_name=None):
247  """Change the robot reference frame"""
248  #self.addline('rdkWObj := [FALSE, TRUE, "", [%s],[[0,0,0],[1,0,0,0]]];' % pose_2_str(pose))
249  #if frame_name == None:
250  # frame_name = self.FRAME_NAME
251  #frame_name = frame_name.replace(' ','_')
252  #self.FRAME_NAME = frame_name
253  self.FRAME_REF = pose
254  #self.addline('%s := [FALSE, TRUE, "", [%s],[[0,0,0],[1,0,0,0]]];' % (self.FRAME_NAME, pose_2_str(pose)))
255 
256  def setTool(self, pose, tool_id=None, tool_name=None):
257  """Change the robot TCP"""
258  #if tool_name == None:
259  # tool_name = self.TOOL_NAME
260  #tool_name = tool_name.replace(' ','_')
261  #self.TOOL_NAME = tool_name
262  if self.TOOL_REF_FIRST is None:
263  self.TOOL_REF_FIRST = pose
264  else:
265  self.addline('%s := [TRUE,[%s],[2,[0,0,50],[1,0,0,0],0,0,0.005]];' % (self.TOOL_NAME, pose_2_str(pose)))
266 
267  def Pause(self, time_ms):
268  """Pause the robot program"""
269  if time_ms <= 0:
270  self.addline('STOP;')
271  else:
272  self.addline('WaitTime %.3f' % (time_ms*0.001))
273 
274  def setSpeed(self, speed_mms):
275  """Changes the robot speed (in mm/s)"""
276  self.SPEEDDATA = '[%.2f,500,5000,1000]' % speed_mms
277 
278  def setAcceleration(self, accel_mmss):
279  """Changes the robot acceleration (in mm/s2)"""
280  self.addlog('setAcceleration is not defined')
281 
282  def setSpeedJoints(self, speed_degs):
283  """Changes the robot joint speed (in deg/s)"""
284  self.addlog('setSpeedJoints not defined')
285 
286  def setAccelerationJoints(self, accel_degss):
287  """Changes the robot joint acceleration (in deg/s2)"""
288  self.addlog('setAccelerationJoints not defined')
289 
290  def setZoneData(self, zone_mm):
291  """Changes the zone data approach (makes the movement more smooth)"""
292  if zone_mm < 0:
293  self.ZONEDATA = 'fine'
294  else:
295  self.ZONEDATA = 'z%i' % zone_mm
296 
297  def setDO(self, io_var, io_value):
298  """Sets a variable (output) to a given value"""
299  if type(io_var) != str: # set default variable name if io_var is a number
300  io_var = 'D_OUT_%s' % str(io_var)
301  if type(io_value) != str: # set default variable value if io_value is a number
302  if io_value > 0:
303  io_value = '1'
304  else:
305  io_value = '0'
306 
307  # at this point, io_var and io_value must be string values
308  self.addline('SetDO %s, %s;' % (io_var, io_value))
309 
310  def waitDI(self, io_var, io_value, timeout_ms=-1):
311  """Waits for an input io_var to attain a given value io_value. Optionally, a timeout can be provided."""
312  if type(io_var) != str: # set default variable name if io_var is a number
313  io_var = 'D_IN_%s' % str(io_var)
314  if type(io_value) != str: # set default variable value if io_value is a number
315  if io_value > 0:
316  io_value = '1'
317  else:
318  io_value = '0'
319 
320  # at this point, io_var and io_value must be string values
321  if timeout_ms < 0:
322  self.addline('WaitDI %s, %s;' % (io_var, io_value))
323  else:
324  self.addline('WaitDI %s, %s, \MaxTime:=%.1f;' % (io_var, io_value, timeout_ms*0.001))
325 
326  def RunCode(self, code, is_function_call = False):
327  """Adds code or a function call"""
328  if is_function_call:
329  code = code.replace(' ','_')
330  self.addline(code + ';')
331  else:
332  if code.startswith('END') or code.startswith('ELSEIF'):
333  # remove tab after ENDWHILE or ENDIF
334  self.TAB = self.TAB[:-len(ONETAB)]
335 
336  self.addline(code.replace('\t',' '))# replace each tab by 2 spaces
337 
338  if code.startswith('IF ') or code.startswith('ELSEIF ') or code.startswith('WHILE '):
339  # add tab (one tab = two spaces)
340  self.TAB = self.TAB + ONETAB
341 
342 
343  def RunMessage(self, message, iscomment = False):
344  """Add a joint movement"""
345  if iscomment:
346  self.addline('! ' + message)
347  else:
348  self.addline('TPWrite "%s";' % message)
349 
350 # ------------------ private ----------------------
351  def addline(self, newline):
352  """Add a program line"""
353  self.PROG = self.PROG + self.TAB + newline + '\n'
354 
355  def addlog(self, newline):
356  """Add a log message"""
357  self.LOG = self.LOG + newline + '\n'
358 
359  def addcode(self, code):
360  """Adds custom code, such as a custom header"""
361  self.PROG = self.PROG + code
362 
363 # -------------------------------------------------
364 # ------------ For testing purposes ---------------
365 def Pose(xyzrpw):
366  [x,y,z,r,p,w] = xyzrpw
367  a = r*math.pi/180
368  b = p*math.pi/180
369  c = w*math.pi/180
370  ca = math.cos(a)
371  sa = math.sin(a)
372  cb = math.cos(b)
373  sb = math.sin(b)
374  cc = math.cos(c)
375  sc = math.sin(c)
376  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]])
377 
378 def test_post():
379  """Test the post with a basic program"""
380 
381  robot = RobotPost('ABB RAPID custom', 'Generic ABB robot')
382 
383  robot.ProgStart("Program")
384  robot.RunMessage("Program generated by RoboDK", True)
385  robot.setFrame(Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
386  robot.setTool(Pose([62.5, -108.253175, 100, -60, 90, 0]))
387  robot.MoveJ(Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
388  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
389  robot.MoveL(Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
390  robot.RunMessage("Setting air valve 1 on")
391  robot.RunCode("TCP_On", True)
392  robot.Pause(1000)
393  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
394  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
395  robot.MoveL(Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
396  robot.RunMessage("Setting air valve off")
397  robot.RunCode("TCP_Off", True)
398  robot.Pause(1000)
399  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
400  robot.MoveL(Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
401  robot.MoveL(Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
402  robot.ProgFinish("Program")
403  # robot.ProgSave(".","Program",True)
404  print(robot.PROG)
405  if len(robot.LOG) > 0:
406  mbox('Program generation LOG:\n\n' + robot.LOG)
407 
408  input("Press Enter to close...")
409 
410 if __name__ == "__main__":
411  """Function to call when the module is executed by itself: test"""
412  test_post()
def setTool(self, pose, tool_id=None, tool_name=None)
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
def UploadFTP(program, robot_ip, remote_path, ftp_user, ftp_pass)
Definition: robodk.py:1312
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
Definition: robodk.py:1458
def waitDI(self, io_var, io_value, timeout_ms=-1)
def setFrame(self, pose, frame_id=None, frame_name=None)
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
def RunMessage(self, message, iscomment=False)
def MoveJ(self, pose, joints, conf_RLF=None)
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
Definition: robodk.py:1354
def RunCode(self, code, is_function_call=False)
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
def MoveL(self, pose, joints, conf_RLF=None)


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