$search
00001 #!/usr/bin/env python 00002 # 00003 # Copyright (c) 2010, Bosch LLC 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions are met: 00008 # 00009 # * Redistributions of source code must retain the above copyright 00010 # notice, this list of conditions and the following disclaimer. 00011 # * Redistributions in binary form must reproduce the above copyright 00012 # notice, this list of conditions and the following disclaimer in the 00013 # documentation and/or other materials provided with the distribution. 00014 # * Neither the name of Bosch LLC nor the names of its 00015 # contributors may be used to endorse or promote products derived from 00016 # this software without specific prior written permission. 00017 # 00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00028 # POSSIBILITY OF SUCH DAMAGE. 00029 # 00030 # Authors: Sebastian Haug, Bosch LLC 00031 00032 """ 00033 This GRIPPER class can be used to control an gripper of the pr2. 00034 00035 For a use case see gripper_test.py 00036 """ 00037 import roslib 00038 roslib.load_manifest("simple_robot_control") 00039 import rospy 00040 00041 from pr2_controllers_msgs.msg import * 00042 import actionlib 00043 00044 class Gripper: 00045 def __init__(self, side): 00046 if side == 'r': 00047 self.side = 'r' 00048 elif side == 'l': 00049 self.side = 'l' 00050 else: 00051 rospy.logerr("Abort. Specify 'l' or 'r' for side!") 00052 exit(1) 00053 00054 self.gripperClient = actionlib.SimpleActionClient("/" + self.side + "_gripper_controller/gripper_action", Pr2GripperCommandAction) 00055 00056 if not self.gripperClient.wait_for_server(rospy.Duration(10.0)): 00057 rospy.logerr("Could not connect to /" + self.side + "_gripper_controller/gripper_action action server.") 00058 exit(1) 00059 00060 def getGripperPos(self): 00061 msg = rospy.wait_for_message("/" + self.side + "_gripper_controller/state", pr2_controllers_msgs.msg.JointControllerState) 00062 return msg.process_value 00063 00064 def closeGripper(self, effort = -1, wait = True): 00065 command = Pr2GripperCommand() 00066 command.position = 0.0 00067 command.max_effort = effort 00068 00069 text_result = self.execGripperCommand(command, wait) 00070 rospy.loginfo("Closing " + self.side + " gripper " + text_result) 00071 00072 def openGripper(self, effort = -1, wait = True): 00073 command = Pr2GripperCommand() 00074 command.position = 0.08 00075 command.max_effort = effort 00076 00077 text_result = self.execGripperCommand(command, wait) 00078 rospy.loginfo("Opening " + self.side + " gripper " + text_result) 00079 00080 def gripperToPos(self, pos, effort = -1, wait = True): 00081 command = Pr2GripperCommand() 00082 command.position = pos 00083 command.max_effort = effort 00084 00085 text_result = self.execGripperCommand(command, wait) 00086 rospy.loginfo("Moving " + self.side + " gripper to position " + text_result) 00087 00088 def relaxGripper(self, wait = True ): 00089 command = Pr2GripperCommand() 00090 command.max_effort = 0 00091 command.position = self.getGripperPos() 00092 goal = Pr2GripperCommandGoal(command) 00093 00094 text_result = self.execGripperCommand(command, wait) 00095 rospy.loginfo("Relaxing " + self.side + " gripper " + text_result) 00096 00097 def execGripperCommand(self, command, wait = True): 00098 goal = Pr2GripperCommandGoal(command) 00099 self.gripperClient.send_goal(goal) 00100 if wait: 00101 self.gripperClient.wait_for_result() 00102 00103 result = self.gripperClient.get_result() 00104 did = [] 00105 if self.gripperClient.get_state() != actionlib.GoalStatus.SUCCEEDED: 00106 did.append("failed!") 00107 else: 00108 if result.stalled: did.append("stalled!") 00109 if result.reached_goal: did.append("succeeded!") 00110 return ' and '.join(did)