rxbag_main.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2009, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of Willow Garage, Inc. nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 
00034 """
00035 The main entry-point to rxbag.
00036 """
00037 
00038 import roslib.message
00039 import rospy
00040 
00041 import optparse
00042 import sys
00043 import threading
00044 import time
00045 
00046 # Ensure wxPython version >= 2.8, and install hotfix for 64-bit Cairo support for wxGTK
00047 import wxversion
00048 WXVER = '2.8'
00049 if wxversion.checkInstalled(WXVER):
00050     wxversion.select(WXVER)
00051 else:
00052     print >> sys.stderr, 'This application requires wxPython version %s' % WXVER
00053     sys.exit(1)
00054 import wx
00055 import wx.lib.wxcairo
00056 if 'wxGTK' in wx.PlatformInfo:
00057     # Workaround for 64-bit systems
00058     import ctypes
00059     gdkLib = wx.lib.wxcairo._findGDKLib()
00060     gdkLib.gdk_cairo_create.restype = ctypes.c_void_p
00061 
00062 import rxbag_app
00063 
00064 def run(options, args):
00065     app = rxbag_app.RxBagApp(options, args)
00066     app.MainLoop()
00067     rospy.signal_shutdown('GUI shutdown')
00068 
00069 def rxbag_main():
00070     # Parse command line for input files and options
00071     parser = optparse.OptionParser(usage='usage: %prog [options] BAG_FILE1 [BAG_FILE2 ...]')
00072     parser.add_option('-s', '--start',         dest='start',   default=0.0,   action='store', type='float', help='start SEC seconds into the bag files', metavar='SEC')
00073     parser.add_option(      '--record',        dest='record',  default=False, action='store_true',          help='record to a bag file')
00074     parser.add_option('-a', '--all',           dest='all',     default=False, action='store_true',          help='record all topics')
00075     parser.add_option('-e', '--regex',         dest='regex',   default=False, action="store_true",          help='match topics using regular expressions')
00076     parser.add_option('-o', '--output-prefix', dest='prefix',  default=None,  action="store",               help='prepend PREFIX to beginning of bag name (name will always end with date stamp)')
00077     parser.add_option('-O', '--output-name',   dest='name',    default=None,  action="store",               help='record to bag with name NAME.bag')
00078     parser.add_option('-l', '--limit',         dest='limit',   default=0,     action="store", type='int',   help='only record NUM messages on each topic', metavar='NUM')
00079     parser.add_option(      '--profile',       dest='profile', default=False, action='store_true',          help='profile and write results to rxbag.prof [advanced]')
00080 
00081     options, args = parser.parse_args(sys.argv[1:])
00082 
00083     if len(args) == 0:
00084         if options.record:
00085             if not options.all:
00086                 parser.error('You must specify topics to record when recording (or specify --all).')
00087         else:
00088             parser.error('You must specify at least one bag file to view.')
00089             
00090     if options.prefix and options.name:
00091         parser.error('Can\'t set both prefix and name.')
00092 
00093     if options.profile:
00094         import cProfile
00095         cProfile.runctx('run(options, args)', globals(), locals(), 'rxbag.prof')
00096     else:
00097         run(options, args)


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