player.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2009, 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 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         # Attempt to connect to the ROS master
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         # Don't publish unless the playhead is moving.
00084         if self.timeline.play_speed <= 0.0:
00085             return
00086         
00087         topic, msg, t = msg_data
00088 
00089         # Create publisher if this is the first message on the topic
00090         if topic not in self._publishers:
00091             try:
00092                 self._publishers[topic] = rospy.Publisher(topic, type(msg))
00093             except Exception, ex:
00094                 # Any errors, stop listening/publishing to this topic
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


rxbag
Author(s): Tim Field
autogenerated on Mon Oct 6 2014 07:26:07