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 roslib
00031 roslib.load_manifest('teleop_microscribe')
00032 import rospy
00033 from joy.msg import *
00034 from pr2_controllers_msgs.msg import *
00035 import actionlib.action_client
00036
00037 rospy.init_node('gripper_pedals')
00038
00039 class PedalGripper:
00040 CLOSED = 0
00041 OPENNING = 1
00042 OPEN = 2
00043 CLOSING = 3
00044 def __init__(self, pedal_topic, pedal_button, gripper_action):
00045 self.state = self.CLOSED
00046 self.gripper_client = actionlib.action_client.ActionClient(
00047 gripper_action, Pr2GripperCommandAction)
00048 self.pedal_button = pedal_button
00049
00050 rospy.Subscriber(pedal_topic, Joy, self.pedal_cb)
00051
00052 def pedal_cb(self, msg):
00053 b = msg.buttons[self.pedal_button]
00054
00055
00056 if self.state is self.CLOSED and b:
00057 self.state = self.OPENNING
00058 self.gripper_client.send_goal(Pr2GripperCommandGoal(
00059 command = Pr2GripperCommand(0.4, -1.0)))
00060 elif self.state is self.OPENNING and not b:
00061 self.state = self.OPEN
00062 self.gripper_client.send_goal(Pr2GripperCommandGoal(
00063 command = Pr2GripperCommand(0.4, 0.0)))
00064 elif self.state is self.OPEN and b:
00065 self.state = self.CLOSING
00066 self.gripper_client.send_goal(Pr2GripperCommandGoal(
00067 command = Pr2GripperCommand(0.0, -1.0,)))
00068 elif self.state is self.CLOSING and not b:
00069 self.state = self.CLOSED
00070
00071 def main():
00072 l = PedalGripper('/r_pedals/joy', 0, '/l_gripper_controller/gripper_action')
00073 r = PedalGripper('/r_pedals/joy', 2, '/r_gripper_controller/gripper_action')
00074 rospy.spin()
00075
00076
00077 if __name__ == '__main__':
00078 main()