$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 # Christian Bersch, Bosch LLC 00032 # Charles DuHadway, Bosch LLC 00033 00034 """ 00035 This ARM class can be used to control an arm of the pr2 (without collision 00036 checking). It uses an inverse kinematics server which must be started (e.g. 00037 with the launch file arms_ik.launch) if goToPose(), goToPosition() or 00038 moveGripperToPose() is used. 00039 00040 For a use case see arm_test.py 00041 """ 00042 import roslib 00043 roslib.load_manifest("simple_robot_control") 00044 import rospy 00045 00046 import pr2_controllers_msgs.msg 00047 import std_msgs.msg 00048 import actionlib 00049 import sensor_msgs.msg 00050 import kinematics_msgs.msg 00051 import kinematics_msgs.srv 00052 import geometry_msgs 00053 import trajectory_msgs 00054 import tf.transformations 00055 import numpy 00056 import copy 00057 00058 class Arm: 00059 def __init__(self, side): 00060 if side == 'r': 00061 self.side = 'r' 00062 self.ikPath = "pr2_right_arm_kinematics" 00063 elif side == 'l': 00064 self.side = 'l' 00065 self.ikPath = "pr2_left_arm_kinematics" 00066 else: 00067 rospy.logerr("Abort. Specify 'l' or 'r' for side!") 00068 exit(1) 00069 00070 self.controller = side+"_arm_controller" 00071 self.trajClient = actionlib.SimpleActionClient(self.controller+"/joint_trajectory_action", pr2_controllers_msgs.msg.JointTrajectoryAction) 00072 00073 if not self.trajClient.wait_for_server(rospy.Duration(10.0)): 00074 rospy.logerr("Could not connect to /joint_trajectory_action of " + self.side + " arm.") 00075 exit(1) 00076 00077 self.joint_names = self.getJointNames() 00078 self.cAngles = self.getJointAngles() 00079 00080 self.runIK = rospy.ServiceProxy(self.ikPath + "/get_ik", kinematics_msgs.srv.GetPositionIK) 00081 00082 def sendTraj(self, traj, wait = True): 00083 """ Send the joint trajectory goal to the action server """ 00084 if wait: 00085 self.trajClient.send_goal_and_wait(traj) 00086 else: 00087 self.trajClient.send_goal(traj) 00088 00089 def getState(self): 00090 """ Returns the current state of action client """ 00091 return self.trajClient.get_state() 00092 00093 def getJointNames(self): 00094 """ Contacts param server to get controller joints """ 00095 return rospy.get_param(self.controller + "/joints"); 00096 00097 def getJointAngles(self): 00098 msg = rospy.wait_for_message("/joint_states", sensor_msgs.msg.JointState) 00099 angles = [] 00100 for name in self.joint_names: 00101 angles.append( msg.position[msg.name.index(name)]) 00102 return angles 00103 00104 def getIK(self, goalPose, link_name, seedAngles): 00105 """ Calls inverse kinematics service for the arm. 00106 goalPose - Pose Stamped message showing desired position of link in coord system 00107 linkName - goal Pose target link name - (r_wrist_roll_link or l_wrist_roll_link) 00108 startAngles - seed angles for IK 00109 """ 00110 ikreq = kinematics_msgs.msg.PositionIKRequest() 00111 ikreq.ik_link_name = link_name 00112 ikreq.pose_stamped = goalPose 00113 ikreq.ik_seed_state.joint_state.name = self.joint_names 00114 ikreq.ik_seed_state.joint_state.position = seedAngles 00115 ikres = self.runIK(ikreq, rospy.Duration(5)) 00116 if (ikres.error_code.val != ikres.error_code.SUCCESS): #figure out which error code 00117 raise rospy.exceptions.ROSException("Could not find IK with " + self.ikPath + "\n\n" + ikres.__str__()) 00118 return ikres 00119 00120 def goToAngle(self, angles, time, wait = True): 00121 """ This method moves the arm to the specified joint angles. Users must make 00122 sure to obey safe joint limits. 00123 """ 00124 if (len(angles) != len(self.joint_names)): 00125 raise Exception("Wrong number of Angles. "+ len(angles) + "given. "+ len(self.joint_names) + "needed.") 00126 00127 trajMsg = pr2_controllers_msgs.msg.JointTrajectoryGoal() 00128 00129 trajPoint = trajectory_msgs.msg.JointTrajectoryPoint() 00130 trajPoint.positions = angles 00131 trajPoint.velocities = [0 for i in range(0, len(self.joint_names))] 00132 trajPoint.time_from_start = rospy.Duration(time) 00133 00134 trajMsg.trajectory.joint_names = self.joint_names 00135 trajMsg.trajectory.points.extend([trajPoint]) 00136 self.sendTraj(trajMsg, wait) 00137 00138 def rotateWrist(self, angle, speed = 2.0, wait = True, velocity = 0.0): 00139 """ Rotates wrist by angle in radians. speed is the amount of time that it would take for one revolution. 00140 Velocity sets explicit speed to be attained - careful! If velocity is to high, the wrist may rotate in 00141 opposite direction first 00142 """ 00143 time = speed * abs(angle) * 3.14 / 2 00144 trajMsg = pr2_controllers_msgs.msg.JointTrajectoryGoal() 00145 00146 trajPoint = trajectory_msgs.msg.JointTrajectoryPoint() 00147 angles = self.getJointAngles() 00148 00149 trajPoint.positions = angles 00150 trajPoint.velocities = [0 for i in range(0, len(self.joint_names) - 1)] 00151 trajPoint.velocities.append(velocity) 00152 trajPoint.time_from_start = rospy.Duration(time) 00153 trajMsg.trajectory.joint_names = self.joint_names 00154 #set new wrist angle 00155 dm = divmod(abs(angle),3.14) 00156 for i in range(int(dm[0])): 00157 trajPoint.positions[-1] += 3.14 * numpy.sign(angle) 00158 trajPoint.time_from_start = rospy.Duration(time * (i+1)*3.14 / abs(angle)) 00159 trajMsg.trajectory.points.append(copy.deepcopy(trajPoint)) 00160 trajPoint.positions[-1] += dm[1] * numpy.sign(angle) 00161 trajPoint.time_from_start = rospy.Duration(time) 00162 trajMsg.trajectory.points.append(trajPoint) 00163 self.sendTraj(trajMsg, wait) 00164 00165 00166 def goToPosition(self, pos, frame_id, time, wait = True): 00167 """ This method uses getIK to move the x_wrist_roll_link to the 00168 specific pos specified in frame_id's coordinates. Time specifies 00169 the duration of the planned trajectory, wait whether to block or not. 00170 """ 00171 self.goToPose(pos, (0, 0, 0, 1), frame_id, time, wait) 00172 00173 def goToPose(self, pos, orientation, frame_id, time, wait = True, seed_angles = False): 00174 """ This method uses getIK to move the x_wrist_roll_link to the 00175 specific point and orientation specified in frame_id's coordinates. 00176 Time specifies the duration of the planned trajectory, 00177 wait whether to block or not. 00178 """ 00179 pose = self.makePose(pos, orientation, frame_id) 00180 if not (seed_angles!= False): 00181 seed_angles = self.getJointAngles() 00182 ik = self.getIK(pose, self.side+"_wrist_roll_link", seed_angles) 00183 self.goToAngle(ik.solution.joint_state.position, time, wait) 00184 00185 00186 def moveGripperToPose(self, pos, orientation, frame_id, time, wait = True, seed_angles=False): 00187 """ This method uses gripperToWrist() to calculate the pos_new of the wrist 00188 so that the gripper is moved to the given pos and orientation. 00189 """ 00190 pos_new = self.gripperToWrist(pos, orientation) 00191 self.goToPose(pos_new, orientation, frame_id, time, wait, seed_angles) 00192 00193 def gripperToWrist(self, pos, orientation): 00194 gripper_length = 0.18 00195 vec = (gripper_length, 0 , 0 , 1) 00196 rot = tf.transformations.quaternion_matrix(orientation) 00197 offset = numpy.dot(rot, vec) 00198 return pos - offset[0:3] 00199 00200 def makePose(self, xyz, orientation, frameID): 00201 """ This is a shortcut method for making pose stamped messages 00202 """ 00203 pose = geometry_msgs.msg.PoseStamped() 00204 pose.pose.position.x, pose.pose.position.y, pose.pose.position.z = xyz[0], xyz[1], xyz[2] 00205 pose.pose.orientation.x = orientation[0] 00206 pose.pose.orientation.y = orientation[1] 00207 pose.pose.orientation.z = orientation[2] 00208 pose.pose.orientation.w = orientation[3] 00209 pose.header.frame_id = frameID 00210 pose.header.stamp = rospy.Time.now() 00211 return pose 00212 00213 00214 00215 00216 00217 00218 00219 00220 00221