Toshiba.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 Toshiba Scara robots
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 
48 # ----------------------------------------------------
49 def pose_2_str(pose):
50  """Converts a pose target to a string"""
51  [x,y,z,w,p,r] = Pose_2_Adept(pose)
52  c = angle3(pose.VX(),[1,0,0])*180/pi # angle between X axes
53  return ('TRANS(%.3f,%.3f,%.3f,%.3f)' % (x,y,z,c))
54 
55 def target_2_str(pose,joints):
56  """Converts a pose target to a string"""
57  [x,y,z,w,p,r] = Pose_2_Adept(pose)
58  c = angle3(pose.VX(),[1,0,0])*180/pi # angle between X axes
59  t = joints[3]
60  if joints[1] >= 0:
61  config = 1
62  else:
63  config = 2
64  return ('POINT(%.3f,%.3f,%.3f,%.3f, %.1f, %i)' % (x,y,z,c,t,config))
65 
66 def angles_2_str(angles):
67  """Contverts a joint target to a string"""
68  return '{%s}' % (','.join(format(ji, ".5f") for ji in angles))
69 
70 # ----------------------------------------------------
71 # Object class that handles the robot instructions/syntax
72 class RobotPost(object):
73  """Robot post object"""
74  PROG_EXT = 'txt' # set the program extension
75 
76  # other variables
77  ROBOT_POST = ''
78  ROBOT_NAME = ''
79  PROG_FILES = []
80 
81  PROG = ''
82  LOG = ''
83  nAxes = 6
84  TAB = ''
85  REF_FRAME = None
86 
87  def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
88  self.ROBOT_POST = robotpost
89  self.ROBOT_NAME = robotname
90  self.PROG = ''
91  self.LOG = ''
92  self.nAxes = robot_axes
93 
94  def ProgStart(self, progname):
95  self.addline('PROGRAM %s' % progname)
96  self.TAB = ' '
97 
98  def ProgFinish(self, progname):
99  self.TAB = ''
100  self.addline('END')
101 
102  def ProgSave(self, folder, progname, ask_user = False, show_result = False):
103  progname = progname + '.' + self.PROG_EXT
104  if ask_user or not DirExists(folder):
105  filesave = getSaveFile(folder, progname, 'Save program as...')
106  if filesave is not None:
107  filesave = filesave.name
108  else:
109  return
110  else:
111  filesave = folder + '/' + progname
112  fid = open(filesave, "w")
113  fid.write(self.PROG)
114  fid.close()
115  print('SAVED: %s\n' % filesave) # tell RoboDK the path of the saved file
116  self.PROG_FILES = filesave
117 
118  # open file with default application
119  if show_result:
120  if type(show_result) is str:
121  # Open file with provided application
122  import subprocess
123  p = subprocess.Popen([show_result, filesave])
124  elif type(show_result) is list:
125  import subprocess
126  p = subprocess.Popen(show_result + [filesave])
127  else:
128  # open file with default application
129  import os
130  os.startfile(filesave)
131  if len(self.LOG) > 0:
132  mbox('Program generation LOG:\n\n' + self.LOG)
133 
134  def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass):
135  """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".
136  The connection parameters must be provided in the robot connection menu of RoboDK"""
137  UploadFTP(self.PROG_FILES, robot_ip, remote_path, ftp_user, ftp_pass)
138 
139  def MoveJ(self, pose, joints, conf_RLF=None):
140  """Add a joint movement"""
141  self.addline('MOVE ' + target_2_str(pose, joints))
142 
143  def MoveL(self, pose, joints, conf_RLF=None):
144  """Add a linear movement"""
145  self.addline('MOVES ' + target_2_str(pose, joints))
146 
147  def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None):
148  """Add a circular movement"""
149  self.addline('MOVEC %s %s' % (target_2_str(pose1, joints1), target_2_str(pose2, joints2)))
150 
151  def setFrame(self, pose, frame_id=None, frame_name=None):
152  """Change the robot reference frame"""
153  self.addline('BASE = %s' % pose_2_str(pose))
154 
155  def setTool(self, pose, tool_id=None, tool_name=None):
156  """Change the robot TCP"""
157  self.addline('TOOL = %s' % pose_2_str(pose))
158 
159  def Pause(self, time_ms):
160  """Pause the robot program"""
161  if time_ms <= 0:
162  self.addline('PAUSE')
163  else:
164  self.addline('DELAY %.3f' % (time_ms*0.001))
165 
166  def setSpeed(self, speed_mms):
167  """Changes the robot speed (in mm/s)"""
168  speed_percent = max(100*speed_mms/5000,100)
169  self.addline('SPEED=%.0f' % (speed_percent))
170 
171  def setAcceleration(self, accel_mmss):
172  """Changes the robot acceleration (in mm/s2)"""
173  # Warning! Here, acceleration in mmss is considered as a percentage!
174  #accel_percentage = min(100,max(0,accel_mmss))
175  #self.addline('ACCEL %.1f, %.1f' % (accel_percentage, accel_percentage))
176 
177  def setSpeedJoints(self, speed_degs):
178  """Changes the robot joint speed (in deg/s)"""
179  #self.addlog('setSpeedJoints not defined')
180 
181  def setAccelerationJoints(self, accel_degss):
182  """Changes the robot joint acceleration (in deg/s2)"""
183  #self.addlog('setAccelerationJoints not defined')
184 
185  def setZoneData(self, zone_mm):
186  """Changes the zone data approach (makes the movement more smooth)"""
187  #self.addlog('setZoneData not defined (%.1f mm)' % zone_mm)
188 
189  def setDO(self, io_var, io_value):
190  """Sets a variable (output) to a given value"""
191  if type(io_var) != str: # set default variable name if io_var is a number
192  io_var = 'OUT[%s]' % str(io_var)
193  if type(io_value) != str: # set default variable value if io_value is a number
194  if io_value > 0:
195  io_value = 'TRUE'
196  else:
197  io_value = 'FALSE'
198 
199  # at this point, io_var and io_value must be string values
200  self.addline('%s=%s' % (io_var, io_value))
201 
202  def waitDI(self, io_var, io_value, timeout_ms=-1):
203  """Waits for an input io_var to attain a given value io_value. Optionally, a timeout can be provided."""
204  if type(io_var) != str: # set default variable name if io_var is a number
205  io_var = 'IN[%s]' % str(io_var)
206  if type(io_value) != str: # set default variable value if io_value is a number
207  if io_value > 0:
208  io_value = 'TRUE'
209  else:
210  io_value = 'FALSE'
211 
212  # at this point, io_var and io_value must be string values
213  if timeout_ms < 0:
214  self.addline('WAIT FOR %s==%s' % (io_var, io_value))
215  else:
216  self.addline('WAIT FOR %s==%s TIMEOUT=%.1f' % (io_var, io_value, timeout_ms))
217 
218  def RunCode(self, code, is_function_call = False):
219  """Adds code or a function call"""
220  if is_function_call:
221  code.replace(' ','_')
222  if code.find('(') < 0:
223  code = code + '()'
224  self.addline(code)
225  else:
226  self.addline(code)
227 
228  def RunMessage(self, message, iscomment = False):
229  """Add a joint movement"""
230  if iscomment:
231  self.addline('REMARK %s' % message)
232  else:
233  self.addline('REMARK %s' % message)
234 
235 # ------------------ private ----------------------
236  def addline(self, newline):
237  """Add a program line"""
238  self.PROG = self.PROG + self.TAB + newline + '\n'
239 
240  def addlog(self, newline):
241  """Add a log message"""
242  self.LOG = self.LOG + newline + '\n'
243 
244 # -------------------------------------------------
245 # ------------ For testing purposes ---------------
246 def Pose(xyzrpw):
247  [x,y,z,r,p,w] = xyzrpw
248  a = r*math.pi/180
249  b = p*math.pi/180
250  c = w*math.pi/180
251  ca = math.cos(a)
252  sa = math.sin(a)
253  cb = math.cos(b)
254  sb = math.sin(b)
255  cc = math.cos(c)
256  sc = math.sin(c)
257  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]])
258 
259 def test_post():
260  """Test the post with a basic program"""
261 
262  robot = RobotPost('Vplus_custom', 'Generic Adept Robot')
263 
264  robot.ProgStart("Program")
265  robot.RunMessage("Program generated by RoboDK", True)
266  robot.setFrame(Pose([807.766544, -963.699898, 41.478944, 0, 0, 0]))
267  robot.setTool(Pose([62.5, -108.253175, 100, -60, 90, 0]))
268  robot.MoveJ(Pose([200, 200, 500, 180, 0, 180]), [-46.18419, -6.77518, -20.54925, 71.38674, 49.58727, -302.54752] )
269  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
270  robot.MoveL(Pose([200, 200, 262.132034, 180, 0, -150]), [-43.73892, -3.91728, -35.77935, 58.57566, 54.11615, -253.81122] )
271  robot.RunMessage("Setting air valve 1 on")
272  robot.RunCode("TCP_On", True)
273  robot.Pause(1000)
274  robot.MoveL(Pose([200, 250, 348.734575, 180, 0, -150]), [-41.62707, -8.89064, -30.01809, 60.62329, 49.66749, -258.98418] )
275  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
276  robot.MoveL(Pose([250, 250, 191.421356, 180, 0, -150]), [-39.75778, -1.04537, -40.37883, 52.09118, 54.15317, -246.94403] )
277  robot.RunMessage("Setting air valve off")
278  robot.RunCode("TCP_Off(55)", True)
279  robot.Pause(1000)
280  robot.MoveL(Pose([250, 300, 278.023897, 180, 0, -150]), [-37.52588, -6.32628, -34.59693, 53.52525, 49.24426, -251.44677] )
281  robot.MoveL(Pose([250, 200, 278.023897, 180, 0, -150]), [-41.85389, -1.95619, -34.89154, 57.43912, 52.34162, -253.73403] )
282  robot.MoveL(Pose([250, 150, 191.421356, 180, 0, -150]), [-43.82111, 3.29703, -40.29493, 56.02402, 56.61169, -249.23532] )
283  robot.ProgFinish("Program")
284  # robot.ProgSave(".","Program",True)
285  print(robot.PROG)
286  if len(robot.LOG) > 0:
287  mbox('Program generation LOG:\n\n' + robot.LOG)
288 
289  input("Press Enter to close...")
290 
291 if __name__ == "__main__":
292  """Function to call when the module is executed by itself: test"""
293  test_post()
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
Definition: Toshiba.py:102
def target_2_str(pose, joints)
Definition: Toshiba.py:55
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
Definition: Toshiba.py:134
def MoveL(self, pose, joints, conf_RLF=None)
Definition: Toshiba.py:143
def waitDI(self, io_var, io_value, timeout_ms=-1)
Definition: Toshiba.py:202
def setAccelerationJoints(self, accel_degss)
Definition: Toshiba.py:181
def MoveJ(self, pose, joints, conf_RLF=None)
Definition: Toshiba.py:139
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
Definition: Toshiba.py:147
def UploadFTP(program, robot_ip, remote_path, ftp_user, ftp_pass)
Definition: robodk.py:1312
def RunCode(self, code, is_function_call=False)
Definition: Toshiba.py:218
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: Toshiba.py:151
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
Definition: robodk.py:1354
def setDO(self, io_var, io_value)
Definition: Toshiba.py:189
def RunMessage(self, message, iscomment=False)
Definition: Toshiba.py:228
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)
Definition: Toshiba.py:87
def setTool(self, pose, tool_id=None, tool_name=None)
Definition: Toshiba.py:155


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