47 from robolink 
import *
    53 def print_message(message):    54     """Force a print output"""    58 def msg_info(robot_msg):    60         return False, -1, "No communication"            62     msg_id = int(robot_msg[1:5])    63     msg_str = robot_msg[7:-2]    64     # msg_id = 1000 to 1500 are error codes    69         error_codes = [3001, 3003]    70         if msg_id in error_codes:    73         print_message(robot_msg)    74     return problems, msg_id, msg_str    77     """Robot class for programming Mecademic robots"""    78     def __init__(self, ip, port):    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...')    88         # receive welcome message and output to the log    89         problems, msg_id, msg_str = msg_info(self.recv_str())    91             print_message(msg_str)    92             raise Exception(msg_str)    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)   102     def send_str(self, msg):   103         sent = self.sock.send(bytes(msg+'\\0','ascii'))   105             raise RuntimeError("Robot connection broken")   108         bdata = self.sock.recv(self.BUFFER_SIZE)   110             raise RuntimeError("Robot connection broken")   111         return bdata.decode('ascii')   113     def Run(self, cmd, values=None, sync=False):   114         if isinstance(values, list):   116                 str_send = cmd + '(' + (','.join(format(vi, ".0f") for vi in values)) + ')'   118                 str_send = cmd + '(' + (','.join(format(vi, ".6f") for vi in values)) + ')'   122             str_send = cmd + '(' + str(values) + ')'   124         print_message('Running: %s' % str_send)   126         # send command to robot   127         self.send_str(str_send)   129             robot_msg = self.recv_str()   130             problems, msg_id, msg_str = msg_info(robot_msg)   131             print_message('Received: %s' % robot_msg)   133                 raise Exception(msg_str)             136 if __name__ == "__main__":   137     """Call Main procedure"""   138     # It is important to disconnect the robot if we force to stop the process   140     atexit.register(RobotDisconnect)   151     """Prints a pose target"""   153     return (
'[%.3f, %.3f, %.3f, %.3f, %.3f, %.3f]' % (x,y,z,r*180.0/pi,p*180.0/pi,w*180.0/pi))
   156     """Prints a joint target"""   158     for i 
in range(len(joints)):
   159         str = str + (
'%.6f, ' % joints[i])
   166     """Robot post object"""   168     ROBOT_IP = 
'192.168.0.100';
   179     MAIN_PROG_NAME = 
None   184     def __init__(self, robotpost=None, robotname=None, robot_axes = 6, **kwargs):
   193         self.
addline(
'def %s():' % progname)
   197             self.
addline(
"'''Main procedure'''")
   202         self.
addline(
'print_message("Running program %s...")' % progname)
   205         self.
addline(
'print_message("Program %s Sent")' % progname)
   214     def ProgSave(self, folder, progname, ask_user=False, show_result=False):
   216         progname = progname + 
'.' + self.
PROG_EXT   218             filesave = 
getSaveFile(folder, progname, 
'Save program as...')
   219             if filesave 
is not None:
   220                 filesave = filesave.name
   224             filesave = folder + 
'/' + progname
   228         robot = RDK.Item(self.
ROBOT_NAME, ITEM_TYPE_ROBOT)
   229         [server_ip, port, remote_path, username, password] = robot.ConnectionParams()            
   231         fid = open(filesave, 
"w")
   233         fid.write(
'MECA_IP = "%s"   # IP of the robot\n' % server_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')
   240         fid.write(
'def Gripper(set_open=0):\n')
   241         fid.write(
'    global robot\n')
   242         fid.write(
'    robot.Run("Gripper", [set_open])\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')
   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)
   261         fid.write(
'    print_message("Program sent.\\nWaiting for program to finish...")\n')
   262         fid.write(
'    robot.sock.settimeout(1e6)\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')
   269         fid.write(
'    print_message("Done. Closing in 2 seconds...")\n')
   270         fid.write(
'    time.sleep(2)\n\n')
   272         fid.write(
'    RobotDisconnect()\n')        
   277         print(
'SAVED: %s\n' % filesave)
   282         selection_view = 
True   284         if selection_view 
and show_result:
   285             if type(show_result) 
is str:
   288                 p = subprocess.Popen([show_result, filesave])   
   289             elif type(show_result) 
