$search
00001 /********************************************************************* 00002 * 00003 * Copyright (c) 2011, Willow Garage, Inc. 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 00008 * are met: 00009 * 00010 * * Redistributions of source code must retain the above copyright 00011 * notice, this list of conditions and the following disclaimer. 00012 * * Redistributions in binary form must reproduce the above 00013 * copyright notice, this list of conditions and the following 00014 * disclaimer in the documentation and/or other materials provided 00015 * with the distribution. 00016 * * Neither the name of the Willow Garage nor the names of its 00017 * contributors may be used to endorse or promote products derived 00018 * from this software without specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 * POSSIBILITY OF SUCH DAMAGE. 00032 *********************************************************************/ 00033 00034 #include "object_manipulator/grasp_execution/unsafe_grasp_executor.h" 00035 #include "object_manipulator/tools/hand_description.h" 00036 #include "object_manipulator/tools/vector_tools.h" 00037 #include "object_manipulator/tools/mechanism_interface.h" 00038 00039 using object_manipulation_msgs::GraspResult; 00040 00041 namespace object_manipulator { 00042 00043 GraspResult 00044 UnsafeGraspExecutor::executeGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal, 00045 const object_manipulation_msgs::Grasp &grasp) 00046 { 00047 ROS_INFO("executing unsafe grasp"); 00048 00049 //compute the pre-grasp pose 00050 //get the grasp pose in the right frame 00051 geometry_msgs::PoseStamped grasp_pose_stamped; 00052 grasp_pose_stamped.pose = grasp.grasp_pose; 00053 grasp_pose_stamped.header.frame_id = pickup_goal.target.reference_frame_id; 00054 grasp_pose_stamped.header.stamp = ros::Time(0); 00055 00056 //use the opposite of the approach direction as we are going backwards, from grasp to pre-grasp 00057 geometry_msgs::Vector3Stamped direction; 00058 direction.header.stamp = ros::Time::now(); 00059 direction.header.frame_id = handDescription().gripperFrame(pickup_goal.arm_name); 00060 direction.vector = mechInterface().negate( handDescription().approachDirection(pickup_goal.arm_name) ); 00061 00062 //make sure the input is normalized 00063 geometry_msgs::Vector3Stamped direction_norm = direction; 00064 direction_norm.vector = mechInterface().normalize(direction.vector); 00065 00066 //multiply the approach direction by the desired length and translate the grasp pose back along it 00067 double desired_trajectory_length = fabs(grasp.desired_approach_distance); 00068 direction_norm.vector.x *= desired_trajectory_length; 00069 direction_norm.vector.y *= desired_trajectory_length; 00070 direction_norm.vector.z *= desired_trajectory_length; 00071 geometry_msgs::PoseStamped pregrasp_pose = mechInterface().translateGripperPose(direction_norm, grasp_pose_stamped, pickup_goal.arm_name); 00072 00073 //move to the pre-grasp using the Cartesian controller 00074 mechInterface().moveArmToPoseCartesian(pickup_goal.arm_name, pregrasp_pose, ros::Duration(15.0), 00075 .0015, .01, 0.02, 0.16, 0.005, 0.087, 0.1, 00076 interpolated_grasp_trajectory_.points[interpolated_grasp_trajectory_.points.size()-1].positions); 00077 00078 //move to the pre-grasp hand posture 00079 mechInterface().handPostureGraspAction(pickup_goal.arm_name, grasp, 00080 object_manipulation_msgs::GraspHandPostureExecutionGoal::PRE_GRASP, -1); 00081 00082 //if not using reactive grasping, execute the unnormalized interpolated trajectory from pre-grasp to grasp 00083 if(!pickup_goal.use_reactive_execution) 00084 { 00085 mechInterface().attemptTrajectory(pickup_goal.arm_name, interpolated_grasp_trajectory_, true); 00086 mechInterface().handPostureGraspAction(pickup_goal.arm_name, grasp, 00087 object_manipulation_msgs::GraspHandPostureExecutionGoal::GRASP, pickup_goal.max_contact_force); 00088 } 00089 00090 //otherwise, call reactive grasping 00091 else 00092 { 00093 geometry_msgs::PoseStamped final_grasp_pose_stamped; 00094 final_grasp_pose_stamped.pose = grasp.grasp_pose; 00095 final_grasp_pose_stamped.header.frame_id = pickup_goal.target.reference_frame_id; 00096 final_grasp_pose_stamped.header.stamp = ros::Time(0); 00097 00098 object_manipulation_msgs::ReactiveGraspGoal reactive_grasp_goal; 00099 reactive_grasp_goal.arm_name = pickup_goal.arm_name; 00100 reactive_grasp_goal.target = pickup_goal.target; 00101 reactive_grasp_goal.final_grasp_pose = final_grasp_pose_stamped; 00102 reactive_grasp_goal.trajectory = interpolated_grasp_trajectory_; 00103 reactive_grasp_goal.collision_support_surface_name = pickup_goal.collision_support_surface_name; 00104 reactive_grasp_goal.pre_grasp_posture = grasp.pre_grasp_posture; 00105 reactive_grasp_goal.grasp_posture = grasp.grasp_posture; 00106 00107 //give the reactive grasp 3 minutes to do its thing 00108 ros::Duration timeout = ros::Duration(180.0); 00109 mechInterface().reactive_grasp_action_client_.client(pickup_goal.arm_name).sendGoal(reactive_grasp_goal); 00110 if ( !mechInterface().reactive_grasp_action_client_.client(pickup_goal.arm_name).waitForResult(timeout) ) 00111 { 00112 ROS_ERROR(" Reactive grasp timed out"); 00113 return Result(GraspResult::GRASP_FAILED, false); 00114 } 00115 object_manipulation_msgs::ReactiveGraspResult reactive_grasp_result = 00116 *mechInterface().reactive_grasp_action_client_.client(pickup_goal.arm_name).getResult(); 00117 if (reactive_grasp_result.manipulation_result.value != reactive_grasp_result.manipulation_result.SUCCESS) 00118 { 00119 ROS_ERROR("Reactive grasp failed with error code %d", reactive_grasp_result.manipulation_result.value); 00120 return Result(GraspResult::GRASP_FAILED, false); 00121 } 00122 } 00123 00124 if (marker_publisher_) marker_publisher_->colorGraspMarker(marker_id_, 0.0, 1.0, 0.0); //green 00125 return Result(GraspResult::SUCCESS, true); 00126 } 00127 00128 00130 arm_navigation_msgs::OrderedCollisionOperations 00131 UnsafeGraspExecutor::collisionOperationsForGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal) 00132 { 00133 arm_navigation_msgs::OrderedCollisionOperations ord; 00134 arm_navigation_msgs::CollisionOperation coll; 00135 coll.object1 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00136 coll.object2 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00137 coll.operation = arm_navigation_msgs::CollisionOperation::DISABLE; 00138 ord.collision_operations.push_back(coll); 00139 ord.collision_operations = concat(ord.collision_operations, 00140 pickup_goal.additional_collision_operations.collision_operations); 00141 return ord; 00142 } 00143 00145 arm_navigation_msgs::OrderedCollisionOperations 00146 UnsafeGraspExecutor::collisionOperationsForLift(const object_manipulation_msgs::PickupGoal &pickup_goal) 00147 { 00148 arm_navigation_msgs::OrderedCollisionOperations ord; 00149 arm_navigation_msgs::CollisionOperation coll; 00150 coll.object1 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00151 coll.object2 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00152 coll.operation = arm_navigation_msgs::CollisionOperation::DISABLE; 00153 ord.collision_operations.push_back(coll); 00154 ord.collision_operations = concat(ord.collision_operations, 00155 pickup_goal.additional_collision_operations.collision_operations); 00156 return ord; 00157 } 00158 00159 } //namespace object_manipulator