$search
00001 #! /usr/bin/env python 00002 00003 PKG = 'arm_navigation_tests' 00004 00005 import roslib; roslib.load_manifest(PKG) 00006 import rospy 00007 import sys 00008 import unittest 00009 import actionlib 00010 import actionlib_msgs 00011 import math 00012 import random 00013 00014 import sensor_msgs.msg 00015 import arm_navigation_msgs.msg 00016 from arm_navigation_msgs.msg import CollisionObject 00017 from arm_navigation_msgs.msg import CollisionOperation, DisplayTrajectory 00018 from arm_navigation_msgs.msg import Shape 00019 from geometry_msgs.msg import Pose, PointStamped, Quaternion 00020 from arm_navigation_msgs.srv import GetMotionPlan, GetMotionPlanRequest 00021 from tf import TransformListener 00022 from arm_navigation_msgs.msg import JointConstraint, OrientationConstraint, PositionConstraint 00023 from arm_navigation_msgs import arm_navigation_msgs_utils 00024 from kinematics_msgs.srv import GetConstraintAwarePositionIK, GetConstraintAwarePositionIKRequest, GetKinematicSolverInfo, GetKinematicSolverInfoRequest 00025 from arm_navigation_msgs.srv import GetStateValidity,GetStateValidityRequest, GetJointTrajectoryValidity, GetJointTrajectoryValidityRequest 00026 00027 class TestConstrainedPlanning(unittest.TestCase): 00028 00029 def generateRandomUnitQuaternion(self): 00030 orientation = Quaternion() 00031 orientation.x = random.uniform(-1.0, 1.0) 00032 orientation.y = random.uniform(-1.0, 1.0) 00033 orientation.z = random.uniform(-1.0, 1.0) 00034 orientation.w = random.uniform(-1.0, 1.0) 00035 00036 mag = math.sqrt(math.pow(orientation.x,2.0)+math.pow(orientation.y,2.0)+math.pow(orientation.z,2.0)+math.pow(orientation.w,2.0)) 00037 orientation.x /= mag 00038 orientation.y /= mag 00039 orientation.z /= mag 00040 orientation.w /= mag 00041 00042 return orientation 00043 00044 def getGraspQuaternion(self, grasp_name): 00045 00046 orientation = Quaternion() 00047 00048 if(grasp_name == 'top'): 00049 orientation.x = 0.0 00050 orientation.y = 0.7071 00051 orientation.z = 0.0 00052 orientation.w = 0.7071 00053 else: 00054 orientation.x = 0.0 00055 orientation.y = 0.0 00056 orientation.z = 0.0 00057 orientation.w = 1.0 00058 00059 return orientation 00060 00061 def generateRandomValues(self): 00062 ret = [float() for _ in range(len(self.min_limits))] 00063 for i in range(len(self.min_limits)): 00064 ret[i] = random.uniform(self.min_limits[i], self.max_limits[i]) 00065 return ret 00066 00067 def generateValidRandomRobotState(self): 00068 00069 valid_state_req = GetStateValidityRequest() 00070 valid_state_req.robot_state.joint_state.name = self.joint_names 00071 valid_state_req.check_collisions = True 00072 00073 while(True): 00074 valid_state_req.robot_state.joint_state.position = self.generateRandomValues() 00075 state_val_res = self.state_validity_service.call(valid_state_req) 00076 if(state_val_res.error_code.val == state_val_res.error_code.SUCCESS): 00077 return valid_state_req.robot_state 00078 00079 def generateRandomValidConstrainedState(self, quat): 00080 00081 kin_req = GetConstraintAwarePositionIKRequest() 00082 kin_req.ik_request.ik_link_name = 'r_wrist_roll_link' 00083 00084 kin_req.ik_request.ik_seed_state.joint_state.name = self.joint_names 00085 kin_req.ik_request.ik_seed_state.joint_state.position = self.generateRandomValues() 00086 kin_req.ik_request.robot_state = self.generateValidRandomRobotState() 00087 00088 kin_req.timeout = rospy.Duration(2.0) 00089 kin_req.ik_request.pose_stamped.header.frame_id = 'base_link' 00090 00091 kin_req.ik_request.pose_stamped.pose.orientation = quat 00092 00093 while(True): 00094 kin_req.ik_request.pose_stamped.pose.position.x = random.uniform(self.x_workspace_min, self.x_workspace_max) 00095 kin_req.ik_request.pose_stamped.pose.position.y = random.uniform(self.y_workspace_min, self.y_workspace_max) 00096 kin_req.ik_request.pose_stamped.pose.position.z = random.uniform(self.z_workspace_min, self.z_workspace_max) 00097 00098 kin_res = self.ik_service.call(kin_req) 00099 00100 if(kin_res.error_code.val == kin_res.error_code.SUCCESS): 00101 break 00102 00103 return (kin_res.solution,kin_req.ik_request.pose_stamped) 00104 00105 def setUp(self): 00106 00107 self.joint_names = ['r_shoulder_pan_joint', 'r_shoulder_lift_joint', 'r_upper_arm_roll_joint', 'r_elbow_flex_joint', 'r_forearm_roll_joint', 'r_wrist_flex_joint', 'r_wrist_roll_joint'] 00108 00109 self.coll_ik_name = '/pr2_right_arm_kinematics/get_constraint_aware_ik' 00110 self.env_server_name = '/environment_server/get_state_validity' 00111 self.ik_info_name = '/pr2_right_arm_kinematics/get_ik_solver_info' 00112 self.motion_planning_name = '/ik_constrained_planner/plan_path' 00113 self.check_trajectory_name = '/environment_server/get_trajectory_validity' 00114 00115 self.x_workspace_min = -.1 00116 self.x_workspace_max = 1.0 00117 00118 self.y_workspace_min = -1.0 00119 self.y_workspace_max = .3 00120 00121 self.z_workspace_min = 1.0 00122 self.z_workspace_max = 0.0 00123 00124 rospy.init_node('test_constrained_planning') 00125 00126 self.trajectory_pub = rospy.Publisher('display_path', DisplayTrajectory) 00127 00128 rospy.wait_for_service(self.coll_ik_name) 00129 self.ik_service = rospy.ServiceProxy(self.coll_ik_name, GetConstraintAwarePositionIK) 00130 00131 rospy.wait_for_service(self.ik_info_name) 00132 self.ik_info_service = rospy.ServiceProxy(self.ik_info_name, GetKinematicSolverInfo) 00133 00134 rospy.wait_for_service(self.env_server_name) 00135 self.state_validity_service = rospy.ServiceProxy(self.env_server_name, GetStateValidity) 00136 00137 rospy.wait_for_service(self.check_trajectory_name) 00138 self.check_trajectory_service = rospy.ServiceProxy(self.check_trajectory_name, GetJointTrajectoryValidity) 00139 00140 rospy.wait_for_service(self.motion_planning_name) 00141 self.motion_planning_service = rospy.ServiceProxy(self.motion_planning_name, GetMotionPlan) 00142 00143 ik_info_req = GetKinematicSolverInfoRequest() 00144 ik_info_res = self.ik_info_service.call(ik_info_req) 00145 self.min_limits = [float() for _ in range(len(ik_info_res.kinematic_solver_info.limits))] 00146 self.max_limits = [float() for _ in range(len(ik_info_res.kinematic_solver_info.limits))] 00147 for i in range(len(ik_info_res.kinematic_solver_info.limits)): 00148 self.min_limits[i] = ik_info_res.kinematic_solver_info.limits[i].min_position 00149 self.max_limits[i] = ik_info_res.kinematic_solver_info.limits[i].max_position 00150 00151 00152 00153 def tearDown(self): 00154 00155 print 'teardown' 00156 00157 def testIkConstrainedPlanner(self): 00158 00159 for _ in range(25): 00160 00161 quat = self.generateRandomUnitQuaternion() 00162 00163 (start_state,start_pose) = self.generateRandomValidConstrainedState(quat) 00164 (goal_state, goal_pose) = self.generateRandomValidConstrainedState(quat) 00165 00166 motion_goal = GetMotionPlanRequest() 00167 motion_goal.motion_plan_request.group_name = "right_arm" 00168 motion_goal.motion_plan_request.num_planning_attempts = 1 00169 motion_goal.motion_plan_request.allowed_planning_time = rospy.Duration(5.) 00170 motion_goal.motion_plan_request.planner_id = "" 00171 00172 motion_goal.motion_plan_request.start_state = start_state 00173 00174 motion_goal.motion_plan_request.goal_constraints.position_constraints = [PositionConstraint() for _ in range(1)] 00175 motion_goal.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id = 'base_link' 00176 motion_goal.motion_plan_request.goal_constraints.position_constraints[0].link_name = 'r_wrist_roll_link' 00177 motion_goal.motion_plan_request.goal_constraints.position_constraints[0].position = goal_pose.pose.position 00178 00179 motion_goal.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.type = Shape.BOX; 00180 motion_goal.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions = [float(.02) for _ in range(3)] 00181 00182 motion_goal.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_orientation.w = 1.0 00183 motion_goal.motion_plan_request.goal_constraints.position_constraints[0].weight = 1.0; 00184 00185 motion_goal.motion_plan_request.goal_constraints.orientation_constraints = [OrientationConstraint() for _ in range(1)] 00186 motion_goal.motion_plan_request.goal_constraints.orientation_constraints[0].header.frame_id = "torso_lift_link" 00187 motion_goal.motion_plan_request.goal_constraints.orientation_constraints[0].header.stamp = rospy.Time.now() 00188 motion_goal.motion_plan_request.goal_constraints.orientation_constraints[0].link_name = "r_wrist_roll_link" 00189 motion_goal.motion_plan_request.goal_constraints.orientation_constraints[0].orientation = goal_pose.pose.orientation 00190 motion_goal.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.04 00191 motion_goal.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.04 00192 motion_goal.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_yaw_tolerance = 0.04 00193 00194 motion_goal.motion_plan_request.path_constraints.orientation_constraints = [OrientationConstraint() for _ in range(1)] 00195 motion_goal.motion_plan_request.path_constraints.orientation_constraints[0].header.frame_id = "torso_lift_link" 00196 motion_goal.motion_plan_request.path_constraints.orientation_constraints[0].header.stamp = rospy.Time.now() 00197 motion_goal.motion_plan_request.path_constraints.orientation_constraints[0].link_name = "r_wrist_roll_link" 00198 00199 motion_goal.motion_plan_request.path_constraints.orientation_constraints[0].orientation = goal_pose.pose.orientation 00200 00201 motion_goal.motion_plan_request.path_constraints.orientation_constraints[0].type = OrientationConstraint.HEADER_FRAME 00202 motion_goal.motion_plan_request.path_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.1 00203 motion_goal.motion_plan_request.path_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.1 00204 motion_goal.motion_plan_request.path_constraints.orientation_constraints[0].absolute_yaw_tolerance = math.pi 00205 00206 try: 00207 motion_res = self.motion_planning_service.call(motion_goal) 00208 except rospy.ServiceException, e: 00209 self.fail('motion planning failed') 00210 00211 #self.failIf(motion_res.error_code.val != motion_res.error_code.SUCCESS, motion_res.error_code.val) 00212 00213 trajectory_check_req = GetJointTrajectoryValidityRequest() 00214 trajectory_check_req.robot_state = motion_res.robot_state 00215 trajectory_check_req.trajectory = motion_res.trajectory.joint_trajectory 00216 trajectory_check_req.check_collisions = True 00217 trajectory_check_req.check_joint_limits = True 00218 trajectory_check_req.check_path_constraints = True 00219 trajectory_check_req.check_full_trajectory = True 00220 trajectory_check_req.goal_constraints = motion_goal.motion_plan_request.goal_constraints 00221 trajectory_check_req.path_constraints = motion_goal.motion_plan_request.path_constraints 00222 00223 trajectory_check_res = self.check_trajectory_service.call(trajectory_check_req) 00224 00225 self.failIf(trajectory_check_res.error_code.val != trajectory_check_res.error_code.SUCCESS) 00226 00227 disp = DisplayTrajectory() 00228 disp.model_id = "right_arm" 00229 disp.trajectory.joint_trajectory = trajectory_check_req.trajectory 00230 disp.robot_state = trajectory_check_req.robot_state 00231 self.trajectory_pub.publish(disp) 00232 00233 rospy.sleep(2.0) 00234 00235 if __name__ == '__main__': 00236 00237 import rostest 00238 rostest.unitrun('test_constrained_planning', 'test_constrained_planning', TestConstrainedPlanning) 00239