Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 import rospy
00029
00030 import baxter_interface
00031
00032 from baxter_interface import CHECK_VERSION
00033
00034
00035 class JointRecorder(object):
00036 def __init__(self, filename, rate):
00037 """
00038 Records joint data to a file at a specified rate.
00039 """
00040 self._filename = filename
00041 self._raw_rate = rate
00042 self._rate = rospy.Rate(rate)
00043 self._start_time = rospy.get_time()
00044 self._done = False
00045
00046 self._limb_left = baxter_interface.Limb("left")
00047 self._limb_right = baxter_interface.Limb("right")
00048 self._gripper_left = baxter_interface.Gripper("left", CHECK_VERSION)
00049 self._gripper_right = baxter_interface.Gripper("right", CHECK_VERSION)
00050 self._io_left_lower = baxter_interface.DigitalIO('left_lower_button')
00051 self._io_left_upper = baxter_interface.DigitalIO('left_upper_button')
00052 self._io_right_lower = baxter_interface.DigitalIO('right_lower_button')
00053 self._io_right_upper = baxter_interface.DigitalIO('right_upper_button')
00054
00055
00056 if self._gripper_left.error():
00057 self._gripper_left.reset()
00058 if self._gripper_right.error():
00059 self._gripper_right.reset()
00060 if (not self._gripper_left.calibrated() and
00061 self._gripper_left.type() != 'custom'):
00062 self._gripper_left.calibrate()
00063 if (not self._gripper_right.calibrated() and
00064 self._gripper_right.type() != 'custom'):
00065 self._gripper_right.calibrate()
00066
00067 def _time_stamp(self):
00068 return rospy.get_time() - self._start_time
00069
00070 def stop(self):
00071 """
00072 Stop recording.
00073 """
00074 self._done = True
00075
00076 def done(self):
00077 """
00078 Return whether or not recording is done.
00079 """
00080 if rospy.is_shutdown():
00081 self.stop()
00082 return self._done
00083
00084 def record(self):
00085 """
00086 Records the current joint positions to a csv file if outputFilename was
00087 provided at construction this function will record the latest set of
00088 joint angles in a csv format.
00089
00090 This function does not test to see if a file exists and will overwrite
00091 existing files.
00092 """
00093 if self._filename:
00094 joints_left = self._limb_left.joint_names()
00095 joints_right = self._limb_right.joint_names()
00096 with open(self._filename, 'w') as f:
00097 f.write('time,')
00098 f.write(','.join([j for j in joints_left]) + ',')
00099 f.write('left_gripper,')
00100 f.write(','.join([j for j in joints_right]) + ',')
00101 f.write('right_gripper\n')
00102
00103 while not self.done():
00104
00105 if self._io_left_lower.state:
00106 self._gripper_left.open()
00107 elif self._io_left_upper.state:
00108 self._gripper_left.close()
00109 if self._io_right_lower.state:
00110 self._gripper_right.open()
00111 elif self._io_right_upper.state:
00112 self._gripper_right.close()
00113 angles_left = [self._limb_left.joint_angle(j)
00114 for j in joints_left]
00115 angles_right = [self._limb_right.joint_angle(j)
00116 for j in joints_right]
00117
00118 f.write("%f," % (self._time_stamp(),))
00119
00120 f.write(','.join([str(x) for x in angles_left]) + ',')
00121 f.write(str(self._gripper_left.position()) + ',')
00122
00123 f.write(','.join([str(x) for x in angles_right]) + ',')
00124 f.write(str(self._gripper_right.position()) + '\n')
00125
00126 self._rate.sleep()