Dobot.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 Dobot Magician 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 import os
49 
50 # Get 32 bit Python path. IMPORTANT! It must be 32 bit Python (not 64)
51 PYTHON_PATH = os.path.abspath(os.getenv('APPDATA') + '/../Local/Programs/Python/Python36-32/python.exe')
52 
53 # Get Dobot DLL path based on Desktop path
54 DOBOT_PATH_DLL = os.path.abspath(os.getenv('HOMEPATH') + '/Desktop/DobotAPI/')
55 
56 PROGRAM_HEADER = '''# Dobot program generated from RoboDK post processor
57 import threading
58 import DobotDllType as dType
59 import sys
60 
61 CON_STR = {
62  dType.DobotConnect.DobotConnect_NoError: "DobotConnect_NoError",
63  dType.DobotConnect.DobotConnect_NotFound: "DobotConnect_NotFound",
64  dType.DobotConnect.DobotConnect_Occupied: "DobotConnect_Occupied"}
65 
66 #Load Dll
67 api = dType.load()
68 
69 #Connect Dobot
70 state = dType.ConnectDobot(api, "", 115200)[0]
71 print("Connect status:",CON_STR[state])
72 sys.stdout.flush()
73 
74 if (state != dType.DobotConnect.DobotConnect_NoError):
75  #Disconnect Dobot
76  dType.DisconnectDobot(api)
77  raise Exception("Connection problems: " + CON_STR[state])
78  quit()
79 
80 #Clean Command Queued
81 dType.SetQueuedCmdClear(api)
82 
83 #Async Motion Params Setting
84 dType.SetHOMEParams(api, 200, 200, 200, 200, isQueued = 1)
85 dType.SetPTPJointParams(api, 200, 200, 200, 200, 200, 200, 200, 200, isQueued = 1)
86 dType.SetPTPCommonParams(api, 100, 100, isQueued = 1)
87 
88 #Async Home
89 dType.SetHOMECmd(api, temp = 0, isQueued = 1)
90 
91 # Main program definition
92 '''
93 
94 PROGRAM_RUN = '''
95  # Save the index command of the last command (set a short pause)
96  lastIndex = dType.SetWAITCmd(api, 0.1, isQueued = 1)[0]
97 
98  # Start to Execute Queued Commands
99  dType.SetQueuedCmdStartExec(api)
100 
101  # Wait until execution is done by verifying current command
102  while lastIndex > dType.GetQueuedCmdCurrentIndex(api)[0]:
103  dType.dSleep(100)
104 '''
105 
106 ROBOT_DISCONNECT = '''
107 #Disconnect Dobot
108 dType.DisconnectDobot(api)
109 '''
110 
111 # ----------------------------------------------------
112 def pose_2_str(pose):
113  """Prints a pose target"""
114  [x,y,z,r,p,w] = Pose_2_TxyzRxyz(pose)
115  #return ('%.3f, %.3f, %.3f, %.3f, %.3f, %.3f' % (x,y,z,r*180.0/pi,p*180.0/pi,w*180.0/pi))
116  return ('%.3f, %.3f, %.3f, %.3f' % (x,y,z, w*180.0/pi))
117 
118 def joints_2_str(joints):
119  """Prints a joint target"""
120  str = ''
121  for i in range(len(joints)):
122  str = str + ('%.6f, ' % joints[i])
123  str = str[:-2]
124  return str
125 
126 # ----------------------------------------------------
127 # Object class that handles the robot instructions/syntax
128 class RobotPost(object):
129  """Robot post object"""
130  PROG_EXT = 'py' # set the program extension
131  ROBOT_IP = '192.168.0.100';
132  ROBOT_PORT = 10000
133 
134  # other variables
135  ROBOT_POST = ''
136  ROBOT_NAME = ''
137  PROG_FILES = []
138 
139  FRAME = eye(4)
140  TOOL = eye(4)
141 
142  PROG = ''
143  LOG = ''
144  TAB = ''
145  MAIN_PROG_NAME = None
146  nAxes = 6
147  Prog_count = 0
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  self.addline('def %s():' % progname)
160  self.TAB = ' '
161  if self.MAIN_PROG_NAME is None:
162  self.MAIN_PROG_NAME = progname
163  self.addline("'''Main procedure'''")
164  else:
165  self.addline("'''Subprogram %s'''" % progname)
166  self.addline("print('Sending program %s ...')" % progname)
167 
168  def ProgFinish(self, progname):
169  #if self.Prog_count == 1:
170  #self.PROG.append(PROGRAM_DISCONNECT)
171  #pass
172  self.addline("print('Program %s sent')" % progname)
173  self.addline("sys.stdout.flush()")
174  self.addline("print('Running program %s on robot...')" % progname)
175  self.addline("sys.stdout.flush()")
176  self.PROG = self.PROG + PROGRAM_RUN
177  self.addline("")
178  self.addline("# Stop executing commands")
179  self.addline("dType.SetQueuedCmdStopExec(api)")
180  self.addline("# Clear all queued commands")
181  self.addline("dType.SetQueuedCmdClear(api)")
182  self.addline("print('Program %s Finished')" % progname)
183  self.addline("sys.stdout.flush()")
184  self.TAB = ''
185  self.addline('')
186 
187 
188  def ProgSave(self, folder, progname, ask_user=False, show_result=False):
189  import subprocess
190  progname = progname + '.' + self.PROG_EXT
191  if ask_user or not DirExists(folder):
192  filesave = getSaveFile(folder, progname, 'Save program as...')
193  if filesave is not None:
194  filesave = filesave.name
195  else:
196  return
197  else:
198  filesave = folder + '/' + progname
199 
200  fid = open(filesave, "w")
201 
202  fid.write(PROGRAM_HEADER)
203  fid.write(self.PROG)
204  fid.write('\n')
205  fid.write('# Main program call: set as a loop\n')
206  fid.write('while True:\n')
207  fid.write(' %s()\n' % self.MAIN_PROG_NAME)
208  fid.write(' break\n')
209  fid.write(ROBOT_DISCONNECT)
210  fid.write('\n\n')
211  fid.close()
212  print('SAVED: %s\n' % filesave)
213  self.PROG_FILES = filesave
214  #---------------------- show result
215 
216  #selection_view = mbox('Do you want to view/edit the program or run it on the robot?', 'View', 'Run')
217  selection_view = True
218 
219  if selection_view and show_result:
220  if type(show_result) is str:
221  # Open file with provided application
222  import subprocess
223  p = subprocess.Popen([show_result, filesave])
224  elif type(show_result) is list:
225  import subprocess
226  p = subprocess.Popen(show_result + [filesave])
227  else:
228  # open file with default application
229  import os
230  os.startfile(filesave)
231 
232  if len(self.LOG) > 0:
233  mbox('Program generation LOG:\n\n' + self.LOG)
234 
235  if not selection_view:
236  #RDK.ShowMessage('Running program...', False)
237  proc = subprocess.Popen(['python', filesave])
238 
239  # Using the same pipe
240  #import io
241  #proc = subprocess.Popen(['python', filesave], stdout=subprocess.PIPE)
242  #for line in io.TextIOWrapper(proc.stdout, encoding="utf-8"): # or another encoding
243  # RDK.ShowMessage(line, False)
244 
245 
246  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
247  """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".
248  The connection parameters must be provided in the robot connection menu of RoboDK"""
249  # retrieve robot IP
250  #RDK = Robolink()
251  #robot = RDK.Item(self.ROBOT_NAME, ITEM_TYPE_ROBOT)
252  #[server_ip, port, remote_path, username, password] = robot.ConnectionParams()
253  #RDK.ShowMessage('Running program...', False)
254  import subprocess
255  import os
256  import sys
257 
258  process_env = os.environ.copy()
259  process_env["PYTHONPATH"] = DOBOT_PATH_DLL + ";"
260  process_env["PATH"] = DOBOT_PATH_DLL + ":" + process_env["PATH"]
261 
262  print("POPUP: Starting process...")
263  PROGRAM_FILE = os.path.abspath(self.PROG_FILES)
264  print("Python path: " + PYTHON_PATH)
265  print("Program file: " + PROGRAM_FILE)
266  sys.stdout.flush()
267 
268  # Start process
269  process = subprocess.Popen([PYTHON_PATH, PROGRAM_FILE], shell=True, stdout=subprocess.PIPE, stderr=subprocess.STDOUT, env=process_env, universal_newlines=True, cwd=DOBOT_PATH_DLL)
270 
271  # Poll process for new output until finished
272  for stdout_line in iter(process.stdout.readline, ""):
273  print("POPUP: " + stdout_line.strip())
274  sys.stdout.flush()
275 
276  process.stdout.close()
277  return_code = process.wait()
278  if return_code:
279  raise subprocess.CalledProcessError(return_code, [PYTHON_PATH, PROGRAM_FILE])
280 
281  if (return_code == 0):
282  import time
283  time.sleep(2)
284  return
285  else:
286  raise ProcessException(command, return_code, output)
287 
288  def MoveJ(self, pose, joints, conf_RLF=None):
289  """Add a joint movement"""
290  # Prioritize a joint move using joint data
291  if joints is not None:
292  self.addline("dType.SetPTPCmd(api, dType.PTPMode.PTPMOVJANGLEMode, %s, isQueued=1)" % joints_2_str(joints))
293  else:
294  robot_pose = self.FRAME*pose*invH(self.TOOL)
295  self.addline("dType.SetPTPCmd(api, dType.PTPMode.PTPMOVLXYZMode, %s, isQueued=1)" % pose_2_str(robot_pose))
296 
297  def MoveL(self, pose, joints, conf_RLF=None):
298  """Add a linear movement"""
299  # Prioritize a linear move using joint data
300  if joints is not None:
301  self.addline("dType.SetPTPCmd(api, dType.PTPMode.PTPMOVJANGLEMode, %s, isQueued=1)" % joints_2_str(joints))
302  else:
303  robot_pose = self.FRAME*pose*invH(self.TOOL)
304  self.addline("dType.SetPTPCmd(api, dType.PTPMode.PTPMOVLXYZMode, %s, isQueued=1)" % pose_2_str(robot_pose))
305 
306  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1, conf_RLF_2):
307  """Add a circular movement"""
308  robot_pose1 = self.FRAME*pose1*invH(self.TOOL)
309  robot_pose2 = self.FRAME*pose2*invH(self.TOOL)
310  self.addline('dType.SetARCCmd(api, (%s), (%s), isQueued=1)' %(pose_2_str(robot_pose1), pose_2_str(robot_pose2)))
311 
312  def setFrame(self, pose, frame_id=None, frame_name=None):
313  """Change the robot reference frame"""
314  self.FRAME = pose
315 
316  def setTool(self, pose, tool_id=None, tool_name=None):
317  """Change the robot TCP"""
318  self.TOOL = pose
319 
320  def Pause(self, time_ms):
321  """Pause the robot program"""
322  if time_ms < 0:
323  self.addline("dType.SetWAITCmd(api, 0.1, 1)")
324  mbox("Robot paused, press OK to continue")
325  else:
326  self.addline("dType.SetWAITCmd(api, %s, 1)" % (time_ms * 0.001))
327 
328  def setSpeed(self, speed_mms):
329  """Changes the robot speed (in mm/s)"""
330  #self.addline("robot.Run('SetCartVel', %.3f)" % speed_mms)
331  pass
332 
333  def setAcceleration(self, accel_mmss):
334  """Changes the robot acceleration (in mm/s2)"""
335  self.addlog('Linear acceleration not supported')
336 
337  def setSpeedJoints(self, speed_degs):
338  """Changes the robot joint speed (in deg/s)"""
339  #self.addline("robot.Run('SetJointVel', %.3f)" % speed_degs)
340  pass
341 
342  def setAccelerationJoints(self, accel_degss):
343  """Changes the robot joint acceleration (in deg/s2)"""
344  #self.addlog('Joint acceleration not supported')
345  pass
346 
347  def setZoneData(self, zone_mm):
348  """Changes the smoothing radius (aka CNT, APO or zone data) to make the movement smoother"""
349  #if zone_mm > 0:
350  # self.addline("robot.Run('SetCornering', 1)")
351  #else:
352  # self.addline("robot.Run('SetCornering', 0)")
353  pass
354 
355  def setDO(self, io_var, io_value):
356  """Sets a variable (digital output) to a given value"""
357  if type(io_var) != str: # set default variable name if io_var is a number
358  io_var = 'OUT[%s]' % str(io_var)
359  if type(io_value) != str: # set default variable value if io_value is a number
360  if io_value > 0:
361  io_value = 'TRUE'
362  else:
363  io_value = 'FALSE'
364 
365  # at this point, io_var and io_value must be string values
366  # self.addline('%s=%s' % (io_var, io_value))
367  self.addlog('Digital IOs not managed by the robot (%s=%s)' % (io_var, io_value))
368 
369  def waitDI(self, io_var, io_value, timeout_ms=-1):
370  """Waits for a variable (digital input) io_var to attain a given value io_value. Optionally, a timeout can be provided."""
371  if type(io_var) != str: # set default variable name if io_var is a number
372  io_var = 'IN[%s]' % str(io_var)
373  if type(io_value) != str: # set default variable value if io_value is a number
374  if io_value > 0:
375  io_value = 'TRUE'
376  else:
377  io_value = 'FALSE'
378 
379  # at this point, io_var and io_value must be string values
380  if timeout_ms < 0:
381  #self.addline('WAIT FOR %s==%s' % (io_var, io_value))
382  self.addlog('Digital IOs not managed by the robot (WAIT FOR %s==%s)' % (io_var, io_value))
383  else:
384  #self.addline('WAIT FOR %s==%s TIMEOUT=%.1f' % (io_var, io_value, timeout_ms))
385  self.addlog('Digital IOs not managed by the robot (WAIT FOR %s==%s)' % (io_var, io_value))
386 
387  def RunCode(self, code, is_function_call = False):
388  """Adds code or a function call"""
389  if is_function_call:
390  code.replace(' ','_')
391  if not code.endswith(')'):
392  code = code + '()'
393  self.addline(code)
394  else:
395  self.addline(code)
396 
397  def RunMessage(self, message, iscomment = False):
398  """Display a message in the robot controller screen (teach pendant)"""
399  if iscomment:
400  self.addline('# ' + message)
401  else:
402  self.addline('print("%s")' % message)
403 
404 # ------------------ private ----------------------
405  def addline(self, newline):
406  """Add a program line"""
407  self.PROG = self.PROG + self.TAB + newline + '\n'
408 
409  def addlog(self, newline):
410  """Add a log message"""
411  self.LOG = self.LOG + newline + '\n'
412 
413 # -------------------------------------------------
414 # ------------ For testing purposes ---------------
415 def Pose(xyzrpw):
416  [x,y,z,r,p,w] = xyzrpw
417  a = r*math.pi/180
418  b = p*math.pi/180
419  c = w*math.pi/180
420  ca = math.cos(a)
421  sa = math.sin(a)
422  cb = math.cos(b)
423  sb = math.sin(b)
424  cc = math.cos(c)
425  sc = math.sin(c)
426  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]])
427 
428 def test_post():
429  """Test the post with a basic program"""
430 
431  robot = RobotPost()
432 
433  robot.ProgStart("Program")
434  robot.RunMessage("Program generated by RoboDK using a custom post processor", True)
435  robot.setFrame(Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
436  robot.setTool(Pose([62.5, -108.253175, 100, -60, 90, 0]))
437  robot.MoveJ(Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
438  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
439  robot.MoveL(Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
440  robot.RunMessage("Setting air valve 1 on")
441  robot.RunCode("TCP_On", True)
442  robot.Pause(1000)
443  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
444  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
445  robot.MoveL(Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
446  robot.RunMessage("Setting air valve off")
447  robot.RunCode("TCP_Off", True)
448  robot.Pause(1000)
449  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
450  robot.MoveL(Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
451  robot.MoveL(Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
452  robot.MoveJ(None, [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
453  robot.ProgFinish("Program")
454  # robot.ProgSave(".","Program",True)
455  print(robot.PROG)
456  if len(robot.LOG) > 0:
457  mbox('Program generation LOG:\n\n' + robot.LOG)
458 
459  input("Press Enter to close...")
460 
461 if __name__ == "__main__":
462  """Function to call when the module is executed by itself: test"""
463  test_post()
def setSpeedJoints(self, speed_degs)
Definition: Dobot.py:337
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
Definition: Dobot.py:150
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
Definition: Dobot.py:246
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1, conf_RLF_2)
Definition: Dobot.py:306
def waitDI(self, io_var, io_value, timeout_ms=-1)
Definition: Dobot.py:369
def RunCode(self, code, is_function_call=False)
Definition: Dobot.py:387
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
Definition: Dobot.py:188
def setTool(self, pose, tool_id=None, tool_name=None)
Definition: Dobot.py:316
def MoveJ(self, pose, joints, conf_RLF=None)
Definition: Dobot.py:288
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
Definition: robodk.py:1458
def setAccelerationJoints(self, accel_degss)
Definition: Dobot.py:342
def RunMessage(self, message, iscomment=False)
Definition: Dobot.py:397
def setFrame(self, pose, frame_id=None, frame_name=None)
Definition: Dobot.py:312
def setAcceleration(self, accel_mmss)
Definition: Dobot.py:333
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
Definition: robodk.py:1354
def MoveL(self, pose, joints, conf_RLF=None)
Definition: Dobot.py:297
def setDO(self, io_var, io_value)
Definition: Dobot.py:355


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