CPR.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 CPR robot (Common place robotics: http://www.cpr-robots.com/)
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 # ----------------------------------------------------
51 def pose_2_str(pose):
52  """Prints a pose target"""
53  [x,y,z,r,p,w] = Pose_2_KUKA(pose)
54  return ('x="%.3f" y="%.3f" z="%.3f" a="%.3f" b"%.3f" c="%.3f"' % (x,y,z,r,p,w))
55 
56 def joints_2_str(joints):
57  """Prints a joint target"""
58  str = ''
59  jnt_tags = ['a1', 'a2', 'a3', 'a4', 'a5', 'a6', 'a7', 'a8']
60  for i in range(len(joints)):
61  str = str + ('%s="%.5f" ' % (jnt_tags[i], joints[i]))
62  str = str[:-1]
63  return str
64 
65 # ----------------------------------------------------
66 # Object class that handles the robot instructions/syntax
67 class RobotPost(object):
68  """Robot post object"""
69  PROG_EXT = 'xml' # set the program extension
70 
71  # other variables
72  ROBOT_POST = ''
73  ROBOT_NAME = ''
74  PROG_FILES = []
75 
76  PROG = ''
77  LOG = ''
78  TAB = ''
79  MAIN_PROG_NAME = None
80  nAxes = 6
81  Prog_count = 0
82  SMOOTH = 'True'
83  SPEED = 70
84  SPEED_PERCENT = 35
85  NR_ID = 0
86  FRAME = eye(4)
87  TOOL = eye(4)
88 
89 
90  def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
91  self.ROBOT_POST = robotpost
92  self.ROBOT_NAME = robotname
93  self.PROG = ''
94  self.LOG = ''
95  self.nAxes = robot_axes
96 
97  def ProgStart(self, progname):
98  self.Prog_count = self.Prog_count + 1
99  self.addline('<?xml version="1.0" encoding="utf-8"?>')
100  self.addline('<!-- values in mm and degree -->')
101  self.addline('<Program>')
102  self.addline('<Header ProgramName ="CPRog recording" Author="nn" SetUpDate="" LastChangeDate="" Kinematic="CPRFour"/>')
103  self.TAB = ' '
104  if self.MAIN_PROG_NAME is None:
105  self.MAIN_PROG_NAME = progname
106  else:
107  pass
108 
109  def ProgFinish(self, progname):
110  self.TAB = ''
111  self.addline('</Program>')
112  self.addline('<!-- End of program: %s -->' % progname)
113  self.addline('')
114  if self.Prog_count == 1:
115  pass
116 
117  def ProgSave(self, folder, progname, ask_user=False, show_result=False):
118  import subprocess
119  progname = progname + '.' + self.PROG_EXT
120  if ask_user or not DirExists(folder):
121  filesave = getSaveFile(folder, progname, 'Save program as...')
122  if filesave is not None:
123  filesave = filesave.name
124  else:
125  return
126  else:
127  filesave = folder + '/' + progname
128 
129  # retrieve robot IP
130  RDK = Robolink()
131  robot = RDK.Item(self.ROBOT_NAME, ITEM_TYPE_ROBOT)
132  [server_ip, port, remote_path, username, password] = robot.ConnectionParams()
133 
134  fid = open(filesave, "w")
135  fid.write(self.PROG)
136  print('SAVED: %s\n' % filesave)
137  self.PROG_FILES = filesave
138  #---------------------- show result
139 
140  #selection_view = mbox('Do you want to view/edit the program or run it on the robot?', 'View', 'Run')
141  selection_view = True
142 
143  if selection_view and show_result:
144  if type(show_result) is str:
145  # Open file with provided application
146  import subprocess
147  p = subprocess.Popen([show_result, filesave])
148  elif type(show_result) is list:
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 
156  if len(self.LOG) > 0:
157  mbox('Program generation LOG:\n\n' + self.LOG)
158 
159  if not selection_view:
160  RDK.ShowMessage('Running program...', False)
161  proc = subprocess.Popen(['python', filesave])
162 
163  # Using the same pipe
164  #import io
165  #proc = subprocess.Popen(['python', filesave], stdout=subprocess.PIPE)
166  #for line in io.TextIOWrapper(proc.stdout, encoding="utf-8"): # or another encoding
167  # RDK.ShowMessage(line, False)
168 
169 
170  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
171  """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".
172  The connection parameters must be provided in the robot connection menu of RoboDK"""
173  import subprocess
174  import os
175  import sys
176  import time
177 
178  print("POPUP: Starting process...")
179  print("Python path " + PATH_PYTHON)
180  print("Program file: " + self.PROG_FILES)
181  sys.stdout.flush()
182 
183  # Start process
184  cmd_run = self.PROG_FILES # run py file itself
185  if PATH_PYTHON != '':
186  # if a python path is specified, use it to run the Py file
187  cmd_run = [PATH_PYTHON, self.PROG_FILES]
188 
189  process = subprocess.Popen(cmd_run, shell=True, stdout=subprocess.PIPE, stderr=subprocess.STDOUT, universal_newlines=True)
190 
191  # Poll process for new output until finished
192  for stdout_line in iter(process.stdout.readline, ""):
193  print("POPUP: " + stdout_line.strip())
194  sys.stdout.flush()
195 
196  process.stdout.close()
197  return_code = process.wait()
198  if return_code:
199  raise subprocess.CalledProcessError(return_code, cmd_run)
200 
201  if (return_code == 0):
202  return
203  else:
204  raise ProcessException(command, return_code, output)
205 
206  def MoveJ(self, pose, joints, conf_RLF=None):
207  """Add a joint movement"""
208  self.NR_ID = self.NR_ID + 1
209  self.addline('<Joint Nr="%i" %s velPercent="%.0f" acc="40" smooth="%s" Descr="" />' % (self.NR_ID, joints_2_str(joints), self.SPEED_PERCENT, self.SMOOTH))
210 
211  def MoveL(self, pose, joints, conf_RLF=None):
212  """Add a linear movement"""
213  self.NR_ID = self.NR_ID + 1
214  if pose is None:
215  # no linear movement allowed by providing joints
216  self.addline('<Joint Nr="%i" %s velPercent="%.0f" acc="40" smooth="%s" Descr="" />' % (self.NR_ID, joints_2_str(joints), self.SPEED_PERCENT, self.SMOOTH))
217  else:
218  self.addline('<Joint Nr="%i" %s vel="%.0f" acc="40" smooth="%s" Descr="" />' % (self.NR_ID, pose_2_str(self.FRAME*pose*invH(self.TOOL)), self.SPEED, self.SMOOTH))
219 
220  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
221  """Add a circular movement"""
222  self.addlog("Cicular moves not supported")
223 
224  def setFrame(self, pose, frame_id=None, frame_name=None):
225  """Change the robot reference frame"""
226  self.FRAME = pose
227  self.addline("<!-- Using Reference: %s -->" % pose_2_str(pose))
228 
229  def setTool(self, pose, tool_id=None, tool_name=None):
230  """Change the robot TCP"""
231  self.TOOL = pose
232  self.addline("<!-- Using Tool: %s -->" % pose_2_str(pose))
233 
234  def Pause(self, time_ms):
235  """Pause the robot program"""
236  self.NR_ID = self.NR_ID + 1
237  if time_ms < 0:
238  self.addline('<Wait Nr="%i" Seconds="%.3f" Descr="" />' % (self.NR_ID, float(9999)))
239  else:
240  #self.addline('time.sleep(%.3f)' % (float(time_ms)*0.001))
241  self.addline('<Wait Nr="%i" Seconds="%.3f" Descr="" />' % (self.NR_ID, float(time_ms)*0.001))
242 
243  def setSpeed(self, speed_mms):
244  """Changes the robot speed (in mm/s)"""
245  self.SPEED_PERCENT = speed_mms
246 
247  def setAcceleration(self, accel_mmss):
248  """Changes the robot acceleration (in mm/s2)"""
249  self.addlog('Linear acceleration not supported')
250 
251  def setSpeedJoints(self, speed_degs):
252  """Changes the robot joint speed (in deg/s)"""
253  self.SPEED_PERCENT = min(speed_degs, 100)
254 
255  def setAccelerationJoints(self, accel_degss):
256  """Changes the robot joint acceleration (in deg/s2)"""
257  self.addlog('Joint acceleration not supported')
258 
259  def setZoneData(self, zone_mm):
260  """Changes the smoothing radius (aka CNT, APO or zone data) to make the movement smoother"""
261  if zone_mm > 0:
262  self.SMOOTH = 'True'
263  else:
264  self.SMOOTH = 'False'
265 
266  def setDO(self, io_var, io_value):
267  """Sets a variable (digital output) to a given value"""
268  if type(io_var) != str: # set default variable name if io_var is a number
269  io_var = '%s' % str(io_var)
270  if type(io_value) != str: # set default variable value if io_value is a number
271  if io_value > 0:
272  io_value = 'True'
273  else:
274  io_value = 'False'
275 
276  self.NR_ID = self.NR_ID + 1
277  # at this point, io_var and io_value must be string values
278  # self.addline('%s=%s' % (io_var, io_value))
279  self.addline('<Output Nr="%i" Local="True" DIO="%s" State="%s" Descr="" />' % (self.NR_ID, io_var, io_value))
280 
281  def waitDI(self, io_var, io_value, timeout_ms=-1):
282  """Waits for a variable (digital input) io_var to attain a given value io_value. Optionally, a timeout can be provided."""
283  if type(io_var) != str: # set default variable name if io_var is a number
284  io_var = '%s' % str(io_var)
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  self.NR_ID = self.NR_ID + 1
292  # at this point, io_var and io_value must be string values
293  self.addline('<WaitInput Nr="%i" Local="True" DIO="%s" State="%s" Descr="" />' % (self.NR_ID, io_var, io_value))
294 
295 
296  def RunCode(self, code, is_function_call = False):
297  """Adds code or a function call"""
298  if is_function_call:
299  code.replace(' ','_')
300  if not code.endswith(')'):
301  code = code + '()'
302  self.addline(code)
303  else:
304  self.addline(code)
305 
306  def RunMessage(self, message, iscomment = False):
307  """Display a message in the robot controller screen (teach pendant)"""
308  if iscomment:
309  self.addline('<!-- %s -->' % message)
310  else:
311  self.addline('<!-- %s -->' % message)
312 
313 # ------------------ private ----------------------
314  def addline(self, newline):
315  """Add a program line"""
316  self.PROG = self.PROG + self.TAB + newline + '\n'
317 
318  def addlog(self, newline):
319  """Add a log message"""
320  self.LOG = self.LOG + newline + '\n'
321 
322 # -------------------------------------------------
323 # ------------ For testing purposes ---------------
324 def Pose(xyzrpw):
325  [x,y,z,r,p,w] = xyzrpw
326  a = r*math.pi/180
327  b = p*math.pi/180
328  c = w*math.pi/180
329  ca = math.cos(a)
330  sa = math.sin(a)
331  cb = math.cos(b)
332  sb = math.sin(b)
333  cc = math.cos(c)
334  sc = math.sin(c)
335  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]])
336 
337 def test_post():
338  """Test the post with a basic program"""
339 
340  robot = RobotPost()
341 
342  robot.ProgStart("Program")
343  robot.RunMessage("Program generated by RoboDK using a custom post processor", True)
344  robot.setFrame(Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
345  robot.setTool(Pose([62.5, -108.253175, 100, -60, 90, 0]))
346  robot.MoveJ(Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
347  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
348  robot.MoveL(Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
349  robot.RunMessage("Setting air valve 1 on")
350  robot.RunCode("TCP_On", True)
351  robot.Pause(1000)
352  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
353  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
354  robot.MoveL(Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
355  robot.RunMessage("Setting air valve off")
356  robot.RunCode("TCP_Off", True)
357  robot.Pause(1000)
358  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
359  robot.MoveL(Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
360  robot.MoveL(Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
361  robot.MoveJ(None, [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
362  robot.ProgFinish("Program")
363  # robot.ProgSave(".","Program",True)
364  print(robot.PROG)
365  if len(robot.LOG) > 0:
366  mbox('Program generation LOG:\n\n' + robot.LOG)
367 
368  input("Press Enter to close...")
369 
370 if __name__ == "__main__":
371  """Function to call when the module is executed by itself: test"""
372  test_post()
def RunCode(self, code, is_function_call=False)
Definition: CPR.py:296
def setTool(self, pose, tool_id=None, tool_name=None)
Definition: CPR.py:229
def RunMessage(self, message, iscomment=False)
Definition: CPR.py:306
def MoveJ(self, pose, joints, conf_RLF=None)
Definition: CPR.py:206
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
Definition: CPR.py:90
def setDO(self, io_var, io_value)
Definition: CPR.py:266
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
Definition: robodk.py:1458
def setFrame(self, pose, frame_id=None, frame_name=None)
Definition: CPR.py:224
def MoveL(self, pose, joints, conf_RLF=None)
Definition: CPR.py:211
def waitDI(self, io_var, io_value, timeout_ms=-1)
Definition: CPR.py:281
def setAccelerationJoints(self, accel_degss)
Definition: CPR.py:255
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
Definition: robodk.py:1354
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
Definition: CPR.py:117
def setAcceleration(self, accel_mmss)
Definition: CPR.py:247
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
Definition: CPR.py:220
def setSpeedJoints(self, speed_degs)
Definition: CPR.py:251
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
Definition: CPR.py:170


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