player.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
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         # Don't publish unless the playhead is moving.
00085         if self.timeline.play_speed <= 0.0:
00086             return
00087 
00088         topic, msg, _ = msg_data
00089 
00090         # Create publisher if this is the first message on the topic
00091         if topic not in self._publishers:
00092             try:
00093                 self._publishers[topic] = rospy.Publisher(topic, type(msg))
00094             except Exception as ex:
00095                 # Any errors, stop listening/publishing to this topic
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


rqt_bag
Author(s): Aaron Blasdel
autogenerated on Fri Jan 3 2014 11:55:06