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 wx
00038
00039 import rosbag
00040 import rospy
00041
00042 class Player(object):
00043 def __init__(self, timeline):
00044 self.timeline = timeline
00045
00046 self._publishing = set()
00047 self._publishers = {}
00048
00049
00050 if not wx.GetApp().connect_to_ros():
00051 raise Exception('Error connecting to ROS')
00052
00053 def is_publishing(self, topic):
00054 return topic in self._publishing
00055
00056 def start_publishing(self, topic):
00057 if topic in self._publishing:
00058 return
00059
00060 self._publishing.add(topic)
00061
00062 self.timeline.add_listener(topic, self)
00063
00064 def stop_publishing(self, topic):
00065 if topic not in self._publishing:
00066 return
00067
00068 self.timeline.remove_listener(topic, self)
00069
00070 if topic in self._publishers:
00071 self._publishers[topic].unregister()
00072 del self._publishers[topic]
00073
00074 self._publishing.remove(topic)
00075
00076 def stop(self):
00077 for topic in list(self._publishing):
00078 self.stop_publishing(topic)
00079
00080
00081
00082 def message_viewed(self, bag, msg_data):
00083
00084 if self.timeline.play_speed <= 0.0:
00085 return
00086
00087 topic, msg, t = msg_data
00088
00089
00090 if topic not in self._publishers:
00091 try:
00092 self._publishers[topic] = rospy.Publisher(topic, type(msg))
00093 except Exception, ex:
00094
00095 rospy.logerr('Error creating publisher on topic %s for type %s' % (topic, str(type(msg))))
00096 self.stop_publishing(topic)
00097
00098 self._publishers[topic].publish(msg)
00099
00100 def message_cleared(self):
00101 pass