Introduction
This example demonstrates the usage of the Joint Recorder interface to record the joint positions traversed by the robot. It records the timestamped joint and gripper positions to a file.
Interface - JointRecorder.record()
Code Walkthrough
Now, let's break down the code.
30 import argparse
31
32 import rospy
33
34 import baxter_interface
35 from baxter_examples import JointRecorder
36
37 from baxter_interface import CHECK_VERSION
This imports the baxter interface for accessing the limb and the gripper class. The baxter_interface
is imported to use its JointRecorder
class. The CHECK_VERSION
is imported to check if the software running on the robot would be compatible with this local version. It is not necessary to check the version in custom programs.
40 def main():
41 """RSDK Joint Recorder Example
42
43 Record timestamped joint and gripper positions to a file for
44 later play back.
45
46 Run this example while moving the robot's arms and grippers
47 to record a time series of joint and gripper positions to a
48 new csv file with the provided *filename*. This example can
49 be run in parallel with any other example or standalone
50 (moving the arms in zero-g mode while pressing the cuff
51 buttons to open/close grippers).
52
53 You can later play the movements back using one of the
54 *_file_playback examples.
55 """
56 epilog = """
57 Related examples:
58 joint_position_file_playback.py; joint_trajectory_file_playback.py.
59 """
60 arg_fmt = argparse.RawDescriptionHelpFormatter
61 parser = argparse.ArgumentParser(formatter_class=arg_fmt,
62 description=main.__doc__,
63 epilog=epilog)
64 required = parser.add_argument_group('required arguments')
65 required.add_argument(
66 '-f', '--file', dest='filename', required=True,
67 help='the file name to record to'
68 )
69 parser.add_argument(
70 '-r', '--record-rate', type=int, default=100, metavar='RECORDRATE',
71 help='rate at which to record (default: 100)'
72 )
73 args = parser.parse_args(rospy.myargv()[1:])
The destination file to store the joint positions along with its path is captured by the parser. The rate at which the positions are to be captured and stored is also captured.
75 print("Initializing node... ")
76 rospy.init_node("rsdk_joint_recorder")
77 print("Getting robot state... ")
78 rs = baxter_interface.RobotEnable(CHECK_VERSION)
79 print("Enabling robot... ")
80 rs.enable()
81
82 recorder = JointRecorder(args.filename, args.record_rate)
83 rospy.on_shutdown(recorder.stop)
84
85 print("Recording. Press Ctrl-C to stop.")
86 recorder.record()
87
88 print("\nDone.")
89
90 if __name__ == '__main__':
91 main()
The node is initialized and the robot is enabled. The record()
method captures the joint and gripper positions at a specified rate and stores them to the destination file.