rosping_existence.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 """
00004 rosping_existence.py
00005 
00006 check the existence of the ros nodes and publish the result to diagnostics
00007 """
00008 
00009 import rospy
00010 try:
00011     from xmlrpc.client import ServerProxy
00012 except ImportError:
00013     from xmlrpclib import ServerProxy
00014 
00015 from rosnode import *
00016 import sys
00017 import roslaunch
00018 import diagnostic_updater
00019 import diagnostic_msgs
00020 
00021 def _succeed(args):
00022     code, msg, val = args
00023     if code != 1:
00024         raise ROSNodeException("remote call failed: %s"%msg)
00025     return val
00026 
00027 def ping(node_name, max_count=None, verbose=False):
00028     """
00029     Test connectivity to node by calling its XMLRPC API
00030     @param node_name: name of node to ping
00031     @type  node_name: str
00032     @param max_count: number of ping requests to make
00033     @type  max_count: int
00034     @param verbose: print ping information to screen
00035     @type  verbose: bool
00036     @return: True if node pinged
00037     @rtype: bool
00038     @raise ROSNodeIOException: if unable to communicate with master
00039     """
00040     master = rosgraph.Master(ID)
00041     node_api = get_api_uri(master,node_name)
00042     if not node_api:
00043         # print "cannot ping [%s]: unknown node" % node_name, file=sys.stderr
00044         return False
00045 
00046     timeout = 3.
00047 
00048     if verbose:
00049         print("pinging %s with a timeout of %ss"%(node_name, timeout))
00050     socket.setdefaulttimeout(timeout)
00051     node = ServerProxy(node_api)
00052     lastcall = 0.
00053     count = 0
00054     acc = 0.
00055     try:
00056         while True:
00057             try:
00058                 count += 1
00059                 start = time.time()
00060                 pid = _succeed(node.getPid(ID))
00061                 end = time.time()
00062 
00063                 dur = (end-start)*1000.
00064                 acc += dur
00065                 
00066 
00067                 if verbose:
00068                     print("xmlrpc reply from %s\ttime=%fms"%(node_api, dur))
00069                 # 1s between pings
00070             except socket.error as e:
00071                 # 3786: catch ValueError on unpack as socket.error is not always a tuple
00072                 try:
00073                     # #3659
00074                     errnum, msg = e
00075                     if errnum == -2: #name/service unknown
00076                         p = urlparse.urlparse(node_api)
00077                         #print("ERROR: Unknown host [%s] for node [%s]"%(p.hostname, node_name), file=sys.stderr)
00078                     elif errnum == errno.ECONNREFUSED:
00079                         # check if node url has changed
00080                         new_node_api = get_api_uri(master,node_name, skip_cache=True)
00081                         if not new_node_api:
00082                             #print("cannot ping [%s]: unknown node"%node_name, file=sys.stderr)
00083                             return False
00084                         if new_node_api != node_api:
00085                             if verbose:
00086                                 print("node url has changed from [%s] to [%s], retrying to ping"%(node_api, new_node_api))
00087                             node_api = new_node_api
00088                             node = ServerProxy(node_api)
00089                             continue
00090                          #print("ERROR: connection refused to [%s]"%(node_api), file=sys.stderr)
00091                     else:
00092                         pass
00093                         #print("connection to [%s] timed out"%node_name, file=sys.stderr)
00094                     return False
00095                 except ValueError:
00096                     print("unknown network error contacting node: %s"%(str(e)))
00097             if max_count and count >= max_count:
00098                 break
00099             time.sleep(1.0)
00100     except KeyboardInterrupt:
00101         pass
00102             
00103     if verbose and count > 1:
00104         print("ping average: %fms"%(acc/count))
00105     return True
00106 
00107 def checkNodeExistence(stat):
00108     global nodes
00109     result = {}
00110     have_dead = False
00111     for n in nodes:
00112         res = ping(n, max_count = 1, verbose = False)
00113         result[n] = res
00114         if not res:
00115             have_dead = True
00116     if have_dead:
00117         stat.summary(diagnostic_msgs.msg.DiagnosticStatus.ERROR,
00118                      "dead nodes: " + ", ".join([n for (n, res) 
00119                                                  in result.items() if not res]))
00120     else:
00121         stat.summary(diagnostic_msgs.msg.DiagnosticStatus.OK,
00122                      "every node is alive")
00123     for n, res in result.items():
00124         stat.add(n, res)
00125     return stat
00126         
00127 if __name__ == "__main__":
00128     rospy.init_node('rosping_existence')
00129     updater = diagnostic_updater.Updater()
00130     updater.setHardwareID(rospy.get_name())
00131     updater.add("node existence", checkNodeExistence)
00132     argv = rospy.myargv()
00133     # you can specify the list of the launch files
00134     launch_files = argv[1:]
00135     config = roslaunch.config.load_config_default(launch_files, 0)
00136     nodes = [n.namespace + n.name for n in config.nodes]
00137     r = rospy.Rate(0.1)
00138     while not rospy.is_shutdown():
00139         updater.update()
00140         r.sleep()
00141     


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Sun Jan 25 2015 12:38:34