topics_to_ssv.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Modification over an existing script from Ryohei Ueda so it can 
00004 # extract the info on topics without a header.
00005 #
00006 # Now, it only works with one topic at time. Need debug.
00007 
00008 import roslib
00009 roslib.load_manifest("sensor_msgs")
00010 roslib.load_manifest("message_filters")
00011 roslib.load_manifest("rxtools")
00012 import rospy
00013 import rxtools
00014 import rxtools.rosplot
00015 import sys
00016 import message_filters
00017 from optparse import OptionParser, OptionValueError
00018 import datetime
00019 
00020 topic_desc = []
00021 fd = False
00022 class Error(Exception):
00023     pass
00024 class InvalidTopic(Error):
00025     pass
00026 class NoFieldName(Error):
00027     pass
00028 class NotSupportedFeature(Error):
00029     pass
00030 
00031 def usage():
00032     print """usage:
00033 bag_to_ssv OUTPUT_FILE TOPIC1 [TOPIC2 TOPIC3 ...]"""
00034     return 1
00035 
00036 def time_axeq(self, other):
00037     if not isinstance(other, roslib.rostime.Time):
00038         return False
00039     secs = abs(self.to_sec() - other.to_sec())
00040     # within 10msec
00041     if secs < tolerance:
00042         return True
00043     else:
00044         return False
00045     #return self.secs == other.secs and self.nsecs == other.nsecs
00046 
00047 def time_cmp(self, other):
00048     if not isinstance(other, roslib.rostime.Time):
00049         raise TypeError("cannot compare to non-Time")
00050     secs = self.to_sec() - other.to_sec()
00051     if abs(secs) < tolerance:
00052         return 0
00053     if secs > 0:
00054         return 1
00055     return -1
00056 
00057 def time_hash(self):
00058     return ("%s.%s"%(self.secs, self.nsecs / int(tolerance * 1e9))) .__hash__()
00059 
00060 
00061 def callback(*values):
00062     for (v, evals) in zip(values, topic_desc):
00063         for f in evals[1]:
00064             v = f(v)            # update v recursively...
00065         fd.write(str(v) + deliminator)
00066     fd.write("\n")
00067     fd.flush()
00068 
00069 def main(args):
00070     global fd
00071     output_file = args[1]
00072     fd = open(output_file, "w")
00073     topics = args[2:]
00074     subscribers = []
00075     # setup subscribers and topic_desc and print the first line
00076     for topic in topics:
00077         (topic_type, real_topic, rest) = rxtools.rosplot.get_topic_type(topic)
00078         if rest == '':
00079             raise NoFieldName("you need to specify filed")
00080 
00081         e = rxtools.rosplot.generate_field_evals(rest)
00082         #if len(e) > 1:
00083         #    raise NotSupportedFeature("sorry, currently we does not support : separate representation")
00084         topic_desc.append([real_topic, e])
00085         data_class = roslib.message.get_message_class(topic_type)
00086         sub = message_filters.Subscriber(real_topic, data_class)
00087         sub.registerCallback(callback)
00088         subscribers.append(sub)
00089         print "subscribing to %s" % (real_topic)
00090         # print line
00091         fd.write(topic + deliminator)
00092     fd.write("\n")
00093     #ts = message_filters.TimeSynchronizer(subscribers, 100)
00094     
00095     #ts.registerCallback(callback)
00096     try:
00097         rospy.spin()
00098     finally:
00099         fd.close()
00100 
00101 def parse_options(args):
00102     if len(sys.argv)<3:
00103         print "Not enough parameters."
00104         usage()
00105         sys.exit(-1)
00106     parser = OptionParser(usage="topics_to_ssv [options] OUTPUT_FILE_NAME TOPICNAME1 TOPICNAME2 ...")
00107     parser.add_option("-d", "--deliminator", dest = "deliminator",
00108                       default = ";",
00109                       help = "specify deliminator character (or string). the default value is ;",
00110                       action = "store")
00111     parser.add_option("-t", "--tolerance", dest = "tolerance",
00112                       default = "0.04",
00113                       help = """specify timestamp tolerance in sec. the default value is 0.04""",
00114                       action = "store")
00115     (options, args) = parser.parse_args(args)
00116     # setup global variables
00117     global tolerance
00118     global deliminator
00119     deliminator = options.deliminator
00120     tolerance = float(options.tolerance)
00121     return args
00122 
00123 if __name__ == "__main__":
00124     rospy.init_node("topics_to_ssv%s"%str(datetime.datetime.now().second))
00125     #rospy.init_node("topics_to_ssv)
00126     args = parse_options(sys.argv)
00127     setattr(roslib.rostime.Time, "__eq__", time_axeq)
00128     setattr(roslib.rostime.Time, "__cmp__", time_cmp)
00129     setattr(roslib.rostime.Time, "__hash__", time_hash)
00130     main(args)


estirabot_apps
Author(s): Jose Luis Rivero
autogenerated on Fri Dec 6 2013 23:20:59