Gripper Keyboard - Code Walkthrough

From sdk-wiki
Revision as of 11:21, 29 April 2015 by Sannoso (talk | contribs)
(diff) ← Older revision | Latest revision (diff) | Newer revision → (diff)
Jump to: navigation, search

Introduction

This example demonstrates the usage of the gripper control via baxter interface. The main() function enables the robot and invokes the map_keyboard() function. It is at this function where the keyboard keys are mapped to individual gripper actions and the commands are executed periodically.
Interfaces -

  • Gripper.reboot()
  • Gripper.calibrate()
  • Gripper.close()
  • Gripper.open()
  • Gripper.set_velocity(<double>)
  • Gripper.stop()
  • Gripper.position()
  • Gripper.command_position(<double>,<double>)
  • Gripper.parameters()
  • Gripper.set_holding_force(<double>, <double>)
  • Gripper.set_moving_force(<double>, <double>)
  • Gripper.set_velocity(<double>, <double>)
  • Gripper.set_dead_band(<double>, <double>)

Code Walkthrough

Now, let's break down the code.

33 import argparse
34 
35 import rospy
36 
37 import baxter_interface
38 import baxter_external_devices
39 
40 from baxter_interface import CHECK_VERSION

This imports the baxter interface for accessing the limb and the gripper class. The baxter_external_devices is imported to use its getch function that captures the key presses on the keyboard. 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.

43 def map_keyboard():
44     # initialize interfaces
45     print("Getting robot state... ")
46     rs = baxter_interface.RobotEnable(CHECK_VERSION)
47     init_state = rs.state().enabled
48     left = baxter_interface.Gripper('left', CHECK_VERSION)
49     right = baxter_interface.Gripper('right', CHECK_VERSION)

The init_state variable captures the current state of the robot. Two instances of the Gripper class are created for either of Baxter's limbs.

51     def clean_shutdown():
52         if not init_state:
53             print("Disabling robot...")
54             rs.disable()
55         print("Exiting example.")
56     rospy.on_shutdown(clean_shutdown)

On shutdown request, Baxter's state is sent back to its initial state.

58     def capability_warning(gripper, cmd):
59         msg = ("%s %s - not capable of '%s' command" %
60                (gripper.name, gripper.type(), cmd))
61         rospy.logwarn(msg)

This function is invoked when a gripper control command is called with custom grippers. It displays a warning message.

63     def offset_position(gripper, offset):
64         if gripper.type() != 'electric':
65             capability_warning(gripper, 'command_position')
66             return
67         current = gripper.position()
68         gripper.command_position(current + offset)

The gripper type is checked for an electric gripper. command_position() sets the gripper to the commanded position. It moves the fingers from close(0) to open(100) state based on the passed double value.

70     def offset_holding(gripper, offset):
71         if gripper.type() != 'electric':
72             capability_warning(gripper, 'set_holding_force')
73             return
74         current = gripper.parameters()['holding_force']
75         gripper.set_holding_force(current + offset)

set_holding_force() method is used to set the force of the grippers when the fingers come in contact with an object between them.

77     def offset_moving(gripper, offset):
78         if gripper.type() != 'electric':
79             capability_warning(gripper, 'set_moving_force')
80             return
81         current = gripper.parameters()['moving_force']
82         gripper.set_moving_force(current + offset)

set_moving_force() method is used to set the force of the grippers immediately before the fingers come in contact with an object between them.

84     def offset_velocity(gripper, offset):
85         if gripper.type() != 'electric':
86             capability_warning(gripper, 'set_velocity')
87             return
88         current = gripper.parameters()['velocity']
89         gripper.set_velocity(current + offset)

set_velocity() method is used to set the velocity at which the grippers would open/close.

91     def offset_dead_band(gripper, offset):
92         if gripper.type() != 'electric':
93             capability_warning(gripper, 'set_dead_band')
94             return
95         current = gripper.parameters()['dead_zone']
96         gripper.set_dead_band(current + offset)