is list:
   291                 p = subprocess.Popen(show_result + [filesave])   
   295                 os.startfile(filesave)  
   297             if len(self.
LOG) > 0:
   298                 mbox(
'Program generation LOG:\n\n' + self.
LOG)
   300         if not selection_view:
   301             RDK.ShowMessage(
'Running program...', 
False)
   302             proc = subprocess.Popen([
'python', filesave])
   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"""   320         print(
"Python path " + PATH_PYTHON)
   325         if PATH_PYTHON != 
'':
   329         process = subprocess.Popen(cmd_run, shell=
True, stdout=subprocess.PIPE, stderr=subprocess.STDOUT, universal_newlines=
True)
   332         for stdout_line 
in iter(process.stdout.readline, 
""):
   335         process.stdout.close()
   336         return_code = process.wait()
   351     def MoveJ(self, pose, joints, conf_RLF=None):
   352         """Add a joint movement"""   361     def MoveL(self, pose, joints, conf_RLF=None):
   362         """Add a linear movement"""   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")
   373     def setFrame(self, pose, frame_id=None, frame_name=None):
   374         """Change the robot reference frame"""   377     def setTool(self, pose, tool_id=None, tool_name=None):
   378         """Change the robot TCP"""   382         """Pause the robot program"""   384             self.
addline(
"robot.Run('Delay', 0, sync=True)")
   385             self.
addline(
'input("Robot paused. Press Enter to continue...")')
   388             self.
addline(
"robot.Run('Delay', %s)" % (float(time_ms)*0.001))
   391         """Changes the robot speed (in mm/s)"""   392         self.
addline(
"robot.Run('SetCartVel', %.3f)" % min(speed_mms,500))
   395         """Changes the robot acceleration (in mm/s2)"""   396         self.
addlog(
'Linear acceleration not supported')
   399         """Changes the robot joint speed (in deg/s)"""   400         self.
addline(
"robot.Run('SetJointVel', %.3f)" % speed_degs)
   403         """Changes the robot joint acceleration (in deg/s2)"""   404         self.
addlog(
'Joint acceleration not supported')
   407         """Changes the smoothing radius (aka CNT, APO or zone data) to make the movement smoother"""   409             self.
addline(
"robot.Run('SetCornering', 1)")
   411             self.
addline(
"robot.Run('SetCornering', 0)")
   414         """Sets a variable (digital output) to a given value"""   415         if type(io_var) != str:  
   416             io_var = 
'OUT[%s]' % str(io_var)
   417         if type(io_value) != str: 
   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))
   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:  
   432             io_var = 
'IN[%s]' % str(io_var)
   433         if type(io_value) != str: 
   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))
   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))
   451     def RunCode(self, code, is_function_call = False):
   452         """Adds code or a function call"""   454             code.replace(
' ',
'_')
   455             if not code.endswith(
')'):
   462         """Display a message in the robot controller screen (teach pendant)"""   466             self.
addline(
'print("%s")' % message)
   470         """Add a program line"""   474         """Add a log message"""   475         self.
LOG = self.
LOG + newline + 
'\n'   480     [x,y,z,r,p,w] = xyzrpw
   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]])
   493     """Test the post with a basic program"""   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)
   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)
   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")
   521     if len(robot.LOG) > 0:
   522         mbox(
'Program generation LOG:\n\n' + robot.LOG)
   524     input(
"Press Enter to close...")
   526 if __name__ == 
"__main__":
   527     """Function to call when the module is executed by itself: test""" def setSpeedJoints(self, speed_degs)
def ProgStart(self, progname)
def ProgFinish(self, progname)
def ProgSave(self, folder, progname, ask_user=False, show_result=False)
def setSpeed(self, speed_mms)
def MoveJ(self, pose, joints, conf_RLF=None)
def setAccelerationJoints(self, accel_degss)
def RunMessage(self, message, iscomment=False)
def setFrame(self, pose, frame_id=None, frame_name=None)
def RunCode(self, code, is_function_call=False)
def setZoneData(self, zone_mm)
def addline(self, newline)
def setDO(self, io_var, io_value)
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
def waitDI(self, io_var, io_value, timeout_ms=-1)
def setTool(self, pose, tool_id=None, tool_name=None)
def ProgSendRobot(self, robot_ip, remote_path, ftp_user, ftp_pass)
def addlog(self, newline)
def MoveC(self, pose1, joints1, pose2, joints2, conf_RLF_1=None, conf_RLF_2=None)
def MoveL(self, pose, joints, conf_RLF=None)
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
def print_message(message)
def setAcceleration(self, accel_mmss)
def __init__(self, robotpost=None, robotname=None, robot_axes=6, kwargs)