Siemens_Sinumerik_Inch.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 sample POST PROCESSOR script to generate robot programs for a
14 # Siemens controller (Siemens Sinumerik programming language)
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 # Customize the following parameters:
45 M_WAIT_DI = 'M66' # Provide the M code to wait for a digital input
46 M_SET_DO_HIGH = 'M62' # Provide the M code to set a digital output HIGH (1 or True)
47 M_SET_DO_LOW = 'M62' # Provide the M code to set a digital output LOW (0 or False)
48 
49 #MM_2_UNITS = 1.0 # Use Millimeter units
50 MM_2_UNITS = 1.0/25.4 # Use Inch units
51 
52 
53 # ----------------------------------------------------
54 # Import RoboDK tools
55 from robodk import *
56 
57 def conf_2_STAT(confRLF):
58  if confRLF is None:
59  return 2 #"'B010'"
60  config = 0
61  if confRLF[2] > 0:
62  config = config + 4
63 
64  if confRLF[1] == 0:
65  config = config + 2
66 
67  if confRLF[0] > 0:
68  config = config + 1
69 
70  return config
71 
72 def joints_2_TU(joints):
73  if joints is None:
74  return 0 # "'B000000'"
75 
76  turn = 0
77  njoints = len(joints)
78  for i in range(njoints):
79  if joints[i] < 0:
80  turn = turn + 2**(njoints-1-i)
81  return turn
82 
83 
84 # ----------------------------------------------------
85 # Object class that handles the robot instructions/syntax
86 class RobotPost(object):
87  """Robot post object"""
88  PROG_EXT = 'mpf' # set the program extension
89 
90  # other variables
91  ROBOT_POST = ''
92  ROBOT_NAME = ''
93  PROG_FILES = []
94 
95  PROG = ''
96  PROG_COUNT = 0
97  LOG = ''
98  nAxes = 6
99  nId = 0
100  REF_FRAME = eye(4)
101  INV_TOOL_FRAME = eye(4) # Force TC_DCP to 0 by post multiplying poses
102 
103  SPEED_UNITS_MIN = 5000 * MM_2_UNITS
104  SPEED_DEG_MIN = 2000
105  Nline = 0
106 
107  LAST_X = None
108  LAST_Y = None
109  LAST_Z = None
110  LAST_POSE = None
111  TRAORI = None
112 
113 
114  # ----------------------------------------------------
115  def pose_2_str(self, pose, remember_last=False):
116  """Prints a pose target"""
117  [x,y,z,a,b,c] = Pose_2_Staubli(pose)
118  x = x * MM_2_UNITS
119  y = y * MM_2_UNITS
120  z = z * MM_2_UNITS
121  if remember_last:
122  G_LINE = ''
123  if self.LAST_X != x:
124  G_LINE += 'X%.3f ' % x
125  if self.LAST_Y != y:
126  G_LINE += 'Y%.3f ' % y
127  if self.LAST_Z != z or len(G_LINE) == 0:
128  G_LINE += 'Z%.3f ' % z
129  G_LINE += 'A=%.3f ' % a
130  G_LINE += 'B=%.3f ' % b
131  G_LINE += 'C=%.3f ' % c
132  self.LAST_X = x
133  self.LAST_Y = y
134  self.LAST_Z = z
135  G_LINE = G_LINE[:-1]
136  return G_LINE
137  else:
138  return ('X%.3f Y%.3f Z%.3f A%.3f B%.3f C%.3f' % (x,y,z,a,b,c))
139 
140  def joints_2_str(self, joints):
141  """Prints a joint target"""
142  str = ''
143  data = ['JT1','JT2','JT3','A','B','C','G','H','I','J','K','L']
144  for i in range(len(joints)):
145  str = str + ('%s=%.6f ' % (data[i], joints[i]))
146  str = str[:-1]
147  return str
148 
149 
150  def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
151  self.ROBOT_POST = robotpost
152  self.ROBOT_NAME = robotname
153  self.PROG = ''
154  self.LOG = ''
155  self.nAxes = robot_axes
156 
157  def ProgStart(self, progname):
158  self.PROG_COUNT = self.PROG_COUNT + 1
159  if self.PROG_COUNT <= 1:
160  import datetime
161  self.addcomment('File: %s' % progname)
162  self.addcomment('Created on %s' % datetime.datetime.now().strftime("%Y-%m-%d %H:%M:%S"))
163  self.addcomment('Program created using RoboDK')
164  if MM_2_UNITS == 1.0:
165  self.addline('G17 G710 G40 ; XY plane selection, metric, no tool radius compensation')
166  elif MM_2_UNITS == 1.0/25.4:
167  self.addline('G17 G700 G40 ; XY plane selection, inch')
168  else:
169  raise Exception("Unknown units!! Define MM_2_UNITS properly.")
170 
171  self.addline('TRAORI')
172  self.TRAORI = True
173  self.addline('M32')
174  self.addline('G54')
175  self.addline('G90') # Absolute coordinates G91 (relative)
176  self.addline('G64')
177  #self.addline('; $P_UIFR[1]=CTRANS(X,0,Y,0,Z,0):CROT(X,0,Y,0,Z,0) ; Clear reference frame')
178  #self.addline('G54')
179  self.addline('ORIWKS') # Use custom work coordinate system and how they are interpreted
180  self.addline('ORIVIRT1')
181  #self.addline('; CYCLE832(0.001,_ORI_FINISH,0.01) ; contour smoothing (requires appropriate license)')
182  #self.addline('PTPG0') # Do not output. If we used G0 it would not work.
183  self.addline('STOPRE ; stop preprocessing')
184  self.addline('; R6=1.181')
185  self.addline('; R19=0.00')
186  self.addline('; R20=83.00')
187  #self.addcomment('R19 = Part Area in SqFt')
188  #self.addcomment('R20 = Variable to set the F speed')
189  self.addline('STOPRE')
190  #self.addcomment('T1 BLADE1')
191  #self.addcomment('T1 D1 ; should be called after setting the TCP')
192  self.addline('; M3 S7458 ; Generic way to turn on the spindle') # Generic way to turn on the spindle
193  self.addline('S1700.0 M80 ; Customized Spindle speed and power on')
194  self.addcomment('---- Program start ----')
195 
196  else:
197  self.addcomment('')
198  self.addcomment('---------- Subprogram: %s ----------' % progname)
199  #self.addline('PROC %s' % progname)
200  self.addline('%s:' % progname)
201  self.addline('TRAORI')
202  self.TRAORI = True
203 
204 
205  def ProgFinish(self, progname):
206  if self.PROG_COUNT <= 1:
207  self.addcomment('End of main program ' + progname)
208  self.addline('M30')
209  self.addcomment('---------------------------')
210  self.addcomment('')
211  else:
212  #self.addline('RET("%s_done")' % progname) # needs to be in a file as SPF
213  #self.addline('M17 ; end of subprogram %s' % progname) # needs to be in a file as SPF
214  self.addline('GOTOB ' + progname + "_done")
215  self.addcomment('------------------------------------')
216  self.addcomment('')
217 
218  def ProgSave(self, folder, progname, ask_user=False, show_result=False):
219  progname = progname + '.' + self.PROG_EXT
220  if ask_user or not DirExists(folder):
221  filesave = getSaveFile(folder, progname, 'Save program as...')
222  if filesave is not None:
223  filesave = filesave.name
224  else:
225  return
226  else:
227  filesave = folder + '/' + progname
228  fid = open(filesave, "w")
229  fid.write(self.PROG)
230  fid.close()
231  print('SAVED: %s\n' % filesave)
232  #---------------------- show result
233  if show_result:
234  if type(show_result) is str:
235  # Open file with provided application
236  import subprocess
237  p = subprocess.Popen([show_result, filesave])
238  elif type(show_result) is list:
239  import subprocess
240  p = subprocess.Popen(show_result + [filesave])
241  else:
242  # open file with default application
243  import os
244  os.startfile(filesave)
245 
246  if len(self.LOG) > 0:
247  mbox('Program generation LOG:\n\n' + self.LOG)
248 
249  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
250  """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".
251  The connection parameters must be provided in the robot connection menu of RoboDK"""
252  UploadFTP(self.PROG_FILES, robot_ip, remote_path, ftp_user, ftp_pass)
253 
255  if not self.TRAORI:
256  self.TRAORI = True
257  self.addline('TRAORI')
258  self.addline('G54')
259 
260  def set_joint_space(self):
261  if self.TRAORI:
262  self.TRAORI = False
263  self.addline('TRAFOOF')
264 
265  def MoveJ(self, pose, joints, conf_RLF=None):
266  """Add a joint movement"""
267  self.set_joint_space()
268  self.addline('G1 ' + self.joints_2_str(joints) + ' F%.1f' % self.SPEED_DEG_MIN)
269  #self.addline('G0 ' + self.joints_2_str(joints)) # G0 is the fastest
270  if pose is not None:
271  self.addline('; TRAORI')
272  self.addline('; PTP G1 ' + self.pose_2_str(self.REF_FRAME * pose * self.INV_TOOL_FRAME, True) + ' STAT=%i TU=%i F%.1f ; same joint coordinate' % (conf_2_STAT(conf_RLF), joints_2_TU(joints), self.SPEED_UNITS_MIN))
273  self.addline('; TRAFOOF')
274 
275  self.LAST_POSE = None
276 
277  def MoveL(self, pose, joints, conf_RLF=None):
278  """Add a linear movement"""
279  if pose is None:
280  self.set_joint_space()
281  self.addline('G1 ' + self.joints_2_str(joints) + ' F%.1f' % self.SPEED_UNITS_MIN)
282  else:
283  self.set_cartesian_space()
284  self.addline('G1 ' + self.pose_2_str(self.REF_FRAME * pose * self.INV_TOOL_FRAME, True) + ' F%.1f' % self.SPEED_UNITS_MIN)
285  #self.addline('PTP G1 ' + self.pose_2_str(self.REF_FRAME * pose * self.INV_TOOL_FRAME, True) + ' STAT=%i TU=%i F%.1f' % (conf_2_STAT(conf_RLF), joints_2_TU(joints), self.SPEED_UNITS_MIN))
286  # Note: it is important to have
287  return
288 
289  if self.LAST_POSE is None:
290  self.addline('G1 ' + self.pose_2_str(self.REF_FRAME * pose * self.INV_TOOL_FRAME, True) + ' F%.1f' % self.SPEED_UNITS_MIN)
291  else:
292  pose_shift = invH(self.LAST_POSE)*pose
293  angle = pose_angle(pose_shift)*180/pi
294 
295  x,y,z,w,p,r = Pose_2_UR(pose_shift)
296  x = x * MM_2_UNITS
297  y = y * MM_2_UNITS
298  z = z * MM_2_UNITS
299 
300  steps = int(angle/(1))
301  steps = float(max(1,steps))
302  self.addline('; next move %.1f deg divided in %i steps' % (angle, steps))
303  xd = x/steps
304  yd = y/steps
305  zd = z/steps
306  wd = w/steps
307  pd = p/steps
308  rd = r/steps
309  for i in range(int(steps)):
310  factor = i+1
311  hi = UR_2_Pose([xd*factor,yd*factor,zd*factor,wd*factor,pd*factor,rd*factor])
312  self.addline('G1 ' + self.pose_2_str(self.REF_FRAME*self.LAST_POSE*hi*self.INV_TOOL_FRAME, True) + ' F%.1f' % self.SPEED_UNITS_MIN)
313 
314  self.LAST_POSE = pose
315 
316  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
317  """Add a circular movement"""
318  self.nId = self.nId + 1
319  xyz1 = (self.REF_FRAME*pose1*self.INV_TOOL_FRAME).Pos()
320  xyz2 = (self.REF_FRAME*pose2*self.INV_TOOL_FRAME).Pos()
321  #xyz1 = (pose1).Pos()
322  #xyz2 = (pose2).Pos()
323  self.addline('G2 X%.3f Y%.3f Z%.3f I1=%.3f J1=%.3f K1=%.3f F%.1f' % (xyz2[0], xyz2[1], xyz2[2], xyz1[0], xyz1[1], xyz1[2], self.SPEED_UNITS_MIN))
324 
325  def setFrame(self, pose, frame_id=None, frame_name=None):
326  """Change the robot reference frame"""
327  self.addcomment('------ Update reference: %s ------' % (frame_name if frame_name is not None else ''))
328  #self.addline('TRAORI')
329  self.set_cartesian_space()
330  #if frame_id is not None and frame_id > 0:
331  # self.addcomment('Using controller definition for tool %i' % frame_id)
332  # self.addline('G%i' % (frame_id+54-1))
333  # return
334 
335  [x,y,z,a,b,c] = Pose_2_Staubli(pose)
336  x = x * MM_2_UNITS
337  y = y * MM_2_UNITS
338  z = z * MM_2_UNITS
339  self.addline('$P_UIFR[1]=CTRANS(X,%.5f,Y,%.5f,Z,%.5f):CROT(X,%.5f,Y,%.5f,Z,%.5f)' % (x,y,z,a,b,c))
340  self.addline('G54')
341  self.addcomment('---------------------------')
342 
343  def setTool(self, pose, tool_id=None, tool_name=None):
344  """Change the robot TCP"""
345  #if tool_id is not None and tool_id > 0:
346  # self.addline('T%i D1' % tool_id)
347  # self.addcomment('Using controller definition for tool %i' % frame_id)
348  # return
349 
350  self.nId = self.nId + 1
351  self.addcomment('------ Update TCP: %s ------' % (tool_name if tool_name is not None else ''))
352  self.set_cartesian_space()#self.addline('TRAORI')
353  [ x, y, z,_a,_b,_c] = Pose_2_Staubli(roty(pi)*pose)
354  [_x,_y,_z, a, b, c] = Pose_2_Staubli(pose)
355  x = x * MM_2_UNITS
356  y = y * MM_2_UNITS
357  z = z * MM_2_UNITS
358  self.INV_TOOL_FRAME = invH(pose)
359  self.INV_TOOL_FRAME.setPos([0,0,0])
360  self.addline('$TC_DP5[1,1]=%.5f' % x)
361  self.addline('$TC_DP4[1,1]=%.5f' % y)
362  self.addline('$TC_DP3[1,1]=%.5f' % z)
363  #self.addline('$TC_DPC3[1,1]=%.5f' % a)
364  #self.addline('$TC_DPC2[1,1]=%.5f' % b)
365  #self.addline('$TC_DPC1[1,1]=%.5f' % c)
366  self.addline('$TC_DPC3[1,1]=0.0')
367  self.addline('$TC_DPC2[1,1]=0.0')
368  self.addline('$TC_DPC1[1,1]=0.0')
369  self.addline('T1 D1') # Use tool 1 profile 1
370  self.addcomment('---------------------------- ')
371 
372  def Pause(self, time_ms):
373  """Pause the robot program"""
374  if time_ms < 0:
375  #self.addline('G9 ; STOP') # can't continue
376  self.addline('M0 ; STOP')
377  else:
378  self.addline('G4 F%.0f ; pause in seconds' % (time_ms*0.001))
379 
380  def setSpeed(self, speed_mms):
381  """Changes the robot speed (in mm/s)"""
382  self.SPEED_UNITS_MIN = speed_mms*60.0*MM_2_UNITS
383 
384  def setAcceleration(self, accel_mmss):
385  """Changes the robot acceleration (in mm/s2)"""
386  self.addcomment('Acceleration set to %.3f mm/s2' % accel_mmss)
387 
388  def setSpeedJoints(self, speed_degs):
389  """Changes the robot joint speed (in deg/s)"""
390  #self.addcomment('Joint speed set to %.3f deg/s' % speed_degs)
391  self.SPEED_DEG_MIN = speed_degs * 60
392 
393  def setAccelerationJoints(self, accel_degss):
394  """Changes the robot joint acceleration (in deg/s2)"""
395  self.addcomment('Joint acceleration set to %.3f deg/s2' % accel_degss)
396 
397  def setZoneData(self, zone_mm):
398  """Changes the rounding radius (aka CNT, APO or zone data) to make the movement smoother"""
399  #self.addcomment('Look ahead desired tolerance: %.1f mm' % zone_mm)
400  if zone_mm < 0:
401  self.addline('CYCLE832(0,_OFF,1)')
402  else:
403  self.addline('CYCLE832(0.1,_FINISH,1)')
404 
405  def setDO(self, io_var, io_value):
406  """Sets a variable (digital output) to a given value"""
407  comment = 'Set digital output %s = %s' % (io_var, io_value)
408  if type(io_var) != str: # set default variable name if io_var is a number
409  io_var = 'P%s' % str(io_var)
410  if type(io_value) != str: # set default variable value if io_value is a number
411  if io_value > 0:
412  io_value = M_SET_DO_HIGH
413  else:
414  io_value = M_SET_DO_LOW
415 
416  # at this point, io_var and io_value must be string values
417  self.addline('%s %s ; %s' % (io_value, io_var, comment))
418 
419  def waitDI(self, io_var, io_value, timeout_ms=-1):
420  """Waits for a variable (digital input) io_var to attain a given value io_value. Optionally, a timeout can be provided."""
421  comment = 'Wait Digital Input %s = %s' % (io_var, io_value)
422  if timeout_ms > 0:
423  comment = comment + ' (timeout = %.3f)' % (timeout_ms*0.001)
424 
425  if type(io_var) != str: # set default variable name if io_var is a number
426  io_var = 'P%s' % str(io_var)
427  if type(io_value) != str: # set default variable value if io_value is a number
428  if io_value > 0:
429  io_value = 'L3'
430  else:
431  io_value = 'L4'
432 
433  # at this point, io_var and io_value must be string values
434  if timeout_ms < 0:
435  self.addline('%s %s %s Q9999; %s' % (M_WAIT_DI, io_var, io_value, comment))
436  else:
437  self.addline('%s %s %s Q%.3f; %s' % (M_WAIT_DI, io_var, io_value, timeout_ms*0.001, comment))
438 
439  def RunCode(self, code, is_function_call = False):
440  """Adds code or a function call"""
441  if is_function_call:
442  code.replace(' ','_')
443  #self.addline(code)
444  self.addline('GOTOF ' + code)
445  self.addline(code + '_done:')
446 
447  else:
448  self.addcomment(code)
449 
450  def RunMessage(self, message, iscomment = False):
451  """Display a message in the robot controller screen (teach pendant)"""
452  if iscomment:
453  self.addcomment(message)
454  else:
455  self.addcomment('Display message: %s' % message)
456 
457 # ------------------ private ----------------------
458  def addline(self, newline):
459  """Add a program line"""
460  self.Nline = self.Nline + 1
461  self.PROG = self.PROG + ('N%02i ' % self.Nline) + newline + '\n'
462 
463  def addcomment(self, newline):
464  """Add a comment line"""
465  self.PROG = self.PROG + '; ' + newline + '\n'
466 
467  def addlog(self, newline):
468  """Add a log message"""
469  self.LOG = self.LOG + newline + '\n'
470 
471 # -------------------------------------------------
472 # ------------ For testing purposes ---------------
473 def Pose(xyzrpw):
474  [x,y,z,r,p,w] = xyzrpw
475  a = r*math.pi/180
476  b = p*math.pi/180
477  c = w*math.pi/180
478  ca = math.cos(a)
479  sa = math.sin(a)
480  cb = math.cos(b)
481  sb = math.sin(b)
482  cc = math.cos(c)
483  sc = math.sin(c)
484  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]])
485 
486 def test_post():
487  """Test the post with a basic program"""
488 
489  robot = RobotPost()
490 
491  robot.ProgStart("Program")
492  robot.RunMessage("Program generated by RoboDK using a custom post processor", True)
493  robot.setFrame(Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
494  robot.setTool(Pose([62.5, -108.253175, 100, -60, 90, 0]))
495  robot.MoveJ(Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
496  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
497  robot.MoveL(Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
498  robot.RunMessage("Setting air valve 1 on")
499  robot.RunCode("TCP_On", True)
500  robot.Pause(1000)
501  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
502  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
503  robot.MoveL(Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
504  robot.RunMessage("Setting air valve off")
505  robot.RunCode("TCP_Off", True)
506  robot.Pause(1000)
507  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
508  robot.MoveL(Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
509  robot.MoveL(Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
510  robot.MoveJ(None, [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
511  robot.ProgFinish("Program")
512  # robot.ProgSave(".","Program",True)
513  print(robot.PROG)
514  if len(robot.LOG) > 0:
515  mbox('Program generation LOG:\n\n' + robot.LOG)
516 
517  input("Press Enter to close...")
518 
519 if __name__ == "__main__":
520  """Function to call when the module is executed by itself: test"""
521  test_post()
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
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 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 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