$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2008, Willow Garage, Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Willow Garage nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 * \author Sachin Chitta, Ioan Sucan 00036 *********************************************************************/ 00037 00038 #include <ros/ros.h> 00039 #include <tf/tf.h> 00040 #include <gtest/gtest.h> 00041 #include <boost/thread.hpp> 00042 #include <kinematics_msgs/GetPositionFK.h> 00043 #include <arm_navigation_msgs/GetMotionPlan.h> 00044 #include <arm_navigation_msgs/GetRobotState.h> 00045 00046 #include <actionlib/client/simple_action_client.h> 00047 #include <arm_navigation_msgs/MoveArmAction.h> 00048 #include <arm_navigation_msgs/Shape.h> 00049 00050 #include <arm_navigation_tests/arm_navigation_utils.h> 00051 00052 void spinThread() 00053 { 00054 ros::spin(); 00055 } 00056 00057 TEST(OMPL, PathConstraintsTest) 00058 { 00059 ros::NodeHandle nh; 00060 ros::NodeHandle private_handle("~"); 00061 boost::thread spin_thread(&spinThread); 00062 00063 actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> move_arm(nh, "move_right_arm"); 00064 move_arm.waitForServer(); 00065 ROS_INFO("Connected to server"); 00066 00067 arm_navigation_utils::ArmNavigationUtils arm_nav_utils; 00068 EXPECT_TRUE(arm_nav_utils.takeStaticMap()); 00069 00070 arm_navigation_msgs::MoveArmGoal goalA; 00071 goalA.motion_plan_request.group_name = "right_arm"; 00072 goalA.motion_plan_request.num_planning_attempts = 1; 00073 private_handle.param<std::string>("planner_id",goalA.motion_plan_request.planner_id,std::string("")); 00074 private_handle.param<std::string>("planner_service_name",goalA.planner_service_name,std::string("/ompl_planning/plan_kinematic_path")); 00075 goalA.motion_plan_request.allowed_planning_time = ros::Duration(5.0); 00076 00077 goalA.motion_plan_request.goal_constraints.position_constraints.resize(1); 00078 goalA.motion_plan_request.goal_constraints.position_constraints[0].header.stamp = ros::Time::now(); 00079 goalA.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id = "torso_lift_link"; 00080 00081 goalA.motion_plan_request.goal_constraints.position_constraints[0].link_name = "r_wrist_roll_link"; 00082 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.x = 0.75; 00083 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.y = -0.188; 00084 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.z = 0; 00085 00086 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.type = arm_navigation_msgs::Shape::BOX; 00087 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02); 00088 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02); 00089 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02); 00090 00091 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_orientation.w = 1.0; 00092 goalA.motion_plan_request.goal_constraints.position_constraints[0].weight = 1.0; 00093 00094 goalA.motion_plan_request.goal_constraints.orientation_constraints.resize(1); 00095 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.stamp = ros::Time::now(); 00096 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.frame_id = "torso_lift_link"; 00097 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].link_name = "r_wrist_roll_link"; 00098 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.x = 0.0; 00099 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.y = 0.0; 00100 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.z = 0.0; 00101 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.w = 1.0; 00102 00103 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.04; 00104 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.04; 00105 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_yaw_tolerance = 0.04; 00106 00107 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].weight = 1.0; 00108 goalA.disable_ik = true; 00109 int num_test_attempts = 0; 00110 int max_attempts = 5; 00111 bool success = false; 00112 while (nh.ok()) 00113 { 00114 bool finished_within_time = false; 00115 move_arm.sendGoal(goalA); 00116 finished_within_time = move_arm.waitForResult(ros::Duration(100.0)); 00117 actionlib::SimpleClientGoalState state = move_arm.getState(); 00118 success = (state == actionlib::SimpleClientGoalState::SUCCEEDED); 00119 if ((!finished_within_time || !success) && num_test_attempts < max_attempts) 00120 { 00121 move_arm.cancelGoal(); 00122 ROS_INFO("Timed out achieving goal A, trying again. Trying again, attempt: %d",num_test_attempts); 00123 num_test_attempts++; 00124 } 00125 else 00126 { 00127 if(!success) 00128 { 00129 ROS_INFO("Action finished: %s",state.toString().c_str()); 00130 move_arm.cancelGoal(); 00131 } 00132 ROS_INFO("Action finished: %s",state.toString().c_str()); 00133 break; 00134 } 00135 } 00136 00137 00138 00139 ROS_INFO("Connected to server"); 00140 ros::service::waitForService("ompl_planning/plan_kinematic_path"); 00141 ros::service::waitForService("pr2_right_arm_kinematics/get_fk"); 00142 ros::service::waitForService("environment_server/get_robot_state"); 00143 00144 ros::ServiceClient get_motion_plan_client_ = nh.serviceClient<arm_navigation_msgs::GetMotionPlan>("ompl_planning/plan_kinematic_path"); 00145 00146 arm_navigation_msgs::GetMotionPlan::Request request; 00147 arm_navigation_msgs::GetMotionPlan::Response response; 00148 00149 ros::ServiceClient get_state_client_ = nh.serviceClient<arm_navigation_msgs::GetRobotState>("environment_server/get_robot_state"); 00150 arm_navigation_msgs::GetRobotState::Request request_state; 00151 arm_navigation_msgs::GetRobotState::Response response_state; 00152 if(get_state_client_.call(request_state,response_state)) 00153 { 00154 request.motion_plan_request.start_state = response_state.robot_state; 00155 request.motion_plan_request.start_state.joint_state.header.frame_id = "base_footprint"; 00156 } 00157 else 00158 { 00159 ROS_ERROR("Service call to get robot state failed on %s",get_state_client_.getService().c_str()); 00160 } 00161 00162 std::vector<std::string> names(7); 00163 names[0] = "r_shoulder_pan_joint"; 00164 names[1] = "r_shoulder_lift_joint"; 00165 names[2] = "r_upper_arm_roll_joint"; 00166 names[3] = "r_elbow_flex_joint"; 00167 names[4] = "r_forearm_roll_joint"; 00168 names[5] = "r_wrist_flex_joint"; 00169 names[6] = "r_wrist_roll_joint"; 00170 00171 request.motion_plan_request.group_name = "right_arm"; 00172 request.motion_plan_request.num_planning_attempts = 1; 00173 request.motion_plan_request.allowed_planning_time = ros::Duration(5.0); 00174 request.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp = ros::Time::now(); 00175 00176 private_handle.param<std::string>("planner_id",request.motion_plan_request.planner_id,std::string("")); 00177 request.motion_plan_request.goal_constraints.joint_constraints.resize(names.size()); 00178 00179 for (unsigned int i = 0 ; i < request.motion_plan_request.goal_constraints.joint_constraints.size(); ++i) 00180 { 00181 request.motion_plan_request.goal_constraints.joint_constraints[i].joint_name = names[i]; 00182 request.motion_plan_request.goal_constraints.joint_constraints[i].position = 0.0; 00183 request.motion_plan_request.goal_constraints.joint_constraints[i].tolerance_below = 0.1; 00184 request.motion_plan_request.goal_constraints.joint_constraints[i].tolerance_above = 0.1; 00185 } 00186 00187 request.motion_plan_request.goal_constraints.joint_constraints[0].position = -2.0; 00188 request.motion_plan_request.goal_constraints.joint_constraints[3].position = -0.2; 00189 request.motion_plan_request.goal_constraints.joint_constraints[5].position = -0.2; 00190 00191 request.motion_plan_request.path_constraints.orientation_constraints.resize(1); 00192 request.motion_plan_request.path_constraints.orientation_constraints[0].header.frame_id = "torso_lift_link"; 00193 request.motion_plan_request.path_constraints.orientation_constraints[0].header.stamp = ros::Time::now(); 00194 request.motion_plan_request.path_constraints.orientation_constraints[0].link_name = "r_wrist_roll_link"; 00195 00196 request.motion_plan_request.path_constraints.orientation_constraints[0].orientation.x = -0.167; 00197 request.motion_plan_request.path_constraints.orientation_constraints[0].orientation.y = -0.107; 00198 request.motion_plan_request.path_constraints.orientation_constraints[0].orientation.z = -0.825; 00199 request.motion_plan_request.path_constraints.orientation_constraints[0].orientation.w = 0.530; 00200 00201 request.motion_plan_request.path_constraints.orientation_constraints[0].type = arm_navigation_msgs::OrientationConstraint::HEADER_FRAME; 00202 request.motion_plan_request.path_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.5; 00203 request.motion_plan_request.path_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.5; 00204 request.motion_plan_request.path_constraints.orientation_constraints[0].absolute_yaw_tolerance = M_PI; 00205 00206 EXPECT_TRUE(get_motion_plan_client_.call(request,response)); 00207 EXPECT_TRUE(!response.trajectory.joint_trajectory.points.empty()); 00208 ROS_INFO("Output path has %d points",(int) response.trajectory.joint_trajectory.points.size()); 00209 ros::ServiceClient fk_client = nh.serviceClient<kinematics_msgs::GetPositionFK>("pr2_right_arm_kinematics/get_fk"); 00210 00211 kinematics_msgs::GetPositionFK::Request fk_request; 00212 kinematics_msgs::GetPositionFK::Response fk_response; 00213 fk_request.header.frame_id = "base_link"; 00214 fk_request.fk_link_names.resize(1); 00215 fk_request.fk_link_names[0] = "r_wrist_roll_link"; 00216 fk_request.robot_state.joint_state.position.resize(names.size()); 00217 fk_request.robot_state.joint_state.name = names; 00218 00219 btQuaternion constraint_orientation_quaternion; 00220 tf::quaternionMsgToTF(request.motion_plan_request.path_constraints.orientation_constraints[0].orientation,constraint_orientation_quaternion); 00221 btMatrix3x3 constraint_orientation = btMatrix3x3(constraint_orientation_quaternion); 00222 00223 00224 // Now, check the returned trajectory to make sure it satisfies the constraints 00225 for(unsigned int i=0; i < response.trajectory.joint_trajectory.points.size(); i++) 00226 { 00227 fk_request.robot_state.joint_state.position = response.trajectory.joint_trajectory.points[i].positions; 00228 EXPECT_TRUE(fk_client.call(fk_request, fk_response)); 00229 00230 btQuaternion actual_orientation_quaternion; 00231 tf::quaternionMsgToTF(fk_response.pose_stamped[0].pose.orientation,actual_orientation_quaternion); 00232 btMatrix3x3 actual_orientation = btMatrix3x3(actual_orientation_quaternion); 00233 btMatrix3x3 result = actual_orientation * constraint_orientation.inverse(); 00234 00235 double roll, pitch, yaw; 00236 result.getRPY(roll, pitch, yaw); 00237 00238 EXPECT_TRUE(abs(roll) < request.motion_plan_request.path_constraints.orientation_constraints[0].absolute_roll_tolerance); 00239 EXPECT_TRUE(abs(pitch) < request.motion_plan_request.path_constraints.orientation_constraints[0].absolute_pitch_tolerance); 00240 EXPECT_TRUE(abs(yaw) < request.motion_plan_request.path_constraints.orientation_constraints[0].absolute_yaw_tolerance); 00241 00242 } 00243 ros::shutdown(); 00244 spin_thread.join(); 00245 } 00246 00247 int main(int argc, char **argv){ 00248 testing::InitGoogleTest(&argc, argv); 00249 ros::init(argc,argv,"path_constraints_test"); 00250 return RUN_ALL_TESTS(); 00251 }