diff --git a/bag_tools/scripts/bag_add_time_offset.py b/bag_tools/scripts/bag_add_time_offset.py index 0274998..7ecaf66 100755 --- a/bag_tools/scripts/bag_add_time_offset.py +++ b/bag_tools/scripts/bag_add_time_offset.py @@ -62,7 +62,7 @@ def fix_bagfile(inbag, outbag, topics, offset): rospy.loginfo('Closing output bagfile.') outbag.close() rospy.loginfo('Changed the following:') - for k, v in count.iteritems(): + for k, v in count.items(): rospy.loginfo( '%s:%s messages.',k,v) if __name__ == "__main__": @@ -70,13 +70,13 @@ def fix_bagfile(inbag, outbag, topics, offset): parser = argparse.ArgumentParser( description='Shift the publishing time of given topics in input bagfile.') parser.add_argument('-o', metavar='OUTPUT_BAGFILE', required=True, help='output bagfile') - parser.add_argument('-i', metavar='INPUT_BAGFILE', required=True, help='input bagfile(s)', nargs='+') + parser.add_argument('-i', metavar='INPUT_BAGFILE', required=True, help='input bagfile(s)') parser.add_argument('-of', metavar='OFFSET', required=True, type=float, help='time offset to add in seconds') parser.add_argument('-t', metavar='TOPIC', required=True, help='topic(s) to change', nargs='+') args = parser.parse_args() try: for bagfile in args.i: fix_bagfile(bagfile, args.o, args.t, args.of) - except Exception, e: - import traceback - traceback.print_exc() + except Exception as e: + import traceback + traceback.print_exc() diff --git a/bag_tools/scripts/check_delay.py b/bag_tools/scripts/check_delay.py index 93704c3..8093efc 100755 --- a/bag_tools/scripts/check_delay.py +++ b/bag_tools/scripts/check_delay.py @@ -38,6 +38,7 @@ import os import sys import argparse +import statistics def check_delay(inbags): delays = {} @@ -59,12 +60,12 @@ def check_delay(inbags): delays[key].append(delay) max_len = max(len(topic) for topic in delays.keys()) topics = delays.keys() - topics.sort() + list(topics).sort() for topic in topics: delay_list = delays[topic] delay_list.sort() dmin, dmax, dmean = min(delay_list), max(delay_list), sum(delay_list)/len(delay_list) - dmedian = delay_list[len(delay_list)/2] + dmedian = statistics.median(delay_list) rospy.loginfo('%s : mean = %s, min = %s, max = %s, median = %s', topic.ljust(max_len + 2), dmean, dmin, dmax, dmedian) if __name__ == "__main__": @@ -77,6 +78,6 @@ def check_delay(inbags): args = parser.parse_args() try: check_delay(args.inbag) - except Exception, e: + except Exception as e: import traceback traceback.print_exc()