topics.py
Go to the documentation of this file.
00001 #
00002 # License: BSD
00003 #   https://raw.github.com/robotics-in-concert/rocon_tools/license/LICENSE
00004 #
00005 ##############################################################################
00006 # Imports
00007 ##############################################################################
00008 
00009 import rospy
00010 import time
00011 import rostopic
00012 
00013 from .exceptions import NotFoundException
00014 
00015 ##############################################################################
00016 # Find topics/services
00017 ##############################################################################
00018 
00019 
00020 def find_topic(topic_type, timeout=rospy.rostime.Duration(5.0), unique=False):
00021     '''
00022       Do a lookup to find topics of the type
00023       specified. This will raise exceptions if it times out or returns
00024       multiple values. It can apply the additional logic of whether this should
00025       return a single unique result, or a list.
00026 
00027       @param topic_type : topic type specification, e.g. rocon_std_msgs/MasterInfo
00028       @type str
00029 
00030       @param timeout : raise an exception if nothing is found before this timeout occurs.
00031       @type rospy.rostime.Duration
00032 
00033       @param unique : flag to select the lookup behaviour (single/multiple results)
00034       @type bool
00035 
00036       @return the fully resolved name of the topic (unique) or list of names (non-unique)
00037       @type str
00038 
00039       @raise rocon_python_comms.NotFoundException if no topic is found within the timeout
00040     '''
00041     topic_name = None
00042     topic_names = []
00043     timeout_time = time.time() + timeout.to_sec()
00044     while not rospy.is_shutdown() and time.time() < timeout_time and not topic_names:
00045         try:
00046             topic_names = rostopic.find_by_type(topic_type)
00047         except rostopic.ROSTopicException:
00048             raise NotFoundException("ros shutdown")
00049         if unique:
00050             if len(topic_names) > 1:
00051                 raise NotFoundException("multiple topics found %s." % topic_names)
00052             elif len(topic_names) == 1:
00053                 topic_name = topic_names[0]
00054         if not topic_names:
00055             rospy.rostime.wallsleep(0.1)
00056     if not topic_names:
00057         raise NotFoundException("timed out")
00058     return topic_name if topic_name else topic_names


rocon_python_comms
Author(s): Daniel Stonier
autogenerated on Fri May 2 2014 10:35:42