KUKA_KRC4_Config.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 Kuka 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 
49 HEADER = ''';FOLD INI
50 BAS (#INITMOV,0 )
51 ;ENDFOLD (INI)
52 
53 ;FOLD STARTPOS
54 $BWDSTART = FALSE
55 PDAT_ACT = {VEL 50,ACC 100,APO_DIST 10}
56 BAS(#PTP_DAT)
57 FDAT_ACT = {TOOL_NO 0,BASE_NO 0,IPO_FRAME #BASE}
58 BAS (#FRAMES)
59 BAS (#VEL_PTP,50)
60 ;ENDFOLD
61 
62 
63 ;FOLD SET DEFAULT SPEED
64 $VEL.CP=0.2
65 BAS(#VEL_PTP,50)
66 BAS(#TOOL,0)
67 BAS(#BASE,0)
68 ;ENDFOLD
69 
70 ;FOLD PTP FIRST POSITION
71 $BWDSTART = FALSE
72 PDAT_ACT = {VEL 50,ACC 100,APO_DIST 10}
73 FDAT_ACT = {TOOL_NO 0,BASE_NO 0,IPO_FRAME #BASE}
74 BAS(#FRAMES)
75 $ADVANCE = 5
76 ;ENDFOLD
77 
78 PTP $AXIS_ACT ; skip BCO quickly
79 '''
80 
81 # ----------------------------------------------------
82 def pose_2_str(pose):
83  """Converts a pose target to a string"""
84  #[x,y,z,w,p,r] = Pose_2_KUKA(pose)
85  #return ('X %.3f, Y %.3f, Z %.3f, A %.3f, B %.3f, C %.3f' % (x,y,z,r,p,w)) # old version had to be switched
86  [x,y,z,r,p,w] = pose_2_xyzrpw(pose)
87  return ('X %.3f,Y %.3f,Z %.3f,A %.3f,B %.3f,C %.3f' % (x,y,z,w,p,r))
88 
89 def pose_2_str_ext(pose,joints):
90  njoints = len(joints)
91  if njoints <= 6:
92  return pose_2_str(pose)
93  else:
94  extaxes = ''
95  for i in range(njoints-6):
96  extaxes = extaxes + (',E%i %.5f' % (i+1, joints[i+6]))
97  return pose_2_str(pose) + extaxes
98 
99 def angles_2_str(angles):
100  """Prints a joint target"""
101  str = 'AXIS: '
102  data = ['A1','A2','A3','A4','A5','A6','E1','E2','E3','E4','E5','E6']
103  for i in range(len(angles)):
104  str = str + ('%s %.5f,' % (data[i], angles[i]))
105  str = str[:-1]
106  return str
107 
108 def conf_2_str(confRLF):
109  if confRLF is None:
110  return "'B010'"
111  strconf = ""
112  if confRLF[2] > 0:
113  strconf = strconf + '1'
114  else:
115  strconf = strconf + '0'
116 
117  if confRLF[1] == 0:
118  strconf = strconf + '1'
119  else:
120  strconf = strconf + '0'
121 
122  if confRLF[0] > 0:
123  strconf = strconf + '1'
124  else:
125  strconf = strconf + '0'
126 
127  return "'B%s'" % strconf
128 
129 def joints_2_turn_str(joints):
130  if joints is None:
131  return "'B000000'"
132 
133  strturn = ""
134  for i in range(len(joints)):
135  if joints[i] < 0:
136  strturn = '1' + strturn
137  else:
138  strturn = '0' + strturn
139  return "'B%s'" % strturn
140 
141 
142 # ----------------------------------------------------
143 # Object class that handles the robot instructions/syntax
144 class RobotPost(object):
145  """Robot post object"""
146  PROG_EXT = 'src' # set the program extension
147 
148  # other variables
149  ROBOT_POST = ''
150  ROBOT_NAME = ''
151  PROG_FILES = []
152 
153  PROG = ''
154  LOG = ''
155  nAxes = 6
156  APO_VALUE = 1
157  C_DIS = ' C_DIS'
158  C_PTP = ' C_PTP'
159 
160 
161  def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
162  self.ROBOT_POST = robotpost
163  self.ROBOT_NAME = robotname
164  self.PROG = ''
165  self.LOG = ''
166  self.nAxes = robot_axes
167 
168  def ProgStart(self, progname):
169  self.addline('DEF %s ( )' % progname)
170  self.PROG = self.PROG + HEADER
171  #if self.nAxes > 6:
172  #self.addline('$ACT_EX_AX = %i' % (self.nAxes-6))
173 
174  def ProgFinish(self, progname):
175  self.addline('END')
176 
177  def ProgSave(self, folder, progname, ask_user = False, show_result = False):
178  progname = progname + '.' + self.PROG_EXT
179  if ask_user or not DirExists(folder):
180  filesave = getSaveFile(folder, progname, 'Save program as...')
181  if filesave is not None:
182  filesave = filesave.name
183  else:
184  return
185  else:
186  filesave = folder + '/' + progname
187  fid = open(filesave, "w")
188  fid.write(self.PROG)
189  fid.close()
190  print('SAVED: %s\n' % filesave) # tell RoboDK the path of the saved file
191  self.PROG_FILES = filesave
192 
193  # open file with default application
194  if show_result:
195  if type(show_result) is str:
196  # Open file with provided application
197  import subprocess
198  p = subprocess.Popen([show_result, filesave])
199  elif type(show_result) is list:
200  import subprocess
201  p = subprocess.Popen(show_result + [filesave])
202  else:
203  # open file with default application
204  import os
205 
206  os.startfile(filesave)
207  if len(self.LOG) > 0:
208  mbox('Program generation LOG:\n\n' + self.LOG)
209 
210  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
211  """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".
212  The connection parameters must be provided in the robot connection menu of RoboDK"""
213  UploadFTP(self.PROG_FILES, robot_ip, remote_path, ftp_user, ftp_pass)
214 
215  def MoveJ(self, pose, joints, conf_RLF=None):
216  """Add a joint movement"""
217  self.addline('PTP {' + angles_2_str(joints) + '}' + self.C_PTP)
218 
219  def MoveL(self, pose, joints, conf_RLF=None):
220  """Add a linear movement"""
221  #self.addline('LIN {' + pose_2_str_ext(pose,joints) + '}' + self.C_DIS)
222  self.addline('LIN {%s, S %s, T %s}%s' % (pose_2_str_ext(pose,joints), conf_2_str(conf_RLF), joints_2_turn_str(joints), self.C_DIS))
223  #; PTP {POS:X 2318.172,Y -484.024,Z 1193.129,A 146.186,B -5.002,C 152.404,S 'B010',T 'B101010'}
224 
225  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
226  """Add a circular movement"""
227  #self.addline('CIRC {' + pose_2_str_ext(pose1,joints1) + '},{' + pose_2_str_ext(pose2,joints2) + '}' + self.C_DIS)
228  self.addline('CIRC {%s},{%s, S %s, T %s}%s' % (pose_2_str_ext(pose1,joints1), pose_2_str_ext(pose2,joints2), conf_2_str(conf_RLF_2), joints_2_turn_str(joints2), self.C_DIS))
229 
230  def setFrame(self, pose, frame_id=None, frame_name=None):
231  """Change the robot reference frame"""
232  self.addline('$BASE = {FRAME: ' + pose_2_str(pose) + '}')
233 
234  def setTool(self, pose, tool_id=None, tool_name=None):
235  """Change the robot TCP"""
236  self.addline('$TOOL = {FRAME: ' + pose_2_str(pose) + '}')
237 
238  def Pause(self, time_ms):
239  """Pause the robot program"""
240  if time_ms <= 0:
241  self.addline('HALT')
242  else:
243  self.addline('WAIT SEC %.3f' % (time_ms*0.001))
244 
245  def setSpeed(self, speed_mms):
246  """Changes the robot speed (in mm/s)"""
247  self.addline('$VEL.CP = %.5f' % (speed_mms/1000.0))
248 
249  def setAcceleration(self, accel_mmss):
250  """Changes the current robot acceleration"""
251  self.addlog('setAcceleration not defined')
252 
253  def setSpeedJoints(self, speed_degs):
254  """Changes the robot joint speed (in deg/s)"""
255  self.addlog('setSpeedJoints not defined')
256 
257  def setAccelerationJoints(self, accel_degss):
258  """Changes the robot joint acceleration (in deg/s2)"""
259  self.addlog('setAccelerationJoints not defined')
260 
261  def setZoneData(self, zone_mm):
262  """Changes the zone data approach (makes the movement more smooth)"""
263  self.APO_VALUE = zone_mm
264  if zone_mm >= 0:
265  self.addline('$APO.CPTP = %.3f' % zone_mm)
266  self.addline('$APO.CDIS = %.3f' % zone_mm)
267  C_DIS = ' C_DIS'
268  C_PTP = ' C_PTP'
269  else:
270  C_DIS = ''
271  C_PTP = ''
272 
273  def setDO(self, io_var, io_value):
274  """Sets a variable (output) to a given value"""
275  if type(io_var) != str: # set default variable name if io_var is a number
276  io_var = '$OUT[%s]' % str(io_var)
277  if type(io_value) != str: # set default variable value if io_value is a number
278  if io_value > 0:
279  io_value = 'TRUE'
280  else:
281  io_value = 'FALSE'
282 
283  # at this point, io_var and io_value must be string values
284  self.addline('%s=%s' % (io_var, io_value))
285 
286  def waitDI(self, io_var, io_value, timeout_ms=-1):
287  """Waits for an input io_var to attain a given value io_value. Optionally, a timeout can be provided."""
288  if type(io_var) != str: # set default variable name if io_var is a number
289  io_var = '$IN[%s]' % str(io_var)
290  if type(io_value) != str: # set default variable value if io_value is a number
291  if io_value > 0:
292  io_value = 'TRUE'
293  else:
294  io_value = 'FALSE'
295 
296  # at this point, io_var and io_value must be string values
297  if timeout_ms < 0:
298  self.addline('WAIT FOR (%s==%s)' % (io_var, io_value))
299  else:
300  self.addline('START_TIMER:')
301  self.addline('$TIMER_STOP[1]=TRUE')
302  self.addline('$TIMER_FLAG[1]=FALSE')
303  self.addline('$TIMER[1]=%.3f' % (float(timeout_ms)*0.001))
304  self.addline('$TIMER_STOP[1]=FALSE')
305  self.addline('WAIT FOR (%s==%s OR $TIMER_FLAG[1])' % (io_var, io_value))
306  self.addline('$TIMER_STOP[1]=TRUE')
307  self.addline('IF $TIMER_FLAG[1]== TRUE THEN')
308  self.addline(' HALT ; Timed out!')
309  self.addline(' GOTO START_TIMER')
310  self.addline('ENDIF')
311 
312  def RunCode(self, code, is_function_call = False):
313  """Adds code or a function call"""
314  if is_function_call:
315  code.replace(' ','_')
316  if not code.endswith(')'):
317  code = code + '()'
318  self.addline(code)
319  else:
320  self.addline(code)
321 
322  def RunMessage(self, message, iscomment = False):
323  """Add a joint movement"""
324  if iscomment:
325  self.addline('; ' + message)
326  else:
327  self.addline('Wait for StrClear($LOOP_MSG[])')
328  self.addline('$LOOP_CONT = TRUE')
329  self.addline('$LOOP_MSG[] = "%s"' % message)
330 
331 # ------------------ private ----------------------
332  def addline(self, newline):
333  """Add a program line"""
334  self.PROG = self.PROG + newline + '\n'
335 
336  def addlog(self, newline):
337  """Add a log message"""
338  self.LOG = self.LOG + newline + '\n'
339 
340 # -------------------------------------------------
341 # ------------ For testing purposes ---------------
342 def Pose(xyzrpw):
343  [x,y,z,r,p,w] = xyzrpw
344  a = r*math.pi/180
345  b = p*math.pi/180
346  c = w*math.pi/180
347  ca = math.cos(a)
348  sa = math.sin(a)
349  cb = math.cos(b)
350  sb = math.sin(b)
351  cc = math.cos(c)
352  sc = math.sin(c)
353  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]])
354 
355 def test_post():
356  """Test the post with a basic program"""
357 
358  robot = RobotPost('Kuka_custom', 'Generic Kuka')
359 
360  robot.ProgStart("Program")
361  robot.RunMessage("Program generated by RoboDK", True)
362  robot.setFrame(Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
363  robot.setTool(Pose([62.5, -108.253175, 100, -60, 90, 0]))
364  robot.MoveJ(Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
365  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
366  robot.MoveL(Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
367  robot.RunMessage("Setting air valve 1 on")
368  robot.RunCode("TCP_On", True)
369  robot.Pause(1000)
370  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
371  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
372  robot.MoveL(Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
373  robot.RunMessage("Setting air valve off")
374  robot.RunCode("TCP_Off", True)
375  robot.Pause(1000)
376  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
377  robot.MoveL(Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
378  robot.MoveL(Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
379  robot.ProgFinish("Program")
380  # robot.ProgSave(".","Program",True)
381  print(robot.PROG)
382  if len(robot.LOG) > 0:
383  mbox('Program generation LOG:\n\n' + robot.LOG)
384 
385  input("Press Enter to close...")
386 
387 if __name__ == "__main__":
388  """Function to call when the module is executed by itself: test"""
389  test_post()
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
def UploadFTP(program, robot_ip, remote_path, ftp_user, ftp_pass)
Definition: robodk.py:1312
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
def setTool(self, pose, tool_id=None, tool_name=None)
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
def setFrame(self, pose, frame_id=None, frame_name=None)
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
Definition: robodk.py:1458
def RunCode(self, code, is_function_call=False)
def waitDI(self, io_var, io_value, timeout_ms=-1)
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
Definition: robodk.py:1354


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