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
00029
00030 import argparse
00031
00032 import rospy
00033
00034 import baxter_interface
00035 from baxter_examples import JointRecorder
00036
00037 from baxter_interface import CHECK_VERSION
00038
00039
00040 def main():
00041 """RSDK Joint Recorder Example
00042
00043 Record timestamped joint and gripper positions to a file for
00044 later play back.
00045
00046 Run this example while moving the robot's arms and grippers
00047 to record a time series of joint and gripper positions to a
00048 new csv file with the provided *filename*. This example can
00049 be run in parallel with any other example or standalone
00050 (moving the arms in zero-g mode while pressing the cuff
00051 buttons to open/close grippers).
00052
00053 You can later play the movements back using one of the
00054 *_file_playback examples.
00055 """
00056 epilog = """
00057 Related examples:
00058 joint_position_file_playback.py; joint_trajectory_file_playback.py.
00059 """
00060 arg_fmt = argparse.RawDescriptionHelpFormatter
00061 parser = argparse.ArgumentParser(formatter_class=arg_fmt,
00062 description=main.__doc__,
00063 epilog=epilog)
00064 required = parser.add_argument_group('required arguments')
00065 required.add_argument(
00066 '-f', '--file', dest='filename', required=True,
00067 help='the file name to record to'
00068 )
00069 parser.add_argument(
00070 '-r', '--record-rate', type=int, default=100, metavar='RECORDRATE',
00071 help='rate at which to record (default: 100)'
00072 )
00073 args = parser.parse_args(rospy.myargv()[1:])
00074
00075 print("Initializing node... ")
00076 rospy.init_node("rsdk_joint_recorder")
00077 print("Getting robot state... ")
00078 rs = baxter_interface.RobotEnable(CHECK_VERSION)
00079 print("Enabling robot... ")
00080 rs.enable()
00081
00082 recorder = JointRecorder(args.filename, args.record_rate)
00083 rospy.on_shutdown(recorder.stop)
00084
00085 print("Recording. Press Ctrl-C to stop.")
00086 recorder.record()
00087
00088 print("\nDone.")
00089
00090 if __name__ == '__main__':
00091 main()