record_voltage.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 pr2_msgs.msg import PowerState
00008 
00009 #starttime = 1
00010 
00011 def callback(data):
00012         writer.writerow( ( round((rospy.Time.now() - starttime).to_sec(),5), data.data) )
00013 
00014 #def timer_callback(data):
00015 #       rospy.loginfo(data.data)
00016 
00017 def record():
00018         rospy.init_node('record_voltage')
00019         global starttime
00020         starttime = rospy.Time.now()
00021 
00022         global f
00023         global writer
00024         filename = rospy.get_param("/record_voltage/filename")
00025         f = open(filename, 'wt', 1)
00026         writer = csv.writer(f)
00027 
00028         rospy.Subscriber("/power_board/voltage", Float64, callback)
00029         
00030 
00031         while not rospy.is_shutdown():
00032                 #pub_em_stop.publish(msg_em)
00033                 #pub_power.publish(msg_power) comes already out of gazebo
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