Universal_Robots_joints.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 Universal 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 # ----------------------------------------------------
49 
50 def pose_2_ur(pose):
51  """Calculate the p[x,y,z,rx,ry,rz] position for a pose target"""
52  def saturate_1(value):
53  return min(max(value,-1.0),1.0)
54 
55  angle = acos( saturate_1((pose[0,0]+pose[1,1]+pose[2,2]-1)/2) )
56  rxyz = [pose[2,1]-pose[1,2], pose[0,2]-pose[2,0], pose[1,0]-pose[0,1]]
57 
58  if angle == 0:
59  rxyz = [0,0,0]
60  else:
61  rxyz = normalize3(rxyz)
62  rxyz = mult3(rxyz, angle)
63  return [pose[0,3], pose[1,3], pose[2,3], rxyz[0], rxyz[1], rxyz[2]]
64 
65 def pose_2_str(pose):
66  """Prints a pose target"""
67  [x,y,z,w,p,r] = pose_2_ur(pose)
68  M_2_MM = 0.001
69  return ('p[%.6f, %.6f, %.6f, %.6f, %.6f, %.6f]' % (x*M_2_MM,y*M_2_MM,z*M_2_MM,w,p,r))
70 
71 def angles_2_str(angles):
72  """Prints a joint target"""
73  njoints = len(angles)
74  d2r = pi/180.0
75  if njoints == 6:
76  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))
77  else:
78  return 'this post only supports 6 joints'
79 
80 # ----------------------------------------------------
81 # Object class that handles the robot instructions/syntax
82 class RobotPost(object):
83  """Robot post object"""
84  PROG_EXT = 'script' # set the program extension
85  SPEED_MS = 0.3 # default speed for linear moves in m/s
86  SPEED_RADS = 0.75 # default speed for joint moves in rad/s
87  ACCEL_MSS = 3 # default acceleration for lineaer moves in m/ss
88  ACCEL_RADSS = 1.2 # default acceleration for joint moves in rad/ss
89  BLEND_RADIUS_M = 0.001 # default blend radius in meters (corners smoothing)
90  REF_FRAME = eye(4) # default reference frame (the robot reference frame)
91  LAST_POS = None # last XYZ position
92 
93  # other variables
94  ROBOT_POST = 'unset'
95  ROBOT_NAME = 'generic'
96  PROG_FILES = []
97  MAIN_PROGNAME = 'unknown'
98 
99  PROG = ''
100  TAB = ''
101  LOG = ''
102 
103  def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
104  self.ROBOT_POST = robotpost
105  self.ROBOT_NAME = robotname
106  self.nPROGS = 0
107  self.PROG = ''
108  self.LOG = ''
109 
110  def ProgStart(self, progname):
111  self.nPROGS = self.nPROGS + 1
112  self.addline('def %s():' % progname)
113  self.TAB = ' '
114  if self.nPROGS == 1:
115  self.MAIN_PROGNAME = progname
116  self.addline('# default parameters:')
117  self.addline('global speed_ms = %.3f' % self.SPEED_MS)
118  self.addline('global speed_rads = %.3f' % self.SPEED_RADS)
119  self.addline('global accel_mss = %.3f' % self.ACCEL_MSS)
120  self.addline('global accel_radss = %.3f' % self.ACCEL_RADSS)
121  self.addline('global blend_radius_m = %.3f' % self.BLEND_RADIUS_M)
122 
123  def ProgFinish(self, progname):
124  self.TAB = ''
125  self.addline('end')
126  self.addline('')
127 
128  def ProgSave(self, folder, progname, ask_user = False, show_result = False):
129  self.addline('%s()' % self.MAIN_PROGNAME)
130  progname = progname + '.' + self.PROG_EXT
131  if ask_user or not DirExists(folder):
132  filesave = getSaveFile(folder, progname, 'Save program as...')
133  if filesave is not None:
134  filesave = filesave.name
135  else:
136  return
137  else:
138  filesave = folder + '/' + progname
139  fid = open(filesave, "w")
140  fid.write(self.PROG)
141  fid.close()
142  print('SAVED: %s\n' % filesave) # tell RoboDK the path of the saved file
143  self.PROG_FILES = filesave
144 
145  # open file with default application
146  if show_result:
147  if type(show_result) is str:
148  # Open file with provided application
149  import subprocess
150  p = subprocess.Popen([show_result, filesave])
151  else:
152  # open file with default application
153  import os
154  os.startfile(filesave)
155  if len(self.LOG) > 0:
156  mbox('Program generation LOG:\n\n' + self.LOG)
157 
158  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
159  """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".
160  The connection parameters must be provided in the robot connection menu of RoboDK"""
161  UploadFTP(self.PROG_FILES, robot_ip, remote_path, ftp_user, ftp_pass)
162 
163  def blend_radius_check(self, pose):
164  # check that the blend radius covers 40% of the move (at most)
165  blend_radius = 'blend_radius_m';
166  current_pos = pose.Pos()
167  if self.LAST_POS is None:
168  blend_radius = '0'
169  else:
170  distance = norm(subs3(self.LAST_POS, current_pos)) # in mm
171  if 0.4*distance < self.BLEND_RADIUS_M*1000:
172  blend_radius = '%.3f' % (max(0.4*distance*0.001, 0.001))
173  self.LAST_POS = current_pos
174  return blend_radius
175 
176  def MoveJ(self, pose, joints, conf_RLF=None):
177  """Add a joint movement"""
178  if pose is None:
179  blend_radius = "0"
180  self.LAST_POS = None
181  else:
182  blend_radius = self.blend_radius_check(pose)
183  self.addline('movej(%s,accel_radss,speed_rads,0,%s)' % (angles_2_str(joints), blend_radius))
184 
185  def MoveL(self, pose, joints, conf_RLF=None):
186  """Add a linear movement"""
187  # Movement in joint space or Cartesian space should give the same result:
188  # pose_wrt_base = self.REF_FRAME*pose
189  # self.addline('movel(%s,accel_mss,speed_ms,0,blend_radius_m)' % (pose_2_str(pose_wrt_base)))
190  if pose is None:
191  blend_radius = "0"
192  self.LAST_POS = None
193  target = angles_2_str(joints)
194  else:
195  blend_radius = self.blend_radius_check(pose)
196  target = pose_2_str(self.REF_FRAME*pose)
197  self.addline('movel(%s,accel_mss,speed_ms,0,%s)' % (angles_2_str(joints), blend_radius))
198  #self.addline('movel(%s,accel_mss,speed_ms,0,%s)' % (target, blend_radius))
199 
200 
201  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
202  """Add a circular movement"""
203  def circle_radius(p0,p1,p2):
204  a = norm(subs3(p0,p1))
205  b = norm(subs3(p1,p2))
206  c = norm(subs3(p2,p0))
207  radius = a*b*c/sqrt(pow(a*a+b*b+c*c,2)-2*(pow(a,4)+pow(b,4)+pow(c,4)))
208  return radius
209 
210  def distance_p1_p02(p0,p1,p2):
211  v01 = subs3(p1, p0)
212  v02 = subs3(p2, p0)
213  return dot(v02,v01)/dot(v02,v02)
214 
215  p0 = self.LAST_POS
216  p1 = pose1.Pos()
217  p2 = pose2.Pos()
218  if p0 is None:
219  self.MoveL(pose2, joints2, conf_RLF_2)
220  return
221 
222  radius = circle_radius(p0, p1, p2)
223  if radius < 1 or radius > 100000:
224  self.MoveL(pose2, joints2, conf_RLF_2)
225  return
226 
227  d_p1_p02 = distance_p1_p02(p0, p1, p2)
228  if d_p1_p02 < 1:
229  self.MoveL(pose2, joints2, conf_RLF_2)
230  return
231 
232  blend_radius = self.blend_radius_check(pose1)
233  self.LAST_POS = pose2.Pos()
234  self.addline('movec(%s,%s,accel_mss,speed_ms,%s)' % (angles_2_str(joints1),angles_2_str(joints2), blend_radius))
235  #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))
236 
237  def setFrame(self, pose, frame_id=None, frame_name=None):
238  """Change the robot reference frame"""
239  # the reference frame is not needed if we use joint space for joint and linear movements
240  # the reference frame is also not needed if we use cartesian moves with respect to the robot base frame
241  # the cartesian targets must be pre-multiplied by the active reference frame
242  self.REF_FRAME = pose
243  self.addline('# set_reference(%s)' % pose_2_str(pose))
244 
245  def setTool(self, pose, tool_id=None, tool_name=None):
246  """Change the robot TCP"""
247  self.addline('set_tcp(%s)' % pose_2_str(pose))
248 
249  def Pause(self, time_ms):
250  """Pause the robot program"""
251  if time_ms <= 0:
252  self.addline('halt() # reimplement this function to force stop')
253  else:
254  self.addline('sleep(%.3f)' % (time_ms*0.001))
255 
256  def setSpeed(self, speed_mms):
257  """Changes the robot speed (in mm/s)"""
258  self.SPEED_MS = speed_mms/1000.0
259  self.addline('speed_ms = %.3f' % self.SPEED_MS)
260 
261  def setAcceleration(self, accel_mmss):
262  """Changes the robot acceleration (in mm/s2)"""
263  self.ACCEL_MSS = accel_mmss/1000.0
264  self.addline('accel_mss = %.3f' % self.ACCEL_MSS)
265 
266  def setSpeedJoints(self, speed_degs):
267  """Changes the robot joint speed (in deg/s)"""
268  self.SPEED_RADS = speed_degs*pi/180
269  self.addline('speed_rads = %.3f' % self.SPEED_RADS)
270 
271  def setAccelerationJoints(self, accel_degss):
272  """Changes the robot joint acceleration (in deg/s2)"""
273  self.ACCEL_RADSS = accel_degss*pi/180
274  self.addline('accel_radss = %.3f' % self.ACCEL_RADSS)
275 
276  def setZoneData(self, zone_mm):
277  """Changes the zone data approach (makes the movement more smooth)"""
278  if zone_mm < 0:
279  zone_mm = 0
280  self.BLEND_RADIUS_M = zone_mm / 1000.0
281  self.addline('blend_radius_m = %.3f' % self.BLEND_RADIUS_M)
282 
283  def setDO(self, io_var, io_value):
284  """Sets a variable (output) to a given value"""
285  if type(io_value) != str: # set default variable value if io_value is a number
286  if io_value > 0:
287  io_value = 'True'
288  else:
289  io_value = 'False'
290 
291  if type(io_var) != str: # set default variable name if io_var is a number
292  newline = 'set_standard_digital_out(%s, %s)' % (str(io_var), io_value)
293  else:
294  newline = '%s = %s' % (io_var, io_value)
295 
296  self.addline(newline)
297 
298  def waitDI(self, io_var, io_value, timeout_ms=-1):
299  """Waits for an input io_var to attain a given value io_value. Optionally, a timeout can be provided."""
300  if type(io_var) != str: # set default variable name if io_var is a number
301  io_var = 'get_standard_digital_in(%s)' % str(io_var)
302  if type(io_value) != str: # set default variable value if io_value is a number
303  if io_value > 0:
304  io_value = 'True'
305  else:
306  io_value = 'False'
307 
308  # at this point, io_var and io_value must be string values
309  #if timeout_ms < 0:
310  self.addline('while (%s != %s):' % (io_var, io_value))
311  self.addline(' sync()')
312  self.addline('end')
313 
314  def RunCode(self, code, is_function_call = False):
315  """Adds code or a function call"""
316  if is_function_call:
317  code.replace(' ','_')
318  if not code.endswith(')'):
319  code = code + '()'
320  self.addline(code)
321  else:
322  #self.addline(code)
323  self.addline('# ' + code) #generate custom code as a comment
324 
325  def RunMessage(self, message, iscomment = False):
326  """Show a message on the controller screen"""
327  if iscomment:
328  self.addline('# ' + message)
329  else:
330  self.addline('popup("%s","Message",False,False,blocking=True)' % message)
331 
332 # ------------------ private ----------------------
333  def addline(self, newline):
334  """Add a program line"""
335  self.PROG = self.PROG + self.TAB + newline + '\n'
336 
337  def addlog(self, newline):
338  """Add a log message"""
339  self.LOG = self.LOG + newline + '\n'
340 
341 # -------------------------------------------------
342 # ------------ For testing purposes ---------------
343 def Pose(xyzrpw):
344  [x,y,z,r,p,w] = xyzrpw
345  a = r*math.pi/180
346  b = p*math.pi/180
347  c = w*math.pi/180
348  ca = math.cos(a)
349  sa = math.sin(a)
350  cb = math.cos(b)
351  sb = math.sin(b)
352  cc = math.cos(c)
353  sc = math.sin(c)
354  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]])
355 
356 def test_post():
357  """Test the post with a basic program"""
358 
359  robot = RobotPost('Universal Robotics', 'Generic UR robot')
360 
361  robot.ProgStart("Program")
362  robot.RunMessage("Program generated by RoboDK", True)
363  robot.setFrame(Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
364  robot.setTool(Pose([62.5, -108.253175, 100, -60, 90, 0]))
365  robot.setSpeed(100) # set speed to 100 mm/s
366  robot.setAcceleration(3000) # set speed to 3000 mm/ss
367  robot.MoveJ(Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
368  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
369  robot.MoveL(Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
370  robot.RunMessage("Setting air valve 1 on")
371  robot.RunCode("TCP_On", True)
372  robot.Pause(1000)
373  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
374  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
375  robot.MoveL(Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
376  robot.RunMessage("Setting air valve off")
377  robot.RunCode("TCP_Off", True)
378  robot.Pause(1000)
379  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
380  robot.MoveL(Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
381  robot.MoveL(Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
382  robot.ProgFinish("Program")
383  # robot.ProgSave(".","Program",True)
384  print(robot.PROG)
385  if len(robot.LOG) > 0:
386  mbox('Program generation LOG:\n\n' + robot.LOG)
387 
388  input("Press Enter to close...")
389 
390 if __name__ == "__main__":
391  """Function to call when the module is executed by itself: test"""
392  test_post()
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
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 MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
Definition: robodk.py:1458
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)


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