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
00039
00040 from python_qt_binding.QtCore import QObject
00041
00042
00043 class Player(QObject):
00044 """
00045 This object handles publishing messages as the playhead passes over their position
00046 """
00047 def __init__(self, timeline):
00048 super(Player, self).__init__()
00049 self.timeline = timeline
00050
00051 self._publishing = set()
00052 self._publishers = {}
00053
00054 def is_publishing(self, topic):
00055 return topic in self._publishing
00056
00057 def start_publishing(self, topic):
00058 if topic in self._publishing:
00059 return
00060 self._publishing.add(topic)
00061 self.timeline.add_listener(topic, self)
00062
00063 def stop_publishing(self, topic):
00064 if topic not in self._publishing:
00065 return
00066 self.timeline.remove_listener(topic, self)
00067
00068 if topic in self._publishers:
00069 self._publishers[topic].unregister()
00070 del self._publishers[topic]
00071
00072 self._publishing.remove(topic)
00073
00074 def stop(self):
00075 for topic in list(self._publishing):
00076 self.stop_publishing(topic)
00077
00078 def message_viewed(self, bag, msg_data):
00079 """
00080 When a message is viewed publish it
00081 :param bag: the bag the message is in, ''rosbag.bag''
00082 :param msg_data: tuple of the message data and topic info, ''(str, msg)''
00083 """
00084
00085 if self.timeline.play_speed <= 0.0:
00086 return
00087
00088 topic, msg, _ = msg_data
00089
00090
00091 if topic not in self._publishers:
00092 try:
00093 self._publishers[topic] = rospy.Publisher(topic, type(msg))
00094 except Exception as ex:
00095
00096 rospy.logerr('Error creating publisher on topic %s for type %s. \nError text: %s' % (topic, str(type(msg)), str(ex)))
00097 self.stop_publishing(topic)
00098
00099 self._publishers[topic].publish(msg)
00100
00101 def message_cleared(self):
00102 pass
00103
00104 def event(self, event):
00105 """
00106 This function will be called to process events posted by post_event
00107 it will call message_cleared or message_viewed with the relevant data
00108 """
00109 bag, msg_data = event.data
00110 if msg_data:
00111 self.message_viewed(bag, msg_data)
00112 else:
00113 self.message_cleared()
00114 return True