$search
00001 #! /usr/bin/env python 00002 00003 PKG = 'move_arm' 00004 00005 import roslib; roslib.load_manifest(PKG) 00006 import rospy 00007 import planning_environment_msgs.srv 00008 import sys 00009 import unittest 00010 import actionlib 00011 import actionlib_msgs 00012 import math 00013 00014 import sensor_msgs.msg 00015 import mapping_msgs.msg 00016 from mapping_msgs.msg import CollisionObject 00017 from motion_planning_msgs.msg import CollisionOperation, MotionPlanRequest, DisplayTrajectory 00018 from motion_planning_msgs.srv import GetMotionPlanRequest, GetMotionPlan 00019 from geometric_shapes_msgs.msg import Shape 00020 from geometry_msgs.msg import Pose, PointStamped 00021 from tf import TransformListener 00022 from motion_planning_msgs.msg import JointConstraint 00023 00024 padd_name = "ompl_planning/robot_padd" 00025 extra_buffer = .1 00026 00027 class TestMotionExecutionBuffer(unittest.TestCase): 00028 00029 def setUp(self): 00030 00031 rospy.init_node('test_motion_execution_buffer') 00032 00033 self.tf = TransformListener() 00034 00035 self.obj_pub = rospy.Publisher('collision_object',CollisionObject,latch=True) 00036 self.traj_pub = rospy.Publisher('rosie_path',DisplayTrajectory,latch=True) 00037 00038 rospy.wait_for_service("ompl_planning/plan_kinematic_path") 00039 self.motion_planning_service = rospy.ServiceProxy("ompl_planning/plan_kinematic_path", GetMotionPlan) 00040 00041 obj1 = CollisionObject() 00042 00043 obj1.header.stamp = rospy.Time.now() 00044 obj1.header.frame_id = "base_link" 00045 obj1.id = "obj1"; 00046 obj1.operation.operation = mapping_msgs.msg.CollisionObjectOperation.ADD 00047 obj1.shapes = [Shape() for _ in range(1)] 00048 obj1.shapes[0].type = Shape.CYLINDER 00049 obj1.shapes[0].dimensions = [float() for _ in range(2)] 00050 obj1.shapes[0].dimensions[0] = .1 00051 obj1.shapes[0].dimensions[1] = 1.5 00052 obj1.poses = [Pose() for _ in range(1)] 00053 obj1.poses[0].position.x = .9 00054 obj1.poses[0].position.y = -.6 00055 obj1.poses[0].position.z = .75 00056 obj1.poses[0].orientation.x = 0 00057 obj1.poses[0].orientation.y = 0 00058 obj1.poses[0].orientation.z = 0 00059 obj1.poses[0].orientation.w = 1 00060 00061 self.obj_pub.publish(obj1) 00062 00063 rospy.sleep(5.0) 00064 00065 def tearDown(self): 00066 obj1 = CollisionObject() 00067 obj1.header.stamp = rospy.Time.now() 00068 obj1.header.frame_id = "base_link" 00069 obj1.id = "all"; 00070 obj1.operation.operation = mapping_msgs.msg.CollisionObjectOperation.REMOVE 00071 00072 #self.obj_pub.publish(obj1) 00073 00074 rospy.sleep(2.0) 00075 00076 def testMotionExecutionBuffer(self): 00077 00078 global padd_name 00079 global extra_buffer 00080 00081 #too much trouble to read for now 00082 allow_padd = .05#rospy.get_param(padd_name) 00083 00084 joint_names = ['right_arm_0_joint', 00085 'right_arm_1_joint', 00086 'right_arm_2_joint', 00087 'right_arm_3_joint', 00088 'right_arm_4_joint', 00089 'right_arm_5_joint', 00090 'right_arm_6_joint'] 00091 00092 motion_plan_request = MotionPlanRequest() 00093 00094 motion_plan_request.goal_constraints.joint_constraints = [JointConstraint() for i in range(len(joint_names))] 00095 00096 motion_plan_request.group_name = "right_arm" 00097 motion_plan_request.num_planning_attempts = 1 00098 motion_plan_request.allowed_planning_time = rospy.Duration(5.) 00099 motion_plan_request.planner_id = "" 00100 planner_service_name = "ompl_planning/plan_kinematic_path" 00101 00102 motion_plan_request.goal_constraints.joint_constraints = [JointConstraint() for i in range(len(joint_names))] 00103 for i in range(len(joint_names)): 00104 motion_plan_request.goal_constraints.joint_constraints[i].joint_name = joint_names[i] 00105 motion_plan_request.goal_constraints.joint_constraints[i].position = 0.0 00106 motion_plan_request.goal_constraints.joint_constraints[i].tolerance_above = 0.08 00107 motion_plan_request.goal_constraints.joint_constraints[i].tolerance_below = 0.08 00108 00109 motion_plan_request.goal_constraints.joint_constraints[0].position = 1.5 00110 motion_plan_request.goal_constraints.joint_constraints[1].position = -1.5 00111 motion_plan_request.goal_constraints.joint_constraints[5].position = 0.0 00112 00113 req = GetMotionPlanRequest() 00114 req.motion_plan_request = motion_plan_request 00115 00116 res = self.motion_planning_service.call(req) 00117 00118 path = DisplayTrajectory() 00119 path.model_id = "right_arm" 00120 path.trajectory.joint_trajectory = res.trajectory.joint_trajectory 00121 self.traj_pub.publish(path) 00122 00123 if __name__ == '__main__': 00124 00125 import rostest 00126 rostest.unitrun('test_motion_execution_buffer', 'test_motion_execution_buffer', TestMotionExecutionBuffer) 00127 00128 00129