record_current.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
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 #from pr2_msgs.msg import PowerState
00009 
00010 #starttime = 1
00011 
00012 def callback(data):
00013         #print data.value[0] # current sensor is on the first port of the phidgets board 
00014         writer.writerow( ( round((rospy.Time.now() - starttime).to_sec(),5), data.value[0]) )
00015 
00016 #def timer_callback(data):
00017 #       rospy.loginfo(data.data)
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 


cob_voltage_control
Author(s): Alexander Bubeck
autogenerated on Thu Aug 27 2015 12:45:45