34 Helper functions for bag files and timestamps. 44 Convert a rospy.Time to a human-readable string. 46 @param t: time to convert 50 if t < rospy.Time.from_sec(60 * 60 * 24 * 365 * 5):
52 return '%.3fs' % t_sec
54 return time.strftime(
'%b %d %Y %H:%M:%S', time.localtime(t_sec)) +
'.%03d' % (t.nsecs / 1000000)
59 Get an alphabetical list of all the unique topics in the bag. 61 @return: sorted list of topics 64 return sorted(set([c.topic
for c
in bag._get_connections()]))
69 Get the earliest timestamp in the bag. 73 @return: earliest timestamp 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
85 Get the latest timestamp in the bag. 89 @return: latest timestamp 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
102 Get all the message types in the bag and their associated topics. 105 @type bag: rosbag.Bag 106 @return: mapping from message typename to list of topics 107 @rtype: dict of str to list of str 109 topics_by_datatype = {}
110 for c
in bag._get_connections():
111 topics_by_datatype.setdefault(c.datatype, []).append(c.topic)
113 return topics_by_datatype
118 Get the datatype of the given topic. 121 @type bag: rosbag.Bag 122 @return: message typename 125 for c
in bag._get_connections(topic):
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)
137 return '%s %s' % (s, size_name[i])
def filesize_to_str(size)
def get_datatype(bag, topic)
def get_topics_by_datatype(bag)