Mecademic.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 Mecademic 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 from robolink import *
48 
49 PATH_PYTHON = ''
50 #PATH_PYTHON = 'C:/Python34/python'
51 
52 ROBOT_CLASS = '''
53 def print_message(message):
54  """Force a print output"""
55  print(message)
56  sys.stdout.flush()
57 
58 def msg_info(robot_msg):
59  if robot_msg is None:
60  return False, -1, "No communication"
61  problems = False
62  msg_id = int(robot_msg[1:5])
63  msg_str = robot_msg[7:-2]
64  # msg_id = 1000 to 1500 are error codes
65  if msg_id < 1500:
66  problems = True
67  else:
68  # Other error codes
69  error_codes = [3001, 3003]
70  if msg_id in error_codes:
71  problems = True
72  if problems:
73  print_message(robot_msg)
74  return problems, msg_id, msg_str
75 
76 class MecaRobot:
77  """Robot class for programming Mecademic robots"""
78  def __init__(self, ip, port):
79  import socket
80  self.BUFFER_SIZE = 512 # bytes
81  self.TIMEOUT = 999999 # seconds
82  self.sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
83  self.sock.settimeout(self.TIMEOUT)
84  print_message('Connecting to robot %s:%i' % (ip, port))
85  self.sock.connect((ip, port))
86  print_message('Waiting for welcome message...')
87 
88  # receive welcome message and output to the log
89  problems, msg_id, msg_str = msg_info(self.recv_str())
90  if problems:
91  print_message(msg_str)
92  raise Exception(msg_str)
93  return
94 
95  # Reset errors, send activate robot and read confirmation
96  self.sock.settimeout(10)
97  self.Run('ResetError',sync=True)
98  self.Run('ActivateRobot',sync=True)
99  self.sock.settimeout(30)
100  self.Run('Home',sync=True)
101 
102  def send_str(self, msg):
103  sent = self.sock.send(bytes(msg+'\\0','ascii'))
104  if sent == 0:
105  raise RuntimeError("Robot connection broken")
106 
107  def recv_str(self):
108  bdata = self.sock.recv(self.BUFFER_SIZE)
109  if bdata == b'':
110  raise RuntimeError("Robot connection broken")
111  return bdata.decode('ascii')
112 
113  def Run(self, cmd, values=None, sync=False):
114  if isinstance(values, list):
115  if cmd == "Gripper":
116  str_send = cmd + '(' + (','.join(format(vi, ".0f") for vi in values)) + ')'
117  else:
118  str_send = cmd + '(' + (','.join(format(vi, ".6f") for vi in values)) + ')'
119  elif values is None:
120  str_send = cmd
121  else:
122  str_send = cmd + '(' + str(values) + ')'
123 
124  print_message('Running: %s' % str_send)
125 
126  # send command to robot
127  self.send_str(str_send)
128  if sync:
129  robot_msg = self.recv_str()
130  problems, msg_id, msg_str = msg_info(robot_msg)
131  print_message('Received: %s' % robot_msg)
132  if problems:
133  raise Exception(msg_str)
134  return True
135 
136 if __name__ == "__main__":
137  """Call Main procedure"""
138  # It is important to disconnect the robot if we force to stop the process
139  import atexit
140  atexit.register(RobotDisconnect)
141 
142 '''
143 
144 
145 def print_message(message):
146  print(message)
147  sys.stdout.flush()
148 
149 # ----------------------------------------------------
150 def pose_2_str(pose):
151  """Prints a pose target"""
152  [x,y,z,r,p,w] = Pose_2_TxyzRxyz(pose)
153  return ('[%.3f, %.3f, %.3f, %.3f, %.3f, %.3f]' % (x,y,z,r*180.0/pi,p*180.0/pi,w*180.0/pi))
154 
155 def joints_2_str(joints):
156  """Prints a joint target"""
157  str = '['
158  for i in range(len(joints)):
159  str = str + ('%.6f, ' % joints[i])
160  str = str[:-2] + ']'
161  return str
162 
163 # ----------------------------------------------------
164 # Object class that handles the robot instructions/syntax
165 class RobotPost(object):
166  """Robot post object"""
167  PROG_EXT = 'py' # set the program extension
168  ROBOT_IP = '192.168.0.100';
169  ROBOT_PORT = 10000
170 
171  # other variables
172  ROBOT_POST = ''
173  ROBOT_NAME = ''
174  PROG_FILES = []
175 
176  PROG = ''
177  LOG = ''
178  TAB = ''
179  MAIN_PROG_NAME = None
180  nAxes = 6
181  Prog_count = 0
182 
183 
184  def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
185  self.ROBOT_POST = robotpost
186  self.ROBOT_NAME = robotname
187  self.PROG = ''
188  self.LOG = ''
189  self.nAxes = robot_axes
190 
191  def ProgStart(self, progname):
192  self.Prog_count = self.Prog_count + 1
193  self.addline('def %s():' % progname)
194  self.TAB = ' '
195  if self.MAIN_PROG_NAME is None:
196  self.MAIN_PROG_NAME = progname
197  self.addline("'''Main procedure'''")
198  self.addline('global robot')
199  self.addline('RobotConnect()')
200  else:
201  self.addline('global robot')
202  self.addline('print_message("Running program %s...")' % progname)
203 
204  def ProgFinish(self, progname):
205  self.addline('print_message("Program %s Sent")' % progname)
206  if self.Prog_count == 1:
207  #self.addline('import time')
208  #self.addline('time.pause(2)')
209  pass
210  self.TAB = ''
211  self.addline('')
212 
213 
214  def ProgSave(self, folder, progname, ask_user=False, show_result=False):
215  import subprocess
216  progname = progname + '.' + self.PROG_EXT
217  if ask_user or not DirExists(folder):
218  filesave = getSaveFile(folder, progname, 'Save program as...')
219  if filesave is not None:
220  filesave = filesave.name
221  else:
222  return
223  else:
224  filesave = folder + '/' + progname
225 
226  # retrieve robot IP
227  RDK = Robolink()
228  robot = RDK.Item(self.ROBOT_NAME, ITEM_TYPE_ROBOT)
229  [server_ip, port, remote_path, username, password] = robot.ConnectionParams()
230 
231  fid = open(filesave, "w")
232 
233  fid.write('MECA_IP = "%s" # IP of the robot\n' % server_ip) #self.ROBOT_IP)
234  fid.write('MECA_PORT = %i # Communication port\n\n' % self.ROBOT_PORT)
235  fid.write('import time\n')
236  fid.write('import sys\n')
237  fid.write('global robot\n\n')
238  fid.write(self.PROG)
239 
240  fid.write('def Gripper(set_open=0):\n')
241  fid.write(' global robot\n')
242  fid.write(' robot.Run("Gripper", [set_open])\n')
243  fid.write('\n')
244  fid.write('def RobotConnect():\n')
245  fid.write(" '''Establish connection with the robot'''\n")
246  fid.write(' global robot\n')
247  fid.write(' robot = MecaRobot(MECA_IP, MECA_PORT)\n\n')
248  fid.write('def RobotDisconnect():\n')
249  fid.write(" '''Establish connection with the robot'''\n")
250  fid.write(' global robot\n')
251  fid.write(' try:\n')
252  fid.write(' if robot.sock != None:\n')
253  fid.write(' robot.sock.close()\n')
254  fid.write(' robot.sock = None\n')
255  fid.write(' except Exception as e:\n')
256  fid.write(' print_message(str(e))\n')
257  fid.write('\n#----------- communication class -------------\n')
258  fid.write(ROBOT_CLASS)
259  fid.write(' %s()\n' % self.MAIN_PROG_NAME)
260  fid.write(' \n')
261  fid.write(' print_message("Program sent.\\nWaiting for program to finish...")\n')
262  fid.write(' robot.sock.settimeout(1e6)\n')
263  fid.write(' \n')
264  fid.write(' problems, msg_id, msg_str = msg_info(robot.recv_str())\n')
265  fid.write(' while not problems and msg_id != 3012:\n')
266  fid.write(' print_message("Working... (" + msg_str + ")")\n')
267  fid.write(' problems, msg_id, msg_str = msg_info(robot.recv_str())\n')
268  fid.write(' \n')
269  fid.write(' print_message("Done. Closing in 2 seconds...")\n')
270  fid.write(' time.sleep(2)\n\n')
271  fid.write(' \n')
272  fid.write(' RobotDisconnect()\n')
273  #fid.write(' # pause execution before closing process (allows users to read last message)\n')
274  #fid.write(' time.sleep(2)\n')
275  fid.write('\n\n')
276  fid.close()
277  print('SAVED: %s\n' % filesave)
278  self.PROG_FILES = filesave
279  #---------------------- show result
280 
281  #selection_view = mbox('Do you want to view/edit the program or run it on the robot?', 'View', 'Run')
282  selection_view = True
283 
284  if selection_view and show_result:
285  if type(show_result) is str:
286  # Open file with provided application
287  import subprocess
288  p = subprocess.Popen([show_result, filesave])
289  elif type(show_result) is list:
290  import subprocess
291  p = subprocess.Popen(show_result + [filesave])
292  else:
293  # open file with default application
294  import os
295  os.startfile(filesave)
296 
297  if len(self.LOG) > 0:
298  mbox('Program generation LOG:\n\n' + self.LOG)
299 
300  if not selection_view:
301  RDK.ShowMessage('Running program...', False)
302  proc = subprocess.Popen(['python', filesave])
303 
304  # Using the same pipe
305  #import io
306  #proc = subprocess.Popen(['python', filesave], stdout=subprocess.PIPE)
307  #for line in io.TextIOWrapper(proc.stdout, encoding="utf-8"): # or another encoding
308  # RDK.ShowMessage(line, False)
309 
310 
311  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
312  """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".
313  The connection parameters must be provided in the robot connection menu of RoboDK"""
314  import subprocess
315  import os
316  import sys
317  import time
318 
319  print_message("POPUP: Starting process...")
320  print("Python path " + PATH_PYTHON)
321  print("Program file: " + self.PROG_FILES)
322 
323  # Start process
324  cmd_run = self.PROG_FILES # run py file itself
325  if PATH_PYTHON != '':
326  # if a python path is specified, use it to run the Py file
327  cmd_run = [PATH_PYTHON, self.PROG_FILES]
328 
329  process = subprocess.Popen(cmd_run, shell=True, stdout=subprocess.PIPE, stderr=subprocess.STDOUT, universal_newlines=True)
330 
331  # Poll process for new output until finished
332  for stdout_line in iter(process.stdout.readline, ""):
333  print_message("POPUP: " + stdout_line.strip())
334 
335  process.stdout.close()
336  return_code = process.wait()
337  if return_code != 0:
338  #raise subprocess.CalledProcessError(return_code, cmd_run)
339  pause(2)
340  else:
341  print_message("POPUP: Done.")
342  pause(1)
343 
344  #if (return_code == 0):
345  # return
346  #else:
347  # #raise ProcessException(command, return_code, output)
348  # pause(2)
349  # return
350 
351  def MoveJ(self, pose, joints, conf_RLF=None):
352  """Add a joint movement"""
353  self.addline("robot.Run('MoveJoints', %s)" % joints_2_str(joints))
354 
355  # A MoveJ in cartesian space would be:
356  #if pose is not None:
357  # # self.addline("robot.Run('SetConf', [%i,%i,%i])" % (conf_RLF[0], conf_RLF[1], conf_RLF[2])
358  # self.addline("robot.Run('MovePose', %s)" % pose_2_str(pose))
359 
360 
361  def MoveL(self, pose, joints, conf_RLF=None):
362  """Add a linear movement"""
363  if pose is None:
364  # no linear movement allowed by providing joints
365  self.addline("robot.Run('MoveJoints', %s)" % joints_2_str(joints))
366  else:
367  self.addline("robot.Run('MoveLin', %s)" % pose_2_str(pose))
368 
369  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
370  """Add a circular movement"""
371  self.addlog("Cicular moves not supported")
372 
373  def setFrame(self, pose, frame_id=None, frame_name=None):
374  """Change the robot reference frame"""
375  self.addline("robot.Run('SetWRF', %s)" % pose_2_str(pose))
376 
377  def setTool(self, pose, tool_id=None, tool_name=None):
378  """Change the robot TCP"""
379  self.addline("robot.Run('SetTRF', %s)" % pose_2_str(pose))
380 
381  def Pause(self, time_ms):
382  """Pause the robot program"""
383  if time_ms < 0:
384  self.addline("robot.Run('Delay', 0, sync=True)")
385  self.addline('input("Robot paused. Press Enter to continue...")')
386  else:
387  #self.addline('time.sleep(%.3f)' % (float(time_ms)*0.001))
388  self.addline("robot.Run('Delay', %s)" % (float(time_ms)*0.001))
389 
390  def setSpeed(self, speed_mms):
391  """Changes the robot speed (in mm/s)"""
392  self.addline("robot.Run('SetCartVel', %.3f)" % min(speed_mms,500))
393 
394  def setAcceleration(self, accel_mmss):
395  """Changes the robot acceleration (in mm/s2)"""
396  self.addlog('Linear acceleration not supported')
397 
398  def setSpeedJoints(self, speed_degs):
399  """Changes the robot joint speed (in deg/s)"""
400  self.addline("robot.Run('SetJointVel', %.3f)" % speed_degs)
401 
402  def setAccelerationJoints(self, accel_degss):
403  """Changes the robot joint acceleration (in deg/s2)"""
404  self.addlog('Joint acceleration not supported')
405 
406  def setZoneData(self, zone_mm):
407  """Changes the smoothing radius (aka CNT, APO or zone data) to make the movement smoother"""
408  if zone_mm > 0:
409  self.addline("robot.Run('SetCornering', 1)")
410  else:
411  self.addline("robot.Run('SetCornering', 0)")
412 
413  def setDO(self, io_var, io_value):
414  """Sets a variable (digital output) to a given value"""
415  if type(io_var) != str: # set default variable name if io_var is a number
416  io_var = 'OUT[%s]' % str(io_var)
417  if type(io_value) != str: # set default variable value if io_value is a number
418  if io_value > 0:
419  io_value = 'TRUE'
420  else:
421  io_value = 'FALSE'
422 
423  # at this point, io_var and io_value must be string values
424  # self.addline('%s=%s' % (io_var, io_value))
425  self.addline("robot.Run('Delay', 0, sync=True)")
426  self.addline('# robot.setDO(%s=%s)' % (io_var, io_value))
427  self.addlog('Digital IOs not managed by the robot (%s=%s)' % (io_var, io_value))
428 
429  def waitDI(self, io_var, io_value, timeout_ms=-1):
430  """Waits for a variable (digital input) io_var to attain a given value io_value. Optionally, a timeout can be provided."""
431  if type(io_var) != str: # set default variable name if io_var is a number
432  io_var = 'IN[%s]' % str(io_var)
433  if type(io_value) != str: # set default variable value if io_value is a number
434  if io_value > 0:
435  io_value = 'TRUE'
436  else:
437  io_value = 'FALSE'
438 
439  # at this point, io_var and io_value must be string values
440  if timeout_ms < 0:
441  #self.addline('WAIT FOR %s==%s' % (io_var, io_value))
442  self.addline("robot.Run('Delay', 0, sync=True)")
443  self.addline('# robot.waitDI(%s=%s)' % (io_var, io_value))
444  self.addlog('Digital IOs not managed by the robot (WAIT FOR %s==%s)' % (io_var, io_value))
445  else:
446  #self.addline('WAIT FOR %s==%s TIMEOUT=%.1f' % (io_var, io_value, timeout_ms))
447  self.addline("robot.Run('Delay', 0, sync=True)")
448  self.addline('# robot.waitDI(%s=%s, %.0f)' % (io_var, io_value, timeout_ms))
449  self.addlog('Digital IOs not managed by the robot (WAIT FOR %s==%s)' % (io_var, io_value))
450 
451  def RunCode(self, code, is_function_call = False):
452  """Adds code or a function call"""
453  if is_function_call:
454  code.replace(' ','_')
455  if not code.endswith(')'):
456  code = code + '()'
457  self.addline(code)
458  else:
459  self.addline(code)
460 
461  def RunMessage(self, message, iscomment = False):
462  """Display a message in the robot controller screen (teach pendant)"""
463  if iscomment:
464  self.addline('# ' + message)
465  else:
466  self.addline('print("%s")' % message)
467 
468 # ------------------ private ----------------------
469  def addline(self, newline):
470  """Add a program line"""
471  self.PROG = self.PROG + self.TAB + newline + '\n'
472 
473  def addlog(self, newline):
474  """Add a log message"""
475  self.LOG = self.LOG + newline + '\n'
476 
477 # -------------------------------------------------
478 # ------------ For testing purposes ---------------
479 def Pose(xyzrpw):
480  [x,y,z,r,p,w] = xyzrpw
481  a = r*math.pi/180
482  b = p*math.pi/180
483  c = w*math.pi/180
484  ca = math.cos(a)
485  sa = math.sin(a)
486  cb = math.cos(b)
487  sb = math.sin(b)
488  cc = math.cos(c)
489  sc = math.sin(c)
490  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]])
491 
492 def test_post():
493  """Test the post with a basic program"""
494 
495  robot = RobotPost()
496 
497  robot.ProgStart("Program")
498  robot.RunMessage("Program generated by RoboDK using a custom post processor", True)
499  robot.setFrame(Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
500  robot.setTool(Pose([62.5, -108.253175, 100, -60, 90, 0]))
501  robot.MoveJ(Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
502  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
503  robot.MoveL(Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
504  robot.RunMessage("Setting air valve 1 on")
505  robot.RunCode("TCP_On", True)
506  robot.Pause(1000)
507  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
508  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
509  robot.MoveL(Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
510  robot.RunMessage("Setting air valve off")
511  robot.RunCode("TCP_Off", True)
512  robot.RunCode("Gripper(1)", True)
513  robot.Pause(1000)
514  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
515  robot.MoveL(Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
516  robot.MoveL(Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
517  robot.MoveJ(None, [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
518  robot.ProgFinish("Program")
519  # robot.ProgSave(".","Program",True)
520  print(robot.PROG)
521  if len(robot.LOG) > 0:
522  mbox('Program generation LOG:\n\n' + robot.LOG)
523 
524  input("Press Enter to close...")
525 
526 if __name__ == "__main__":
527  """Function to call when the module is executed by itself: test"""
528  test_post()
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
Definition: Mecademic.py:214
def MoveJ(self, pose, joints, conf_RLF=None)
Definition: Mecademic.py:351
def RunMessage(self, message, iscomment=False)
Definition: Mecademic.py:461
def setFrame(self, pose, frame_id=None, frame_name=None)
Definition: Mecademic.py:373
def RunCode(self, code, is_function_call=False)
Definition: Mecademic.py:451
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
Definition: robodk.py:1458
def waitDI(self, io_var, io_value, timeout_ms=-1)
Definition: Mecademic.py:429
def setTool(self, pose, tool_id=None, tool_name=None)
Definition: Mecademic.py:377
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
Definition: Mecademic.py:311
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
Definition: Mecademic.py:369
def MoveL(self, pose, joints, conf_RLF=None)
Definition: Mecademic.py:361
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
Definition: robodk.py:1354
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
Definition: Mecademic.py:184


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