zeroconf.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # License: BSD
00004 #   https://raw.github.com/robotics-in-concert/rocon_multimaster/master/rocon_gateway/LICENSE
00005 #
00006 
00007 ###############################################################################
00008 # Imports
00009 ###############################################################################
00010 
00011 import roslib
00012 roslib.load_manifest('rocon_gateway')
00013 import rospy
00014 import zeroconf_msgs.srv
00015 
00016 ###############################################################################
00017 # Constants
00018 ###############################################################################
00019 
00020 gateway_hub_service = "_ros-multimaster-hub._tcp"
00021 
00022 ###############################################################################
00023 # Functions
00024 ###############################################################################
00025 
00026 def resolve_address(msg):
00027     '''
00028       Resolves a zeroconf address into ip/port portions.
00029       @var msg : zeroconf_msgs.DiscoveredService 
00030       @return (string,int) : ip, port pair.
00031     '''
00032     ip = "localhost"
00033     if not msg.is_local:
00034         ip = msg.ipv4_addresses[0]
00035     return (ip,msg.port)
00036     
00037 def setup_ros_services():
00038     '''
00039       Looks to see if it can find the zeroconf services that
00040       will help it auto-discover a hub. If it finds them, 
00041       it hooks up the required ros services with the zeroconf node.
00042       
00043       @return success of the hookup
00044       @rtype bool
00045     '''
00046     zeroconf_services = {}
00047     zeroconf_timeout = 5 # Amount of time to wait for the zeroconf services to appear
00048     rospy.loginfo("Gateway : looking to see if zeroconf services are available...")
00049     try:
00050         rospy.wait_for_service("zeroconf/add_listener", timeout=zeroconf_timeout)
00051         zeroconf_services["add_listener"] = rospy.ServiceProxy("zeroconf/add_listener",zeroconf_msgs.srv.AddListener)
00052         zeroconf_services["list_discovered_services"] = rospy.ServiceProxy("zeroconf/list_discovered_services",zeroconf_msgs.srv.ListDiscoveredServices)
00053         if not zeroconf_services["add_listener"](service_type = gateway_hub_service):
00054             zeroconf.services = {} # failure
00055     except rospy.ROSException:
00056         rospy.logwarn("Gateway : timed out waiting for zeroconf services to become available.")
00057     return zeroconf_services
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


rocon_gateway
Author(s): Daniel Stonier, Jihoon Lee,
autogenerated on Tue Jan 15 2013 17:43:24