bag_helper.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, STRICTS
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 Helper functions for bag files and timestamps.
00035 """
00036 
00037 import math
00038 import time
00039 import rospy
00040 
00041 def stamp_to_str(t):
00042     """
00043     Convert a rospy.Time to a human-readable string.
00044 
00045     @param t: time to convert
00046     @type  t: rospy.Time
00047     """
00048     t_sec = t.to_sec()
00049     if t < rospy.Time.from_sec(60 * 60 * 24 * 365 * 5):
00050         # Display timestamps earlier than 1975 as seconds
00051         return '%.3fs' % t_sec
00052     else:
00053         return time.strftime('%b %d %Y %H:%M:%S', time.localtime(t_sec)) + '.%03d' % (t.nsecs / 1000000)
00054 
00055 
00056 def get_topics(bag):
00057     """
00058     Get an alphabetical list of all the unique topics in the bag.
00059 
00060     @return: sorted list of topics
00061     @rtype:  list of str
00062     """
00063     return sorted(set([c.topic for c in bag._get_connections()]))
00064 
00065 
00066 def get_start_stamp(bag):
00067     """
00068     Get the earliest timestamp in the bag.
00069 
00070     @param bag: bag file
00071     @type  bag: rosbag.Bag
00072     @return: earliest timestamp
00073     @rtype:  rospy.Time
00074     """
00075     start_stamp = None
00076     for connection_start_stamp in [index[0].time for index in bag._connection_indexes.values()]:
00077         if not start_stamp or connection_start_stamp < start_stamp:
00078             start_stamp = connection_start_stamp
00079     return start_stamp
00080 
00081 
00082 def get_end_stamp(bag):
00083     """
00084     Get the latest timestamp in the bag.
00085 
00086     @param bag: bag file
00087     @type  bag: rosbag.Bag
00088     @return: latest timestamp
00089     @rtype:  rospy.Time
00090     """
00091     end_stamp = None
00092     for connection_end_stamp in [index[-1].time for index in bag._connection_indexes.values()]:
00093         if not end_stamp or connection_end_stamp > end_stamp:
00094             end_stamp = connection_end_stamp
00095 
00096     return end_stamp
00097 
00098 
00099 def get_topics_by_datatype(bag):
00100     """
00101     Get all the message types in the bag and their associated topics.
00102 
00103     @param bag: bag file
00104     @type  bag: rosbag.Bag
00105     @return: mapping from message typename to list of topics
00106     @rtype:  dict of str to list of str
00107     """
00108     topics_by_datatype = {}
00109     for c in bag._get_connections():
00110         topics_by_datatype.setdefault(c.datatype, []).append(c.topic)
00111 
00112     return topics_by_datatype
00113 
00114 
00115 def get_datatype(bag, topic):
00116     """
00117     Get the datatype of the given topic.
00118 
00119     @param bag: bag file
00120     @type  bag: rosbag.Bag
00121     @return: message typename
00122     @rtype:  str
00123     """
00124     for c in bag._get_connections(topic):
00125         return c.datatype
00126 
00127     return None
00128 
00129 
00130 def filesize_to_str(size):
00131     size_name = ('B', 'KB', 'MB', 'GB', 'TB', 'PB', 'EB', 'ZB', 'YB')
00132     i = int(math.floor(math.log(size, 1024)))
00133     p = math.pow(1024, i)
00134     s = round(size / p, 2)
00135     if s > 0:
00136         return '%s %s' % (s, size_name[i])
00137     return '0 B'


rqt_bag
Author(s): Aaron Blasdel, Tim Field
autogenerated on Thu Aug 17 2017 02:19:26