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 Player listens to messages from the timeline and publishes them to ROS.
00035 """
00036
00037 import rospy
00038 import rosgraph_msgs
00039
00040 from python_qt_binding.QtCore import QObject
00041
00042 CLOCK_TOPIC = "/clock"
00043
00044 class Player(QObject):
00045 """
00046 This object handles publishing messages as the playhead passes over their position
00047 """
00048 def __init__(self, timeline):
00049 super(Player, self).__init__()
00050 self.timeline = timeline
00051
00052 self._publishing = set()
00053 self._publishers = {}
00054
00055 self._publish_clock = False
00056
00057 def is_publishing(self, topic):
00058 return topic in self._publishing
00059
00060 def start_publishing(self, topic):
00061 if topic in self._publishing:
00062 return
00063 self._publishing.add(topic)
00064 self.timeline.add_listener(topic, self)
00065
00066 def stop_publishing(self, topic):
00067 if topic not in self._publishing:
00068 return
00069 self.timeline.remove_listener(topic, self)
00070
00071 if topic in self._publishers:
00072 self._publishers[topic].unregister()
00073 del self._publishers[topic]
00074
00075 self._publishing.remove(topic)
00076
00077 def start_clock_publishing(self):
00078 if CLOCK_TOPIC not in self._publishers:
00079
00080 self._publish_clock = self.create_publisher(CLOCK_TOPIC, rosgraph_msgs.msg.Clock())
00081
00082 def stop_clock_publishing(self):
00083 self._publish_clock = False
00084 if CLOCK_TOPIC in self._publishers:
00085 self._publishers[CLOCK_TOPIC].unregister()
00086 del self._publishers[CLOCK_TOPIC]
00087
00088 def stop(self):
00089 for topic in list(self._publishing):
00090 self.stop_publishing(topic)
00091 self.stop_clock_publishing()
00092
00093 def create_publisher(self, topic, msg):
00094 try:
00095 try:
00096 self._publishers[topic] = rospy.Publisher(topic, type(msg), queue_size=100)
00097 except TypeError:
00098 self._publishers[topic] = rospy.Publisher(topic, type(msg))
00099 return True
00100 except Exception as ex:
00101
00102 rospy.logerr('Error creating publisher on topic %s for type %s. \nError text: %s' % (topic, str(type(msg)), str(ex)))
00103 if topic != CLOCK_TOPIC:
00104 self.stop_publishing(topic)
00105 return False
00106
00107 def message_viewed(self, bag, msg_data):
00108 """
00109 When a message is viewed publish it
00110 :param bag: the bag the message is in, ''rosbag.bag''
00111 :param msg_data: tuple of the message data and topic info, ''(str, msg)''
00112 """
00113
00114 if self.timeline.play_speed <= 0.0:
00115 return
00116
00117 topic, msg, clock = msg_data
00118
00119
00120 if topic not in self._publishers:
00121 self.create_publisher(topic, msg)
00122
00123 if self._publish_clock:
00124 time_msg = rosgraph_msgs.msg.Clock()
00125 time_msg.clock = clock
00126 self._publishers[CLOCK_TOPIC].publish(time_msg)
00127
00128 self._publishers[topic].publish(msg)
00129
00130 def message_cleared(self):
00131 pass
00132
00133 def event(self, event):
00134 """
00135 This function will be called to process events posted by post_event
00136 it will call message_cleared or message_viewed with the relevant data
00137 """
00138 bag, msg_data = event.data
00139 if msg_data:
00140 self.message_viewed(bag, msg_data)
00141 else:
00142 self.message_cleared()
00143 return True