34 Player listens to messages from the timeline and publishes them to ROS.
40 from python_qt_binding.QtCore
import QObject
42 CLOCK_TOPIC =
"/clock"
48 This object handles publishing messages as the playhead passes over their position
72 self.
timeline.add_listener(topic, self)
77 self.
timeline.remove_listener(topic, self)
104 self.
_publishers[topic] = rospy.Publisher(topic, type(msg), queue_size=100)
106 self.
_publishers[topic] = rospy.Publisher(topic, type(msg))
108 except Exception
as ex:
110 rospy.logerr(
'Error creating publisher on topic %s for type %s. \nError text: %s' %
111 (topic, str(type(msg)), str(ex)))
112 if topic != CLOCK_TOPIC:
118 When a message is viewed publish it
119 :param bag: the bag the message is in, ''rosbag.bag''
120 :param msg_data: tuple of the message data and topic info, ''(str, msg)''
126 topic, msg, clock = msg_data
133 time_msg = rosgraph_msgs.msg.Clock()
134 time_msg.clock = clock
146 This function will be called to process events posted by post_event
147 it will call message_cleared or message_viewed with the relevant data
149 bag, msg_data = event.data
151 self.message_viewed(bag, msg_data)
153 self.message_cleared()