set_dead_band() method is used to set the dead zone of the grippers. Precisely, it refers to the minimum distance between the gripper fingers when they are in closed state.

 98     bindings = {
 99     #   key: (function, args, description)
100         'r': (left.reboot, [], "left: reboot"),
101         'R': (right.reboot, [], "right: reboot"),
102         'c': (left.calibrate, [], "left: calibrate"),
103         'C': (right.calibrate, [], "right: calibrate"),
104         'q': (left.close, [], "left: close"),
105         'Q': (right.close, [], "right: close"),
106         'w': (left.open, [], "left: open"),
107         'W': (right.open, [], "right: open"),
108         '[': (left.set_velocity, [100.0], "left:  set 100% velocity"),
109         '{': (right.set_velocity, [100.0], "right:  set 100% velocity"),
110         ']': (left.set_velocity, [30.0], "left:  set 30% velocity"),
111         '}': (right.set_velocity, [30.0], "right:  set 30% velocity"),
112         's': (left.stop, [], "left: stop"),
113         'S': (right.stop, [], "right: stop"),
114         'z': (offset_dead_band, [left, -1.0], "left:  decrease dead band"),
115         'Z': (offset_dead_band, [right, -1.0], "right:  decrease dead band"),
116         'x': (offset_dead_band, [left, 1.0], "left:  increase dead band"),
117         'X': (offset_dead_band, [right, 1.0], "right:  increase dead band"),
118         'f': (offset_moving, [left, -5.0], "left:  decrease moving force"),
119         'F': (offset_moving, [right, -5.0], "right:  decrease moving force"),
120         'g': (offset_moving, [left, 5.0], "left:  increase moving force"),
121         'G': (offset_moving, [right, 5.0], "right:  increase moving force"),
122         'h': (offset_holding, [left, -5.0], "left:  decrease holding force"),
123         'H': (offset_holding, [right, -5.0], "right:  decrease holding force"),
124         'j': (offset_holding, [left, 5.0], "left:  increase holding force"),
125         'J': (offset_holding, [right, 5.0], "right:  increase holding force"),
126         'v': (offset_velocity, [left, -5.0], "left:  decrease velocity"),
127         'V': (offset_velocity, [right, -5.0], "right:  decrease velocity"),
128         'b': (offset_velocity, [left, 5.0], "left:  increase velocity"),
129         'B': (offset_velocity, [right, 5.0], "right:  increase velocity"),
130         'u': (offset_position, [left, -15.0], "left:  decrease position"),
131         'U': (offset_position, [right, -15.0], "right:  decrease position"),
132         'i': (offset_position, [left, 15.0], "left:  increase position"),
133         'I': (offset_position, [right, 15.0], "right:  increase position"),
134     }

The bindings is a dictionary that holds the set of characters in the keyboard and their corresponding gripperfunctions.

136     done = False
137     print("Enabling robot... ")
138     rs.enable()
139     print("Controlling grippers. Press ? for help, Esc to quit.")
140     while not done and not rospy.is_shutdown():
141         c = baxter_external_devices.getch()
142         if c:
143             if c in ['\x1b', '\x03']:
144                 done = True

The done variable is used to capture if "esc" or "ctrl-c" was hit. The while loop iterates till the "esc" or "ctrl-c" is inputted or ros-shutdown signal is given. c captures the keyboard input. If "esc" or "ctrl-c" is given then done gets updated as true, and shutdown signal is sent.

145             elif c in bindings:
146                 cmd = bindings[c]
147                 cmd[0](*cmd[1])
148                 print("command: %s" % (cmd[2],))

The user inputted key is checked whether it is in the bindings dictionary. bindings[c] returns the value of the key c from the dictionary. The 0th index of the value refers to the function to be called and the next index holds the arguments to be sent along with that function. cmd[2] is the description of the joint command from the dictionary above.

149             else:
150                 print("key bindings: ")
151                 print("  Esc: Quit")
152                 print("  ?: Help")
153                 for key, val in sorted(bindings.items(),
154                                        key=lambda x: x[1][2]):
155                     print("  %s: %s" % (key, val[2]))
156     # force shutdown call if caught by key handler
157     rospy.signal_shutdown("Example finished.")

This case is executed when the key pressed is not valid. So, the key is sorted and printed along with its corresponding description.

160 def main():
161     """RSDK Gripper Example: Keyboard Control
162 
163     Use your dev machine's keyboard to control and configure
164     Baxter's grippers.
165 
166     Run this example to command various gripper movements while
167     adjusting gripper parameters, including calibration, velocity,
168     and force. Uses the baxter_interface.Gripper class and the
169     helper function, baxter_external_devices.getch.
170     """
171     epilog = """
172 See help inside the example with the '?' key for key bindings.
173     """
174     arg_fmt = argparse.RawDescriptionHelpFormatter
175     parser = argparse.ArgumentParser(formatter_class=arg_fmt,
176                                      description=main.__doc__,
177                                      epilog=epilog)
178     parser.parse_args(rospy.myargv()[1:])
179 
180     print("Initializing node... ")
181     rospy.init_node("rsdk_gripper_keyboard")

The node is initialized.

183     map_keyboard()
184 
185 
186 if __name__ == '__main__':
187     main()

It is important to note that Baxter should be enabled before trying to move its joints. map_keyboard() function captures the key input and moves the joint as explained above.