bag_helper.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICTS
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 """
34 Helper functions for bag files and timestamps.
35 """
36 
37 import math
38 import time
39 import rospy
40 
41 
42 def stamp_to_str(t):
43  """
44  Convert a rospy.Time to a human-readable string.
45 
46  @param t: time to convert
47  @type t: rospy.Time
48  """
49  t_sec = t.to_sec()
50  if t < rospy.Time.from_sec(60 * 60 * 24 * 365 * 5):
51  # Display timestamps earlier than 1975 as seconds
52  return '%.3fs' % t_sec
53  else:
54  return time.strftime('%b %d %Y %H:%M:%S', time.localtime(t_sec)) + '.%03d' % (t.nsecs / 1000000)
55 
56 
57 def get_topics(bag):
58  """
59  Get an alphabetical list of all the unique topics in the bag.
60 
61  @return: sorted list of topics
62  @rtype: list of str
63  """
64  return sorted(set([c.topic for c in bag._get_connections()]))
65 
66 
67 def get_start_stamp(bag):
68  """
69  Get the earliest timestamp in the bag.
70 
71  @param bag: bag file
72  @type bag: rosbag.Bag
73  @return: earliest timestamp
74  @rtype: rospy.Time
75  """
76  start_stamp = None
77  for connection_start_stamp in [index[0].time for index in bag._connection_indexes.values()]:
78  if not start_stamp or connection_start_stamp < start_stamp:
79  start_stamp = connection_start_stamp
80  return start_stamp
81 
82 
83 def get_end_stamp(bag):
84  """
85  Get the latest timestamp in the bag.
86 
87  @param bag: bag file
88  @type bag: rosbag.Bag
89  @return: latest timestamp
90  @rtype: rospy.Time
91  """
92  end_stamp = None
93  for connection_end_stamp in [index[-1].time for index in bag._connection_indexes.values()]:
94  if not end_stamp or connection_end_stamp > end_stamp:
95  end_stamp = connection_end_stamp
96 
97  return end_stamp
98 
99 
101  """
102  Get all the message types in the bag and their associated topics.
103 
104  @param bag: bag file
105  @type bag: rosbag.Bag
106  @return: mapping from message typename to list of topics
107  @rtype: dict of str to list of str
108  """
109  topics_by_datatype = {}
110  for c in bag._get_connections():
111  topics_by_datatype.setdefault(c.datatype, []).append(c.topic)
112 
113  return topics_by_datatype
114 
115 
116 def get_datatype(bag, topic):
117  """
118  Get the datatype of the given topic.
119 
120  @param bag: bag file
121  @type bag: rosbag.Bag
122  @return: message typename
123  @rtype: str
124  """
125  for c in bag._get_connections(topic):
126  return c.datatype
127 
128  return None
129 
130 
131 def filesize_to_str(size):
132  size_name = ('B', 'KB', 'MB', 'GB', 'TB', 'PB', 'EB', 'ZB', 'YB')
133  i = int(math.floor(math.log(size, 1024)))
134  p = math.pow(1024, i)
135  s = round(size / p, 2)
136  if s > 0:
137  return '%s %s' % (s, size_name[i])
138  return '0 B'
def filesize_to_str(size)
Definition: bag_helper.py:131
def get_end_stamp(bag)
Definition: bag_helper.py:83
def get_start_stamp(bag)
Definition: bag_helper.py:67
def get_topics(bag)
Definition: bag_helper.py:57
def get_datatype(bag, topic)
Definition: bag_helper.py:116
def get_topics_by_datatype(bag)
Definition: bag_helper.py:100


rqt_bag
Author(s): Aaron Blasdel, Tim Field
autogenerated on Fri Jun 7 2019 22:05:54