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