RSI.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 Robotic Systems Integration controllers, targeted to Comau and other robot brands
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 from robolink import *
48 
49 # ----------------------------------------------------
50 def pose_2_str(pose):
51  """Prints a pose target"""
52  [x,y,z,w,p,r] = Pose_2_TxyzRxyz(pose)
53  return ('pose([%.6f, %.6f, %.6f, %.6f, %.6f, %.6f])' % (x,y,z,r,p,w))
54 
55 def angles_2_str(angles):
56  """Prints a joint target"""
57  njoints = len(angles)
58  if njoints == 6:
59  return ('[%.6f, %.6f, %.6f, %.6f, %.6f, %.6f]' % (angles[0], angles[1], angles[2], angles[3], angles[4], angles[5]))
60  else:
61  return 'this post only supports 6-axis robots'
62 
63 # ----------------------------------------------------
64 # Object class that handles the robot instructions/syntax
65 class RobotPost(object):
66  """Robot post object"""
67  PROG_EXT = 'txt' # set the program extension
68  SPEED_MMS = 0.3 # default speed for linear moves in m/s
69  SPEED_DEGS = 0.75 # default speed for joint moves in rad/s
70  ACCEL_MMSS = 3 # default acceleration for lineaer moves in m/ss
71  ACCEL_DEGSS = 1.2 # default acceleration for joint moves in rad/ss
72  BLEND_RADIUS_MM = 0.001 # default smooth radius in mm (corners smoothing)
73  REF_FRAME = eye(4) # default reference frame (the robot reference frame)
74  MOVE_COUNT = 0
75 
76  # other variables
77  ROBOT_POST = 'unset'
78  ROBOT_NAME = 'generic'
79  PROG_FILES = []
80  MAIN_PROGNAME = 'unknown'
81  PROG = ''
82  TAB = ''
83  LOG = ''
84 
85  def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
86  self.ROBOT_POST = robotpost
87  self.ROBOT_NAME = robotname
88  self.nPROGS = 0
89  self.PROG = ''
90  self.LOG = ''
91 
92  def ProgStart(self, progname):
93  self.nPROGS = self.nPROGS + 1
94  self.addline('def %s():' % progname)
95  self.TAB = ' '
96  if self.nPROGS == 1:
97  self.MAIN_PROGNAME = progname
98  self.addline('# default parameters:')
99  self.addline('global speed_mms = %.3f' % self.SPEED_MMS)
100  self.addline('global speed_degs = %.3f' % self.SPEED_DEGS)
101  self.addline('global accel_mmss = %.3f' % self.ACCEL_MMSS)
102  self.addline('global accel_degss = %.3f' % self.ACCEL_DEGSS)
103  self.addline('global smooth_radius_mm = %.3f' % self.BLEND_RADIUS_MM)
104 
105  def ProgFinish(self, progname):
106  self.TAB = ''
107  self.addline('')
108 
109  def ProgSave(self, folder, progname, ask_user = False, show_result = False):
110  self.addline('%s()' % self.MAIN_PROGNAME)
111  progname = progname + '.' + self.PROG_EXT
112  if ask_user or not DirExists(folder):
113  filesave = getSaveFile(folder, progname, 'Save program as...')
114  if filesave is not None:
115  filesave = filesave.name
116  else:
117  return
118  else:
119  filesave = folder + '/' + progname
120  fid = open(filesave, "w")
121  fid.write(self.PROG)
122  fid.close()
123  print('SAVED: %s\n' % filesave) # tell RoboDK the path of the saved file
124  self.PROG_FILES = filesave
125 
126  # write the joint list of points as a separate file
127  RDK = Robolink()
128  progitem = RDK.Item(self.MAIN_PROGNAME, ITEM_TYPE_PROGRAM)
129  filesave_control = filesave + '.control'
130  if not progitem.Valid():
131  error_msg = 'Problems getting the program'
132  error_code = -1
133  else:
134  error_msg, joint_list, error_code = progitem.InstructionListJoints(0.5, 0.5, filesave + '.control')
135 
136  if error_code != 0:
137  mbox('Program issues:\n\n' + error_msg)
138 
139  # open file with default application
140  if show_result:
141  if type(show_result) is str:
142  # Open file with provided application
143  import subprocess
144  p = subprocess.Popen([show_result, filesave])
145  p = subprocess.Popen([show_result, filesave_control])
146  elif type(show_result) is list:
147  import subprocess
148  p = subprocess.Popen(show_result + [filesave])
149  else:
150  # open file with default application
151  import os
152  os.startfile(filesave)
153  if len(self.LOG) > 0:
154  mbox('Program generation LOG:\n\n' + self.LOG)
155 
156  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
157  """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".
158  The connection parameters must be provided in the robot connection menu of RoboDK"""
159  UploadFTP(self.PROG_FILES, robot_ip, remote_path, ftp_user, ftp_pass)
160 
161  def MoveJ(self, pose, joints, conf_RLF=None):
162  """Add a joint movement"""
163  self.MOVE_COUNT = self.MOVE_COUNT + 1
164  self.addline('movej(%s,accel_degss,speed_degs,0,smooth_radius_mm) # move_id = %.0f' % (angles_2_str(joints), self.MOVE_COUNT))
165 
166  def MoveL(self, pose, joints, conf_RLF=None):
167  """Add a linear movement"""
168  self.MOVE_COUNT = self.MOVE_COUNT + 1
169  # Movement in joint space or Cartesian space should give the same result:
170  self.addline('movel(%s,accel_mss,speed_mms,0,smooth_radius_mm) # move_id = %.0f' % (angles_2_str(joints), self.MOVE_COUNT))
171 
172  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
173  """Add a circular movement"""
174  self.MOVE_COUNT = self.MOVE_COUNT + 1
175  self.addline('movec(%s,%s,accel_mmss,speed_mms,0,smooth_radius_mm) # move_id = %.0f' % (angles_2_str(joints1),angles_2_str(joints2), self.MOVE_COUNT))
176 
177  def setFrame(self, pose, frame_id=None, frame_name=None):
178  """Change the robot reference frame"""
179  # the reference frame is not needed if we use joint space for joint and linear movements
180  # the reference frame is also not needed if we use cartesian moves with respect to the robot base frame
181  # the cartesian targets must be pre-multiplied by the active reference frame
182  self.REF_FRAME = pose
183  self.addline('set_reference(%s)' % pose_2_str(pose))
184 
185  def setTool(self, pose, tool_id=None, tool_name=None):
186  """Change the robot TCP"""
187  self.addline('set_tcp(%s)' % pose_2_str(pose))
188 
189  def Pause(self, time_ms):
190  """Pause the robot program"""
191  if time_ms <= 0:
192  self.addline('halt()')
193  else:
194  self.addline('sleep(%.3f)' % (time_ms*0.001))
195 
196  def setSpeed(self, speed_mms):
197  """Changes the robot speed (in mm/s)"""
198  self.addline('speed_mms = %.3f' % speed_mms)
199 
200  def setAcceleration(self, accel_mmss):
201  """Changes the robot acceleration (in mm/s2)"""
202  self.addline('accel_mmss = %.3f' % accel_mmss)
203 
204  def setSpeedJoints(self, speed_degs):
205  """Changes the robot joint speed (in deg/s)"""
206  self.addline('speed_degs = %.3f' % speed_degs)
207 
208  def setAccelerationJoints(self, accel_degss):
209  """Changes the robot joint acceleration (in deg/s2)"""
210  self.addline('accel_degss = %.3f' % accel_degss)
211 
212  def setZoneData(self, zone_mm):
213  """Changes the zone data approach (makes the movement more smooth)"""
214  if zone_mm < 0:
215  zone_mm = 0
216  self.BLEND_RADIUS_M = zone_mm / 1000.0
217  self.addline('smooth_radius_mm = %.3f' % self.BLEND_RADIUS_M)
218 
219  def setDO(self, io_var, io_value):
220  """Sets a variable (output) to a given value"""
221  if type(io_var) != str: # set default variable name if io_var is a number
222  io_var = 'OUT[%s]' % str(io_var)
223  if type(io_value) != str: # set default variable value if io_value is a number
224  if io_value > 0:
225  io_value = 'TRUE'
226  else:
227  io_value = 'FALSE'
228 
229  # at this point, io_var and io_value must be string values
230  self.addline('%s=%s' % (io_var, io_value))
231 
232  def waitDI(self, io_var, io_value, timeout_ms=-1):
233  """Waits for an input io_var to attain a given value io_value. Optionally, a timeout can be provided."""
234  if type(io_var) != str: # set default variable name if io_var is a number
235  io_var = 'IN[%s]' % str(io_var)
236  if type(io_value) != str: # set default variable value if io_value is a number
237  if io_value > 0:
238  io_value = 'TRUE'
239  else:
240  io_value = 'FALSE'
241 
242  # at this point, io_var and io_value must be string values
243  if timeout_ms < 0:
244  self.addline('WAIT FOR %s==%s' % (io_var, io_value))
245  else:
246  self.addline('WAIT FOR %s==%s TIMEOUT=%.1f' % (io_var, io_value, timeout_ms))
247 
248  def RunCode(self, code, is_function_call = False):
249  """Adds code or a function call"""
250  if is_function_call:
251  code.replace(' ','_')
252  self.addline(code + '()')
253  else:
254  #self.addline(code)
255  self.addline('# ' + code) #generate custom code as a comment
256 
257  def RunMessage(self, message, iscomment = False):
258  """Show a message on the controller screen"""
259  if iscomment:
260  self.addline('# ' + message)
261  else:
262  self.addline('popup("%s")' % message)
263 
264 # ------------------ private ----------------------
265  def addline(self, newline):
266  """Add a program line"""
267  self.PROG = self.PROG + self.TAB + newline + '\n'
268 
269  def addlog(self, newline):
270  """Add a log message"""
271  self.LOG = self.LOG + newline + '\n'
272 
273 # -------------------------------------------------
274 # ------------ For testing purposes ---------------
275 def Pose(xyzrpw):
276  [x,y,z,r,p,w] = xyzrpw
277  a = r*math.pi/180
278  b = p*math.pi/180
279  c = w*math.pi/180
280  ca = math.cos(a)
281  sa = math.sin(a)
282  cb = math.cos(b)
283  sb = math.sin(b)
284  cc = math.cos(c)
285  sc = math.sin(c)
286  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]])
287 
288 def test_post():
289  """Test the post with a basic program"""
290 
291  robot = RobotPost('Universal Robotics', 'Generic UR robot')
292 
293  robot.ProgStart("Program")
294  robot.RunMessage("Program generated by RoboDK", True)
295  robot.setFrame(Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
296  robot.setTool(Pose([62.5, -108.253175, 100, -60, 90, 0]))
297  robot.setSpeed(100) # set speed to 100 mm/s
298  robot.setAcceleration(3000) # set speed to 3000 mm/ss
299  robot.MoveJ(Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
300  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
301  robot.MoveL(Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
302  robot.RunMessage("Setting air valve 1 on")
303  robot.RunCode("TCP_On", True)
304  robot.Pause(1000)
305  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
306  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
307  robot.MoveL(Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
308  robot.RunMessage("Setting air valve off")
309  robot.RunCode("TCP_Off", True)
310  robot.Pause(1000)
311  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
312  robot.MoveL(Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
313  robot.MoveL(Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
314  robot.ProgFinish("Program")
315  # robot.ProgSave(".","Program",True)
316  print(robot.PROG)
317  if len(robot.LOG) > 0:
318  mbox('Program generation LOG:\n\n' + robot.LOG)
319 
320  input("Press Enter to close...")
321 
322 if __name__ == "__main__":
323  """Function to call when the module is executed by itself: test"""
324  test_post()
def RunCode(self, code, is_function_call=False)
Definition: RSI.py:248
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
Definition: RSI.py:172
def setDO(self, io_var, io_value)
Definition: RSI.py:219
def MoveL(self, pose, joints, conf_RLF=None)
Definition: RSI.py:166
def setSpeedJoints(self, speed_degs)
Definition: RSI.py:204
def waitDI(self, io_var, io_value, timeout_ms=-1)
Definition: RSI.py:232
def setAcceleration(self, accel_mmss)
Definition: RSI.py:200
def setTool(self, pose, tool_id=None, tool_name=None)
Definition: RSI.py:185
def UploadFTP(program, robot_ip, remote_path, ftp_user, ftp_pass)
Definition: robodk.py:1312
def MoveJ(self, pose, joints, conf_RLF=None)
Definition: RSI.py:161
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
Definition: robodk.py:1458
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
Definition: RSI.py:85
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
Definition: RSI.py:156
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
Definition: robodk.py:1354
def setFrame(self, pose, frame_id=None, frame_name=None)
Definition: RSI.py:177
def setAccelerationJoints(self, accel_degss)
Definition: RSI.py:208
def RunMessage(self, message, iscomment=False)
Definition: RSI.py:257
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
Definition: RSI.py:109


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