$search
00001 #! /usr/bin/python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2009, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of the Willow Garage nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 # 00034 # author: Kaijen Hsiao 00035 00036 ## @package ik_utilities 00037 #Utility functions for doing inverse kinematics, forward kinematics, checking a Cartesian path 00038 00039 import roslib; roslib.load_manifest('interpolated_ik_motion_planner') 00040 import rospy 00041 from kinematics_msgs.srv import GetKinematicSolverInfo, GetPositionIK, GetPositionFK, GetConstraintAwarePositionIK, GetConstraintAwarePositionIKRequest 00042 from kinematics_msgs.msg import PositionIKRequest 00043 from geometry_msgs.msg import PoseStamped, Pose, Point, Quaternion, PointStamped, Vector3Stamped 00044 from visualization_msgs.msg import Marker 00045 from arm_navigation_msgs.msg import RobotState, MultiDOFJointState, ArmNavigationErrorCodes 00046 from arm_navigation_msgs.srv import GetStateValidity, GetStateValidityRequest 00047 from sensor_msgs.msg import JointState 00048 import math 00049 import random 00050 import time 00051 import tf 00052 import numpy 00053 import pdb 00054 00055 #pretty-print list to string 00056 def pplist(list): 00057 return ' '.join(['%8.5f'%x for x in list]) 00058 00059 #utility functions for doing inverse kinematics, forward kinematics, checking a Cartesian path 00060 class IKUtilities: 00061 00062 #initialize all service functions 00063 #if wait_for_services = 0, you must call check_services_and_get_ik_info externally before running any of the IK/FK functions 00064 def __init__(self, whicharm, tf_listener = None, wait_for_services = 1): #whicharm is 'right' or 'left' 00065 00066 #gets the robot_prefix from the parameter server. Default is pr2 00067 robot_prefix = rospy.get_param('~robot_prefix', 'pr2') 00068 self.srvroot = '/'+robot_prefix+'_'+whicharm+'_arm_kinematics/' 00069 00070 #If collision_aware_ik is set to 0, then collision-aware IK is disabled 00071 self.perception_running = rospy.get_param('~collision_aware_ik', 1) 00072 00073 self._ik_service = rospy.ServiceProxy(self.srvroot+'get_ik', GetPositionIK, True) 00074 if self.perception_running: 00075 self._ik_service_with_collision = rospy.ServiceProxy(self.srvroot+'get_constraint_aware_ik', GetConstraintAwarePositionIK, True) 00076 00077 self._fk_service = rospy.ServiceProxy(self.srvroot+'get_fk', GetPositionFK, True) 00078 self._query_service = rospy.ServiceProxy(self.srvroot+'get_ik_solver_info', GetKinematicSolverInfo, True) 00079 self._check_state_validity_service = rospy.ServiceProxy('/planning_scene_validity_server/get_state_validity', GetStateValidity, True) 00080 00081 #wait for IK/FK/query services and get the joint names and limits 00082 if wait_for_services: 00083 self.check_services_and_get_ik_info() 00084 00085 if tf_listener == None: 00086 rospy.loginfo("ik_utilities: starting up tf_listener") 00087 self.tf_listener = tf.TransformListener() 00088 else: 00089 self.tf_listener = tf_listener 00090 00091 self.marker_pub = rospy.Publisher('interpolation_markers', Marker) 00092 00093 #dictionary for the possible kinematics error codes 00094 self.error_code_dict = {} #codes are things like SUCCESS, NO_IK_SOLUTION 00095 for element in dir(ArmNavigationErrorCodes): 00096 if element[0].isupper(): 00097 self.error_code_dict[eval('ArmNavigationErrorCodes.'+element)] = element 00098 00099 #reads the start angles from the parameter server 00100 start_angles_list = rospy.get_param('~ik_start_angles', []) 00101 00102 #good additional start angles to try for IK for the PR2, used 00103 #if no start angles were provided 00104 if start_angles_list == []: 00105 self.start_angles_list = [[-0.697, 1.002, 0.021, -0.574, 0.286, -0.095, 1.699], 00106 [-1.027, 0.996, 0.034, -0.333, -3.541, -0.892, 1.694], 00107 [0.031, -0.124, -2.105, -1.145, -1.227, -1.191, 2.690], 00108 [0.410, 0.319, -2.231, -0.839, -2.751, -1.763, 5.494], 00109 [0.045, 0.859, 0.059, -0.781, -1.579, -0.891, 7.707], 00110 [0.420, 0.759, 0.014, -1.099, -3.204, -1.907, 8.753], 00111 [-0.504, 1.297, -1.857, -1.553, -4.453, -1.308, 9.572]] 00112 else: 00113 self.start_angles_list = start_angles_list 00114 00115 if whicharm == 'left': 00116 for i in range(len(self.start_angles_list)): 00117 for joint_ind in [0, 2, 4]: 00118 self.start_angles_list[i][joint_ind] *= -1. 00119 00120 #changes the set of ids used to show the arrows every other call 00121 self.pose_id_set = 0 00122 00123 rospy.loginfo("ik_utilities: done init") 00124 00125 00126 #wait for the various services and run the IK query to get the joint names and limits 00127 def check_services_and_get_ik_info(self): 00128 00129 rospy.loginfo("ik_utilities: waiting for IK services to be there") 00130 rospy.wait_for_service(self.srvroot+'get_ik') 00131 if self.perception_running: 00132 rospy.wait_for_service(self.srvroot+'get_constraint_aware_ik') 00133 rospy.wait_for_service(self.srvroot+'get_fk') 00134 rospy.wait_for_service(self.srvroot+'get_ik_solver_info') 00135 rospy.loginfo("ik_utilities: services found") 00136 00137 #get and store the joint names and limits 00138 #only one IK link available so far ('r_wrist_roll_link' or 'l_wrist_roll_link') 00139 rospy.loginfo("getting the IK solver info") 00140 (self.joint_names, self.min_limits, self.max_limits, self.link_names) = \ 00141 self.run_query() 00142 self.link_name = self.link_names[-1] 00143 rospy.loginfo("done getting the IK solver info") 00144 00145 00146 ##draw a PoseStamped in rviz as a set of arrows (x=red, y=green, z=blue) 00147 #id is the id number for the x-arrow (y is id+1, z is id+2) 00148 def draw_pose(self, pose_stamped, id): 00149 marker = Marker() 00150 marker.header = pose_stamped.header 00151 marker.ns = "basic_shapes" 00152 marker.type = 0 #arrow 00153 marker.action = 0 #add 00154 marker.scale.x = 0.01 00155 marker.scale.y = 0.02 00156 marker.color.a = 1.0 00157 marker.lifetime = rospy.Duration(30.0) 00158 00159 orientation = pose_stamped.pose.orientation 00160 quat = [orientation.x, orientation.y, orientation.z, orientation.w] 00161 mat = tf.transformations.quaternion_matrix(quat) 00162 start = [pose_stamped.pose.position.x, pose_stamped.pose.position.y, pose_stamped.pose.position.z] 00163 x_end = list(mat[:,0][0:3]*.05 + numpy.array(start)) 00164 y_end = list(mat[:,1][0:3]*.05 + numpy.array(start)) 00165 z_end = list(mat[:,2][0:3]*.05 + numpy.array(start)) 00166 #print "start: %5.3f, %5.3f, %5.3f"%(pose_stamped.pose.position.x, pose_stamped.pose.position.y, pose_stamped.pose.position.z) 00167 #print "x_end:", pplist(x_end) 00168 #print "y_end:", pplist(y_end) 00169 #print "z_end:", pplist(z_end) 00170 marker.id = id 00171 marker.points = [pose_stamped.pose.position, Point(*x_end)] 00172 marker.color.r = 1.0 00173 marker.color.g = 0.0 00174 marker.color.b = 0.0 00175 self.marker_pub.publish(marker) 00176 marker.id = id+1 00177 marker.points = [pose_stamped.pose.position, Point(*y_end)] 00178 marker.color.r = 0.0 00179 marker.color.g = 1.0 00180 marker.color.b = 0.0 00181 self.marker_pub.publish(marker) 00182 marker.id = id+2 00183 marker.points = [pose_stamped.pose.position, Point(*z_end)] 00184 marker.color.r = 0.0 00185 marker.color.g = 0.0 00186 marker.color.b = 1.0 00187 self.marker_pub.publish(marker) 00188 00189 00190 ##get the joint names and limits, and the possible link names for running IK 00191 def run_query(self): 00192 try: 00193 resp = self._query_service() 00194 except rospy.ServiceException, e: 00195 rospy.logerr("GetKinematicSolverInfo service call failed! error msg: %s"%e) 00196 return (None, None, None) 00197 00198 min_limits = [limit.min_position for limit in resp.kinematic_solver_info.limits] 00199 max_limits = [limit.max_position for limit in resp.kinematic_solver_info.limits] 00200 # rospy.loginfo("joint_names:" + str(resp.kinematic_solver_info.joint_names)) 00201 # rospy.loginfo("min_limits:" + pplist(min_limits)) 00202 # rospy.loginfo("max_limits:" + pplist(max_limits)) 00203 # rospy.loginfo("link names:" + str(resp.kinematic_solver_info.link_names)) 00204 return (resp.kinematic_solver_info.joint_names, min_limits, max_limits, resp.kinematic_solver_info.link_names) 00205 00206 00207 ##run forward kinematics on a set of 7 joint angles 00208 #link_name specifies the desired output frame 00209 #returns a PoseStamped 00210 def run_fk(self, angles, link_name): 00211 if link_name not in self.link_names: 00212 rospy.logerr("link name %s not possible!"%link_name) 00213 return None 00214 self.link_name = link_name 00215 00216 header = rospy.Header() 00217 header.stamp = rospy.get_rostime() 00218 header.frame_id = 'base_link' 00219 joint_state = JointState(header, self.joint_names, angles, [], []) 00220 try: 00221 resp = self._fk_service(header, [link_name], RobotState(joint_state, MultiDOFJointState())) 00222 except rospy.ServiceException, e: 00223 rospy.logerr("FK service call failed! error msg: %s"%e) 00224 return None 00225 00226 #ik failed, print the error code 00227 if resp.error_code.val != 1: 00228 rospy.loginfo("FK error code: %s"%self.error_code_dict[resp.error_code.val]) 00229 00230 return resp.pose_stamped[0] 00231 00232 00233 ##run inverse kinematics on a PoseStamped (7-dof pose 00234 #(position + quaternion orientation) + header specifying the 00235 #frame of the pose) 00236 #tries to stay close to double start_angles[7] 00237 #returns the solution angles as double solution[7] 00238 #link_name is the link frame to position at pose 00239 #if collision_aware is 1, runs ik_service_with_collision 00240 #ordered_collision_operations is a list of collision operations to feed to IK to modify the collision space 00241 def run_ik(self, pose_stamped, start_angles, link_name, collision_aware = 1, ordered_collision_operations = None, IK_robot_state = None, link_padding = None): 00242 00243 if link_name not in self.link_names: 00244 rospy.logerr("link name %s not possible!"%link_name) 00245 return None 00246 self.link_name = link_name 00247 00248 #print "request:\n", pose_stamped 00249 00250 ik_request = PositionIKRequest() 00251 ik_request.ik_link_name = self.link_name 00252 ik_request.pose_stamped = pose_stamped 00253 ik_request.ik_seed_state.joint_state.header.stamp = rospy.get_rostime() 00254 ik_request.ik_seed_state.joint_state.position = start_angles 00255 ik_request.ik_seed_state.joint_state.name = self.joint_names 00256 00257 if IK_robot_state: 00258 ik_request.robot_state = IK_robot_state 00259 00260 try: 00261 if collision_aware and self.perception_running: 00262 col_free_ik_request = GetConstraintAwarePositionIKRequest() 00263 col_free_ik_request.ik_request = ik_request 00264 col_free_ik_request.timeout = rospy.Duration(10.0) #timeout after 10 seconds 00265 00266 if ordered_collision_operations != None: 00267 col_free_ik_request.ordered_collision_operations = ordered_collision_operations 00268 if link_padding != None: 00269 col_free_ik_request.link_padding = link_padding 00270 00271 resp = self._ik_service_with_collision(col_free_ik_request) 00272 else: 00273 resp = self._ik_service(ik_request, rospy.Duration(10.0)) 00274 except rospy.ServiceException, e: 00275 rospy.logwarn("IK service call failed! error msg: %s"%e) 00276 return (None, None) 00277 00278 #ik failed, print the error code 00279 if resp.error_code.val != 1: 00280 rospy.loginfo("IK error code: %s"%self.error_code_dict[resp.error_code.val]) 00281 #print "requested pose:\n", pose_stamped 00282 00283 return (resp.solution.joint_state.position, self.error_code_dict[resp.error_code.val]) 00284 00285 00286 ##check whether a set of joint angles is in collision with the environment 00287 #allows the same modifications as IK 00288 def check_state_validity(self, joint_angles, ordered_collision_operations = None, \ 00289 robot_state = None, link_padding = None): 00290 00291 req = GetStateValidityRequest() 00292 if robot_state != None: 00293 req.robot_state = robot_state 00294 req.robot_state.joint_state.name.extend(self.joint_names) 00295 req.robot_state.joint_state.position.extend(joint_angles) 00296 req.robot_state.joint_state.header.stamp = rospy.Time.now() 00297 req.check_collisions = True 00298 00299 if ordered_collision_operations != None: 00300 req.ordered_collision_operations = ordered_collision_operations 00301 if link_padding != None: 00302 req.link_padding = link_padding 00303 00304 try: 00305 res = self._check_state_validity_service(req) 00306 except rospy.ServiceException, e: 00307 rospy.logwarn("Check state validity call failed! error msg: %s"%e) 00308 return 0 00309 if res.error_code.val == res.error_code.SUCCESS: 00310 return 1 00311 rospy.loginfo("Check state validity error code: %s"%self.error_code_dict[res.error_code.val]) 00312 return 0 00313 00314 00315 ##convert a pointStamped to a pos list in a desired frame 00316 def point_stamped_to_list(self, point, frame): 00317 00318 #convert the pointStamped to the desired frame, if necessary 00319 if point.header.frame_id != frame: 00320 try: 00321 trans_point = self.tf_listener.transformPoint(frame, point) 00322 except rospy.ServiceException, e: 00323 print "point:\n", point 00324 print "frame:", frame 00325 rospy.logerr("point_stamped_to_list: error in transforming point from " + point.header.frame_id + " to " + frame + "error msg: %s"%e) 00326 return None 00327 else: 00328 trans_point = point 00329 00330 #extract position as a list 00331 pos = [trans_point.point.x, trans_point.point.y, trans_point.point.z] 00332 00333 return pos 00334 00335 00336 ##convert a Vector3Stamped to a rot list in a desired frame 00337 def vector3_stamped_to_list(self, vector3, frame): 00338 00339 #convert the vector3Stamped to the desired frame, if necessary 00340 if vector3.header.frame_id != frame: 00341 try: 00342 trans_vector3 = self.tf_listener.transformVector3(frame, vector3) 00343 except rospy.ServiceException, e: 00344 print "vector3:\n", vector3 00345 print "frame:", frame 00346 rospy.logerr("vector3_stamped_to_list: error in transforming point from " + vector3.header.frame_id + " to " + frame + "error msg: %s"%e) 00347 return None 00348 else: 00349 trans_vector3 = vector3 00350 00351 #extract vect as a list 00352 vect = [trans_vector3.vector.x, trans_vector3.vector.y, trans_vector3.vector.z] 00353 00354 return vect 00355 00356 00357 ##convert a QuaternionStamped to a quat list in a desired frame 00358 def quaternion_stamped_to_list(self, quaternion, frame): 00359 00360 #convert the QuaternionStamped to the desired frame, if necessary 00361 if quaternion.header.frame_id != frame: 00362 try: 00363 trans_quat = self.tf_listener.transformQuaternion(frame, quaternion) 00364 except rospy.ServiceException, e: 00365 print "quaternion:\n", quaternion 00366 print "frame:", frame 00367 rospy.logerr("quaternion_stamped_to_list: error in transforming point from " + quaternion.header.frame_id + " to " + frame + "error msg: %s"%e) 00368 return None 00369 else: 00370 trans_quat = quaternion 00371 00372 #extract quat as a list 00373 quat = [trans_quat.quaternion.x, trans_quat.quaternion.y, trans_quat.quaternion.z, trans_quat.quaternion.w] 00374 00375 return quat 00376 00377 00378 ##convert a poseStamped to pos and rot (quaternion) lists in a desired frame 00379 def pose_stamped_to_lists(self, pose, frame): 00380 00381 #convert the poseStamped to the desired frame, if necessary 00382 if pose.header.frame_id != frame: 00383 pose.header.stamp = rospy.Time(0) 00384 self.tf_listener.waitForTransform(frame, pose.header.frame_id, pose.header.stamp, rospy.Duration(5)) 00385 try: 00386 trans_pose = self.tf_listener.transformPose(frame, pose) 00387 except rospy.ServiceException, e: 00388 print "pose:\n", pose 00389 print "frame:", frame 00390 rospy.logerr("pose_stamped_to_lists: error in transforming pose from " + pose.header.frame_id + " to " + frame + "error msg: %s"%e) 00391 return (None, None) 00392 else: 00393 trans_pose = pose 00394 00395 #extract position and orientation as quaternion 00396 pos = [trans_pose.pose.position.x, trans_pose.pose.position.y, trans_pose.pose.position.z] 00397 rot = [trans_pose.pose.orientation.x, trans_pose.pose.orientation.y, \ 00398 trans_pose.pose.orientation.z, trans_pose.pose.orientation.w] 00399 00400 return (pos, rot) 00401 00402 00403 ##convert pos and rot lists (relative to in_frame) to a poseStamped (relative to to_frame) 00404 def lists_to_pose_stamped(self, pos, rot, in_frame, to_frame): 00405 00406 #stick lists in a poseStamped 00407 m = PoseStamped() 00408 m.header.frame_id = in_frame 00409 m.header.stamp = rospy.get_rostime() 00410 m.pose = Pose(Point(*pos), Quaternion(*rot)) 00411 00412 try: 00413 pose_stamped = self.tf_listener.transformPose(to_frame, m) 00414 except rospy.ServiceException, e: 00415 rospy.logerr("error in transforming pose from " + in_frame + " to " + to_frame + "err msg: %s"%e) 00416 return None 00417 return pose_stamped 00418 00419 00420 ##vector norm of a list 00421 def vect_norm(self, vect): 00422 return sum([x**2 for x in vect])**.5 00423 00424 00425 ##normalize a vector 00426 def normalize_vect(self, vect): 00427 return list(numpy.array(vect)/self.vect_norm(vect)) 00428 00429 00430 ##angle between two quaternions (as lists) 00431 def quat_angle(self, quat1, quat2): 00432 dot = sum([x*y for (x,y) in zip(quat1, quat2)]) 00433 if dot > 1.: 00434 dot = 1. 00435 if dot < -1.: 00436 dot = -1. 00437 angle = 2*math.acos(math.fabs(dot)) 00438 return angle 00439 00440 00441 ##interpolate a Cartesian path (expressed as pos and rot lists) 00442 #pos_spacing is max wrist translation in meters between trajectory points 00443 #rot_spacing is max wrist rotation in radians between trajectory points 00444 #num_steps overrides the number of steps (if != 0, ignore pos_spacing and rot_spacing) 00445 def interpolate_cartesian(self, start_pos, start_rot, end_pos, end_rot, pos_spacing, rot_spacing, num_steps = 0): 00446 00447 #normalize quaternion rotations just in case 00448 norm_start_rot = self.normalize_vect(start_rot) 00449 norm_end_rot = self.normalize_vect(end_rot) 00450 00451 #the desired wrist translation 00452 diff = [x-y for (x,y) in zip(end_pos, start_pos)] 00453 00454 if num_steps == 0: 00455 #compute how far the wrist translates 00456 pos_move = self.vect_norm(diff) 00457 00458 #compute how far the wrist rotates 00459 rot_move = self.quat_angle(norm_start_rot, norm_end_rot) 00460 00461 #compute the number of steps to move no more than pos_spacing and rot_spacing in each step 00462 #(min 2, start and end) 00463 num_steps_pos = math.floor(pos_move/pos_spacing)+1 00464 num_steps_rot = math.floor(rot_move/rot_spacing)+1 00465 num_steps = int(max([num_steps_pos, num_steps_rot])+1) 00466 00467 #interpolate 00468 steps = [] 00469 for stepind in range(num_steps): 00470 fraction = float(stepind)/(num_steps-1) #add both start (0) and end (1) 00471 rot = list(tf.transformations.quaternion_slerp(norm_start_rot, norm_end_rot, fraction)) 00472 pos = list(numpy.array(diff)*fraction + numpy.array(start_pos)) 00473 steps.append((pos, rot)) 00474 #print "fraction: %5.3f"%fraction, "pos:", pplist(pos), "rot:", pplist(rot) 00475 00476 return steps 00477 00478 00479 ##check that all differences between angles1 and angles2 (lists of joint angles) are within consistent_range 00480 def check_consistent(self, angles1, angles2, consistent_range): 00481 diff = [math.fabs(x-y) for (x,y) in zip(angles1, angles2)] 00482 inconsistent = any([x>consistent_range for x in diff]) 00483 return not inconsistent 00484 00485 00486 ##generate appropriate times and joint velocities for a joint path (such as that output by check_cartesian_path) 00487 #max_joint_vels is a list of maximum velocities to move the arm joints 00488 #max_joint_accs is a list of maximum accelerations to move the arm joints (can be ignored) 00489 #starts and ends in stop 00490 def trajectory_times_and_vels(self, joint_path, max_joint_vels = [.2]*7, max_joint_accs = [.5]*7): 00491 00492 #min time for each segment 00493 min_segment_time = .01 00494 00495 if not joint_path: 00496 rospy.logdebug("joint path was empty!") 00497 return([], []) 00498 traj_length = len(joint_path) 00499 num_joints = len(joint_path[0]) 00500 00501 #sanity-check max vels and accelerations 00502 if not max_joint_vels: 00503 max_joint_vels = [.2]*7 00504 elif len(max_joint_vels) != num_joints: 00505 rospy.logerr("invalid max_joint_vels!") 00506 return ([], []) 00507 if not max_joint_accs: 00508 max_joint_accs = [.5]*7 00509 elif len(max_joint_accs) != num_joints: 00510 rospy.logerr("invalid max_joint_accs!") 00511 return ([], []) 00512 for ind in range(num_joints): 00513 if max_joint_vels[ind] <= 0.: 00514 max_joint_vels[ind] = .2 00515 if max_joint_accs[ind] <= 0.: 00516 max_joint_accs[ind] = .5 00517 00518 vels = [[None]*num_joints for i in range(traj_length)] 00519 00520 #give the trajectory a bit of time to start 00521 segment_times = [None]*traj_length 00522 segment_times[0] = 0.05 00523 00524 #find vaguely appropriate segment times, assuming that we're traveling at max_joint_vels at the fastest joint 00525 for ind in range(traj_length-1): 00526 joint_diffs = [math.fabs(joint_path[ind+1][x]-joint_path[ind][x]) for x in range(num_joints)] 00527 joint_times = [diff/vel for (diff, vel) in zip(joint_diffs, max_joint_vels)] 00528 segment_times[ind+1] = max(joint_times+[min_segment_time]) 00529 00530 #set the initial and final velocities to 0 for all joints 00531 vels[0] = [0.]*num_joints 00532 vels[traj_length-1] = [0.]*num_joints 00533 00534 #also set the velocity where any joint changes direction to be 0 for that joint 00535 #and otherwise use the average velocity (assuming piecewise-linear velocities for the segments before and after) 00536 for ind in range(1, traj_length-1): 00537 for joint in range(num_joints): 00538 diff0 = joint_path[ind][joint]-joint_path[ind-1][joint] 00539 diff1 = joint_path[ind+1][joint]-joint_path[ind][joint] 00540 if (diff0>0 and diff1<0) or (diff0<0 and diff1>0): 00541 vels[ind][joint] = 0. 00542 else: 00543 vel0 = diff0/segment_times[ind] 00544 vel1 = diff1/segment_times[ind+1] 00545 vels[ind][joint] = (vel0+vel1)/2. 00546 00547 #increase the times if the desired velocities would require overly large accelerations 00548 for ind in range(1, traj_length): 00549 for joint in range(num_joints): 00550 veldiff = math.fabs(vels[ind][joint]-vels[ind-1][joint]) 00551 acc = veldiff/segment_times[ind] 00552 try: 00553 if acc > max_joint_accs[joint]: 00554 segment_times[ind] = veldiff/max_joint_accs[joint] 00555 except: 00556 pdb.set_trace() 00557 00558 #turn the segment_times into waypoint times (cumulative) 00559 times = [None]*traj_length 00560 times[0] = segment_times[0] 00561 for ind in range(1, traj_length): 00562 try: 00563 times[ind] = times[ind-1]+segment_times[ind] 00564 except: 00565 pdb.set_trace() 00566 00567 #return the times and velocities 00568 return (times, vels) 00569 00570 00571 ##check a Cartesian path for consistent, non-colliding IK solutions 00572 #start_pose and end_pose are PoseStamped messages with the wrist poses 00573 #start_angles are angles to try to stay close to 00574 #num_steps is the number of interpolation steps to use (if 0, use 00575 # pos_spacing and rot_spacing instead to calculate the number of steps) 00576 #pos_spacing is max wrist translation in meters between trajectory points 00577 #rot_spacing is max wrist rotation in radians between trajectory points 00578 #consistent_angle is the max joint angle change before 2 steps are declared inconsistent 00579 #collision_check_resolution is the resolution at which to check collisions (0 or 1 for every) 00580 #steps_before_abort is the number of invalid steps found before aborting (-1 to ignore) 00581 #if collision_aware is 0, ignore collisions 00582 #ordered_collision_operations is an optional list of collision operations to feed to IK to modify the collision space 00583 #link_padding is an optional list of link paddings to feed to IK to modify the robot collision padding 00584 #IK_robot_state is an optional RobotState message to pass to IK 00585 #if start_from_end is 1, find an IK solution for the end first and work backwards 00586 #returns the joint angle trajectory and the error codes (0=good, 00587 # 1=collisions, 2=inconsistent, 3=out of reach, 4=aborted before checking) 00588 def check_cartesian_path(self, start_pose, end_pose, start_angles, pos_spacing = 0.01, rot_spacing = 0.1, consistent_angle = math.pi/9., collision_aware = 1, collision_check_resolution = 1, steps_before_abort = -1, num_steps = 0, ordered_collision_operations = None, start_from_end = 0, IK_robot_state = None, link_padding = None, use_additional_start_angles = 0): 00589 00590 #sanity-checking 00591 if num_steps != 0 and num_steps < 2: 00592 num_steps = 2 00593 if collision_check_resolution < 1: 00594 collision_check_resolution = 1 00595 if num_steps == 0 and (pos_spacing <= 0 or rot_spacing <= 0): 00596 rospy.logerr("invalid pos_spacing or rot_spacing") 00597 return ([], []) 00598 00599 #convert to lists 00600 (start_pos, start_rot) = self.pose_stamped_to_lists(start_pose, 'base_link') 00601 (end_pos, end_rot) = self.pose_stamped_to_lists(end_pose, 'base_link') 00602 if start_pos == None or end_pos == None: 00603 return (None, None) 00604 00605 #interpolate path 00606 steps = self.interpolate_cartesian(start_pos, start_rot, end_pos, end_rot, pos_spacing, rot_spacing, num_steps) 00607 00608 #run collision-aware ik on each step, starting from the end and going backwards if start_from_end is true 00609 if start_from_end: 00610 steps.reverse() 00611 00612 #use additional start angles from a pre-chosen set 00613 if use_additional_start_angles: 00614 num_to_use = max(use_additional_start_angles, len(self.start_angles_list)) 00615 start_angles_list = [start_angles,] + self.start_angles_list[0:num_to_use] 00616 else: 00617 start_angles_list = [start_angles,] 00618 00619 #go through each set of start angles, see if we can find a consistent trajectory 00620 for (start_angles_ind, start_angles) in enumerate(start_angles_list): 00621 trajectory = [] 00622 error_codes = [] 00623 00624 if use_additional_start_angles: 00625 rospy.loginfo("start_angles_ind: %d"%start_angles_ind) 00626 00627 for stepind in range(len(steps)): 00628 (pos,rot) = steps[stepind] 00629 pose_stamped = self.lists_to_pose_stamped(pos, rot, 'base_link', 'base_link') 00630 00631 #draw the pose in rviz that we're checking in IK 00632 self.draw_pose(pose_stamped, stepind*3+self.pose_id_set*50) 00633 self.pose_id_set = (self.pose_id_set+1)%2 00634 00635 #check for a non-collision_aware IK solution first 00636 (colliding_solution, error_code) = self.run_ik(pose_stamped, start_angles, self.link_name, collision_aware = 0, IK_robot_state = IK_robot_state) 00637 if not colliding_solution: 00638 rospy.loginfo("non-collision-aware IK solution not found for step %d!"%stepind) 00639 trajectory.append([0.]*7) 00640 error_codes.append(3) #3=out of reach 00641 00642 else: 00643 #if we're checking for collisions, then look for a collision-aware solution 00644 collision_aware_this_step = collision_aware and (stepind % collision_check_resolution == 0 or stepind == len(steps)-1) 00645 if collision_aware_this_step: 00646 (solution, error_code) = self.run_ik(pose_stamped, start_angles, self.link_name, collision_aware, ordered_collision_operations, IK_robot_state = IK_robot_state, link_padding = link_padding) 00647 if not solution: 00648 rospy.loginfo("non-colliding IK solution not found for step %d!"%stepind) 00649 collision_aware_solution_found = 0 00650 solution = colliding_solution 00651 else: 00652 collision_aware_solution_found = 1 00653 else: 00654 solution = colliding_solution 00655 00656 trajectory.append(list(solution)) 00657 00658 #first trajectory point, or last point was all 0s, or consistent with previous point 00659 if stepind == 0 or error_codes[-1] == 3 or self.check_consistent(trajectory[-2], solution, consistent_angle): 00660 if not collision_aware_this_step or collision_aware_solution_found: 00661 error_codes.append(0) #0=good 00662 else: 00663 error_codes.append(1) #1=collisions 00664 else: 00665 rospy.loginfo("IK solution not consistent for step %d!"%stepind) 00666 error_codes.append(2) #2=inconsistent 00667 00668 start_angles = solution 00669 00670 #check if we should abort due to finding too many invalid points 00671 if error_codes[-1] > 0 and steps_before_abort >= 0 and stepind >= steps_before_abort: 00672 rospy.loginfo("aborting due to too many invalid steps") 00673 trajectory.extend([[0.]*7 for i in range(len(steps)-stepind-1)]) 00674 error_codes.extend([4]*(len(steps)-stepind-1)) #4=aborted before checking 00675 break 00676 00677 #if we didn't abort, stop and return the trajectory 00678 #if not any(error_codes): 00679 else: 00680 break 00681 00682 if start_from_end: 00683 trajectory.reverse() 00684 error_codes.reverse() 00685 return (trajectory, error_codes) 00686 00687 00688 #test functions 00689 if __name__ == '__main__': 00690 00691 def keypause(): 00692 print "press enter to continue" 00693 raw_input() 00694 00695 #run check_cartesian_path after converting lists to poseStamped 00696 def check_cartesian_path_lists(ik_utilities, approachpos, approachquat, grasppos, graspquat, start_angles, pos_spacing = 0.01, \ 00697 rot_spacing = 0.1, consistent_angle = math.pi/9., collision_aware = 1, \ 00698 collision_check_resolution = 1, steps_before_abort = -1, num_steps = 0, frame = 'base_link'): 00699 00700 print "approachpos:", pplist(approachpos), " approachquat:", pplist(approachquat) 00701 print "grasppos: ", pplist(grasppos), " graspquat: ", pplist(graspquat) 00702 00703 start_pose = ik_utilities.lists_to_pose_stamped(approachpos, approachquat, frame, frame) 00704 end_pose = ik_utilities.lists_to_pose_stamped(grasppos, graspquat, frame, frame) 00705 00706 (trajectory, error_codes) = ik_utilities.check_cartesian_path(start_pose, \ 00707 end_pose, start_angles, pos_spacing, rot_spacing, consistent_angle, collision_aware, collision_check_resolution, \ 00708 steps_before_abort, num_steps, use_additional_start_angles = 2) 00709 (times, vels) = ik_utilities.trajectory_times_and_vels(trajectory, [.2]*7, [.5]*7) 00710 00711 rospy.loginfo("trajectory:") 00712 for ind in range(len(trajectory)): 00713 rospy.loginfo("error code "+ str(error_codes[ind]) + " pos : " + pplist(trajectory[ind])) 00714 rospy.loginfo("") 00715 for ind in range(len(trajectory)): 00716 rospy.loginfo("time: " + "%5.3f "%times[ind] + "vels: " + pplist(vels[ind])) 00717 00718 return (trajectory, error_codes) 00719 00720 00721 #test check_cartesian_path 00722 def run_cartesian_path_test(ik_utilities): 00723 00724 #side grasp 00725 #start_angles = [-0.447, -0.297, -2.229, -0.719, 0.734, -1.489, 1.355] 00726 start_angles = [0]*7 00727 sideapproachmat = numpy.array([[0., -1., 0., 0.], 00728 [1., 0., 0., 0.], 00729 [0., 0., 1., 0.], 00730 [0., 0., 0., 1.]]) 00731 sideapproachpos = [.62, -.3, .75] 00732 approachmat = sideapproachmat 00733 approachpos = sideapproachpos 00734 approachquat = list(tf.transformations.quaternion_from_matrix(approachmat)) 00735 sidegrasppos = sideapproachpos[:] 00736 sidegrasppos[1] += .05 00737 grasppos = sidegrasppos 00738 graspquat = approachquat[:] 00739 print "side grasp" 00740 check_cartesian_path_lists(ik_utilities, approachpos, approachquat, grasppos, graspquat, start_angles) 00741 00742 00743 #top to side grasp 00744 start_angles = [0.]*7 00745 approachpos = [.62, -.05, .85] 00746 approachquat = [-0.5, 0.5, 0.5, 0.5] #from the top 00747 grasppos = [.62, -.05, .75] 00748 graspquat = [0.00000, 0.00000, 0.70711, 0.70711] #from the side 00749 print "top to side grasp, collision-aware" 00750 check_cartesian_path_lists(ik_utilities, approachpos, approachquat, grasppos, graspquat, start_angles, pos_spacing = .01, rot_spacing = .2) 00751 00752 print "more finely spaced rotations, not collision-aware" 00753 check_cartesian_path_lists(ik_utilities, approachpos, approachquat, grasppos, graspquat, start_angles, pos_spacing = .02, rot_spacing = .05, collision_aware = 0) 00754 00755 print "5 steps, too far apart for default consistent_angle" 00756 check_cartesian_path_lists(ik_utilities, approachpos, approachquat, grasppos, graspquat, start_angles, num_steps = 5) 00757 00758 print "5 steps, consistent_angle of pi/4" 00759 check_cartesian_path_lists(ik_utilities, approachpos, approachquat, grasppos, graspquat, start_angles, num_steps = 5, consistent_angle = math.pi/4) 00760 00761 #top grasp through the table 00762 start_angles = [0.]*7 00763 approachpos = [.62, -.05, .65] 00764 approachquat = [-0.5, 0.5, 0.5, 0.5] #from the top 00765 grasppos = [.62, -.05, .25] 00766 graspquat = approachquat[:] 00767 print "top grasp through the table" 00768 check_cartesian_path_lists(ik_utilities, approachpos, approachquat, grasppos, graspquat, start_angles, pos_spacing = 0.02, collision_aware = 1, collision_check_resolution = 2, steps_before_abort = -1) 00769 00770 print "abort early" 00771 check_cartesian_path_lists(ik_utilities, approachpos, approachquat, grasppos, graspquat, start_angles, pos_spacing = 0.02, collision_aware = 1, collision_check_resolution = 2, steps_before_abort = 1) 00772 00773 print "not collision-aware" 00774 check_cartesian_path_lists(ik_utilities, approachpos, approachquat, grasppos, graspquat, start_angles, pos_spacing = 0.02, collision_aware = 0, steps_before_abort = -1) 00775 00776 print "12 steps, collision-aware, collision_check_resolution of 3" 00777 check_cartesian_path_lists(ik_utilities, approachpos, approachquat, grasppos, graspquat, start_angles, collision_aware = 1, collision_check_resolution = 3, num_steps = 12) 00778 00779 00780 #test ik and fk using a randomly-generated joint pose 00781 def run_ik_and_fk_test(ik_utilities, collision_aware = 1): 00782 00783 #check if two lists of numbers are near each other 00784 trans_near = 1e-4 00785 rot_near = 1e-4 00786 def not_near(list1, list2, near): 00787 return any([math.fabs(v1-v2) > near for (v1, v2) in zip(list1, list2)]) 00788 00789 #random seed based on the current time 00790 random.seed() 00791 00792 #generate a random joint-angle configuration 00793 random_angles = [random.uniform(min, max) for (min, max) in \ 00794 zip(ik_utilities.min_limits, ik_utilities.max_limits)] 00795 00796 #run forward kinematics to get the corresponding Cartesian pose 00797 fk_pose = ik_utilities.run_fk(random_angles, ik_utilities.link_name) 00798 pos1 = fk_pose.pose.position 00799 rot1 = fk_pose.pose.orientation 00800 pos1list = [pos1.x, pos1.y, pos1.z] 00801 rot1list = [rot1.x, rot1.y, rot1.z, rot1.w] 00802 00803 #run inverse kinematics on that pose to get a set of angles 00804 #that also make that Cartesian pose (starting from all 0 angles) 00805 rospy.loginfo("IK request: pos "+pplist(pos1list)+" rot "+pplist(rot1list)) 00806 (ik_angles, error_code) = ik_utilities.run_ik(fk_pose, [0]*7, ik_utilities.link_name, collision_aware) 00807 if not ik_angles: 00808 00809 #test check_state_validity to see if it is in agreement about random_angles being in collision 00810 if collision_aware: 00811 valid = ik_utilities.check_state_validity(random_angles) 00812 if valid: 00813 rospy.logerr("check state validity thinks random_angles is not in collision!") 00814 00815 return 0 00816 00817 #run forward kinematics on the ik solution to see if the 00818 #resulting pose matches the first 00819 fk_pose2 = ik_utilities.run_fk(ik_angles, ik_utilities.link_name) 00820 pos2 = fk_pose2.pose.position 00821 rot2 = fk_pose2.pose.orientation 00822 pos2list = [pos2.x, pos2.y, pos2.z] 00823 rot2list = [rot2.x, rot2.y, rot2.z, rot2.w] 00824 00825 #test check_state_validity to see if it is in agreement about ik_angles not being in collision 00826 if collision_aware: 00827 valid = ik_utilities.check_state_validity(ik_angles) 00828 if not valid: 00829 rospy.logerr("check state validity thinks ik_angles is in collision!") 00830 00831 #check the resulting solution 00832 if not_near(pos1list, pos2list, trans_near) or \ 00833 not_near(rot1list, rot2list, rot_near): 00834 rospy.loginfo("IK solution incorrect!") 00835 correct = 0 00836 else: 00837 rospy.loginfo("IK solution good") 00838 correct = 1 00839 rospy.loginfo("FK response:pos "+pplist(pos2list)+" rot "+pplist(rot2list)) 00840 if not correct: 00841 return 0 00842 00843 return 1 00844 00845 00846 def test_ik_with_specific_pose(ik_utilities): 00847 pose_stamped = ik_utilities.lists_to_pose_stamped([.62, -.05, .5], [.5, -.5, -.5, -.5], 'base_link', 'base_link') 00848 print "link name:", ik_utilities.link_name 00849 print "desired pose:\n", pose_stamped 00850 (solution, error_code) = ik_utilities.run_ik(pose_stamped, [0]*7, ik_utilities.link_name, 0) 00851 print "solution:", solution 00852 00853 00854 rospy.init_node('test_ik_and_fk', anonymous=True) 00855 00856 ik_utilities = IKUtilities('right', wait_for_services = 0) 00857 ik_utilities.check_services_and_get_ik_info() 00858 00859 print "testing ik and fk with random joint angles" 00860 for i in range(20): 00861 run_ik_and_fk_test(ik_utilities) 00862 00863 print "testing the cartesian path interpolator" 00864 run_cartesian_path_test(ik_utilities) 00865 00866 print "running a specific pose" 00867 test_ik_with_specific_pose(ik_utilities) 00868 00869 00870 00871 00872