Go to the documentation of this file.00001
00002 import roslib; roslib.load_manifest('cob_voltage_control')
00003 import rospy
00004 import time
00005 import csv
00006 from std_msgs.msg import Float64
00007 from cob_phidgets.msg import *
00008
00009
00010
00011
00012 def callback(data):
00013
00014 writer.writerow( ( round((rospy.Time.now() - starttime).to_sec(),5), data.value[0]) )
00015
00016
00017
00018
00019 def record():
00020 rospy.init_node('record_current')
00021 global starttime
00022 starttime = rospy.Time.now()
00023
00024 global f
00025 global writer
00026 filename = rospy.get_param("/record_current/filename")
00027 f = open(filename, 'wt', 1)
00028 writer = csv.writer(f)
00029
00030 rospy.Subscriber("/analog_sensors", AnalogSensor, callback)
00031
00032
00033 while not rospy.is_shutdown():
00034 rospy.sleep(1.0)
00035
00036 if __name__ == '__main__':
00037 record()
00038