$search
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 Defines the rxbag wx.App. 00035 """ 00036 00037 from __future__ import with_statement 00038 00039 PKG = 'rxbag' 00040 import roslib; roslib.load_manifest(PKG) 00041 import rospy 00042 00043 import sys 00044 import threading 00045 import time 00046 00047 import wx 00048 00049 import rosbag 00050 00051 from util.base_frame import BaseFrame 00052 from timeline import Timeline 00053 00054 class RxBagApp(wx.App): 00055 def __init__(self, options, args): 00056 self.options = options 00057 self.args = args 00058 00059 self.connected_to_ros = False 00060 00061 wx.App.__init__(self) 00062 00063 def OnInit(self): 00064 try: 00065 if self.options.record: 00066 # Connect to ROS master 00067 if not self.connect_to_ros(): 00068 raise Exception('recording requires connection to master') 00069 00070 # Get filename to record to 00071 record_filename = time.strftime('%Y-%m-%d-%H-%M-%S.bag', time.localtime(time.time())) 00072 if self.options.name: 00073 record_filename = self.options.name 00074 if not record_filename.endswith('.bag'): 00075 record_filename += '.bag' 00076 elif self.options.prefix: 00077 prefix = self.options.prefix 00078 if prefix.endswith('.bag'): 00079 prefix = prefix[:-len('.bag')] 00080 if prefix: 00081 record_filename = '%s_%s' % (prefix, record_filename) 00082 00083 rospy.loginfo('Recording to %s.' % record_filename) 00084 00085 # Create main timeline frame 00086 self.frame = BaseFrame(None, 'rxbag', 'Timeline') 00087 self.frame.BackgroundColour = wx.WHITE 00088 self.frame.Bind(wx.EVT_CLOSE, lambda e: wx.Exit()) 00089 00090 scroll = wx.ScrolledWindow(self.frame, -1) 00091 scroll.BackgroundColour = wx.WHITE 00092 00093 timeline = Timeline(scroll, -1) 00094 timeline.Size = (100, 100) 00095 00096 self.frame.Show() 00097 self.SetTopWindow(self.frame) 00098 00099 timeline.SetFocus() 00100 00101 if self.options.record: 00102 timeline.record_bag(record_filename, all=self.options.all, topics=self.args, regex=self.options.regex, limit=self.options.limit) 00103 else: 00104 RxBagInitThread(self, timeline) 00105 00106 except Exception, ex: 00107 print >> sys.stderr, 'Error initializing application:', ex 00108 #import traceback 00109 #traceback.print_exc() 00110 return False 00111 00112 return True 00113 00114 def connect_to_ros(self, init_timeout=3): 00115 if self.connected_to_ros: 00116 return True 00117 00118 # Attempt to connect to master node 00119 class InitNodeThread(threading.Thread): 00120 def __init__(self): 00121 threading.Thread.__init__(self) 00122 self.setDaemon(True) 00123 self.inited = False 00124 self.init_cv = threading.Condition() 00125 00126 def run(self): 00127 rospy.loginfo('Master found. Connecting...') 00128 rospy.init_node('rxbag', anonymous=True, disable_signals=True) 00129 with self.init_cv: 00130 self.inited = True 00131 self.init_cv.notify_all() 00132 00133 try: 00134 # Check whether ROS master is running 00135 master = rospy.get_master() 00136 master.getPid() 00137 00138 # If so (i.e. no exception), attempt to initialize node 00139 init_thread = InitNodeThread() 00140 with init_thread.init_cv: 00141 init_thread.start() 00142 init_thread.init_cv.wait(init_timeout) 00143 00144 if init_thread.inited: 00145 rospy.core.register_signals() 00146 rospy.loginfo('Connected to ROS master.') 00147 self.connected_to_ros = True 00148 return True 00149 else: 00150 rospy.logerr('Couldn\'t connect to ROS master.') 00151 except Exception: 00152 rospy.loginfo('ROS master not found.') 00153 00154 return False 00155 00156 class RxBagInitThread(threading.Thread): 00157 def __init__(self, app, timeline): 00158 threading.Thread.__init__(self) 00159 00160 self.app = app 00161 self.timeline = timeline 00162 00163 self.start() 00164 00165 def run(self): 00166 for input_file in self.app.args: 00167 self.timeline.loading_filename = input_file 00168 00169 try: 00170 self.timeline.add_bag(rosbag.Bag(input_file)) 00171 except Exception, ex: 00172 print >> sys.stderr, 'Error loading [%s]: %s' % (input_file, str(ex)) 00173 00174 self.timeline.loading_filename = None 00175 00176 if self.app.options.start: 00177 playhead = self.timeline.start_stamp + rospy.Duration.from_sec(self.app.options.start) 00178 if playhead > self.timeline.end_stamp: 00179 playhead = self.timeline.end_stamp 00180 elif playhead < self.timeline.start_stamp: 00181 playhead = self.timeline.start_stamp 00182 00183 self.timeline.playhead = playhead