Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 """
00034 topics.py
00035
00036 Functions to do with topics
00037 """
00038 import roslib
00039 roslib.load_manifest('starmac_roshlib')
00040 from rospy import loginfo, sleep
00041 from rosh import nodes, info, topics
00042
00043 def is_publishing(node_name, topic_name):
00044 if nodes is None:
00045 return False
00046 else:
00047 topics_published = [info(s).name for s in info(nodes[node_name]).pubs]
00048 return True in [s.find(topic_name) >= 0 for s in topics_published]
00049
00050 def is_subscribing(node_name, topic_name):
00051 if nodes is None:
00052 return False
00053 else:
00054 topics_subscribed = [info(s).name for s in info(nodes[node_name]).subs]
00055 return True in [s.find(topic_name) >= 0 for s in topics_subscribed]
00056
00057 def wait_for_topic(node_name, topic_name, sleep_time=0.5):
00058 loginfo("Waiting for node %s to publish topic %s" % (node_name, topic_name))
00059 while not is_publishing(node_name, topic_name):
00060
00061 sleep(sleep_time)
00062 loginfo("Node %s is now publishing topic %s" % (node_name, topic_name))
00063
00064 def wait_for_topic_sub(node_name, topic_name, sleep_time=0.5):
00065 loginfo("Waiting for node %s to subscribe to topic %s" % (node_name, topic_name))
00066 while not is_subscribing(node_name, topic_name):
00067
00068 sleep(sleep_time)
00069 loginfo("Node %s is now subscribing to topic %s" % (node_name, topic_name))
00070
00071 def topics_list():
00072 all_topics = []
00073 for t in topics:
00074 all_topics.extend(list(t._list()))
00075 return all_topics
00076
00077 def wait_for_topic_existence(topic_name, sleep_time=0.5):
00078 loginfo("Waiting for topic %s to show up in topics list" % topic_name)
00079 while not topic_name in topics_list():
00080 sleep(sleep_time)
00081 loginfo("Topic %s is now in topics list" % topic_name)