reactive_grasp_executor.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 *  Copyright (c) 2009, 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 // Author(s): Kaijen Hsiao Matei Ciocarlie
00035 
00036 #include "object_manipulator/grasp_execution/reactive_grasp_executor.h"
00037 
00038 #include <object_manipulation_msgs/ReactiveGrasp.h>
00039 
00040 //#include <demo_synchronizer/synchronizer_client.h>
00041 
00042 #include "object_manipulator/tools/hand_description.h"
00043 #include "object_manipulator/tools/vector_tools.h"
00044 
00045 using object_manipulation_msgs::GraspResult;
00046 
00047 namespace object_manipulator {
00048 
00049 GraspResult 
00050 ReactiveGraspExecutor::executeGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal,
00051                                     const object_manipulation_msgs::Grasp &grasp)
00052 {
00053   //demo_synchronizer::getClient().sync(2, "Using motion planner to move arm to pre-grasp position");
00054   //demo_synchronizer::getClient().rviz(1, "Collision models;Environment contacts;Planning goal;Collision map");
00055 
00056   if ( !mechInterface().attemptMoveArmToGoal(pickup_goal.arm_name, 
00057                                              interpolated_grasp_trajectory_.points.front().positions,
00058                                              pickup_goal.additional_collision_operations,
00059                                              pickup_goal.additional_link_padding) ) 
00060   {
00061     ROS_DEBUG_NAMED("manipulation","  Grasp executor: move_arm to pre-grasp reports failure");
00062     if (marker_publisher_) marker_publisher_->colorGraspMarker(marker_id_, 1.0, 0.5, 0.0); //orange-ish
00063     return Result(GraspResult::MOVE_ARM_FAILED, true);
00064   }
00065 
00066   mechInterface().handPostureGraspAction(pickup_goal.arm_name, grasp, 
00067                                          object_manipulation_msgs::GraspHandPostureExecutionGoal::PRE_GRASP, -1);
00068   
00069   geometry_msgs::PoseStamped final_grasp_pose_stamped;
00070   final_grasp_pose_stamped.pose = grasp.grasp_pose;
00071   final_grasp_pose_stamped.header.frame_id = pickup_goal.target.reference_frame_id;
00072   final_grasp_pose_stamped.header.stamp = ros::Time(0);
00073 
00074   object_manipulation_msgs::ReactiveGraspGoal reactive_grasp_goal;
00075   reactive_grasp_goal.arm_name = pickup_goal.arm_name;
00076   reactive_grasp_goal.target = pickup_goal.target;
00077   reactive_grasp_goal.final_grasp_pose = final_grasp_pose_stamped;
00078   reactive_grasp_goal.trajectory = interpolated_grasp_trajectory_;
00079   reactive_grasp_goal.collision_support_surface_name = pickup_goal.collision_support_surface_name;
00080   reactive_grasp_goal.pre_grasp_posture = grasp.pre_grasp_posture;
00081   reactive_grasp_goal.grasp_posture = grasp.grasp_posture;
00082   reactive_grasp_goal.max_contact_force = pickup_goal.max_contact_force;
00083 
00084   //demo_synchronizer::getClient().sync(2, "Calling fingertip reactive grasping module to execute grasp");
00085   //demo_synchronizer::getClient().rviz(1, "Collision models");
00086 
00087   //give the reactive grasp 3 minutes to do its thing
00088   ros::Duration timeout = ros::Duration(180.0);
00089   mechInterface().reactive_grasp_action_client_.client(pickup_goal.arm_name).sendGoal(reactive_grasp_goal);
00090   if ( !mechInterface().reactive_grasp_action_client_.client(pickup_goal.arm_name).waitForResult(timeout) )
00091   {
00092     ROS_ERROR("  Reactive grasp timed out");
00093     return Result(GraspResult::GRASP_FAILED, false);
00094   }
00095   object_manipulation_msgs::ReactiveGraspResult reactive_grasp_result = 
00096     *mechInterface().reactive_grasp_action_client_.client(pickup_goal.arm_name).getResult();
00097   if (reactive_grasp_result.manipulation_result.value != reactive_grasp_result.manipulation_result.SUCCESS)
00098   {
00099     ROS_ERROR("Reactive grasp failed with error code %d", reactive_grasp_result.manipulation_result.value);
00100     return Result(GraspResult::GRASP_FAILED, false);
00101   }
00102   if (marker_publisher_) marker_publisher_->colorGraspMarker(marker_id_, 0.0, 1.0, 0.0); //green
00103   return Result(GraspResult::SUCCESS, true);
00104 }
00105 
00106 GraspResult 
00107 ReactiveGraspExecutor::nonReactiveLift(const object_manipulation_msgs::PickupGoal &pickup_goal)
00108 {
00109   arm_navigation_msgs::OrderedCollisionOperations ord;
00110   arm_navigation_msgs::CollisionOperation coll;
00111   coll.object1 = handDescription().gripperCollisionName(pickup_goal.arm_name);
00112   coll.operation = arm_navigation_msgs::CollisionOperation::DISABLE;
00113   //disable collisions between end-effector and table
00114   if (!pickup_goal.collision_support_surface_name.empty())
00115   {
00116     coll.object2 = pickup_goal.collision_support_surface_name;
00117     ord.collision_operations.push_back(coll);
00118   }
00119   //disable collisions between attached object and table
00120   if (!pickup_goal.collision_support_surface_name.empty() && !pickup_goal.collision_object_name.empty())
00121   {
00122     coll.object1 = pickup_goal.collision_object_name;
00123     coll.object2 = pickup_goal.collision_support_surface_name;
00124     ord.collision_operations.push_back(coll);
00125   }
00126   ord.collision_operations = concat(ord.collision_operations, 
00127                                     pickup_goal.additional_collision_operations.collision_operations);
00128 
00129   float actual_distance;
00130   if (!mechInterface().translateGripper(pickup_goal.arm_name, 
00131                                         pickup_goal.lift.direction, 
00132                                         ord, pickup_goal.additional_link_padding, 
00133                                         pickup_goal.lift.desired_distance, 0.0, actual_distance))
00134   {
00135     ROS_DEBUG_NAMED("manipulation","  Reactive grasp executor: lift performed no steps");
00136     return Result(GraspResult::LIFT_FAILED, false);
00137   }
00138   if (actual_distance < pickup_goal.lift.min_distance)
00139   {
00140     ROS_DEBUG_NAMED("manipulation","  Reactive grasp executor: lift distance below min threshold ");
00141     return Result(GraspResult::LIFT_FAILED, false);
00142   }
00143   if (actual_distance < pickup_goal.lift.desired_distance)
00144   {
00145     ROS_DEBUG_NAMED("manipulation","  Reactive grasp executor: lift distance below desired, but above min threshold");
00146   }
00147   else 
00148   {
00149     ROS_DEBUG_NAMED("manipulation","  Reactive grasp executor: desired lift distance executed");
00150   }
00151   return Result(GraspResult::SUCCESS, true);
00152 }
00153 
00154 GraspResult 
00155 ReactiveGraspExecutor::reactiveLift(const object_manipulation_msgs::PickupGoal &pickup_goal)
00156 {
00157   object_manipulation_msgs::ReactiveLiftGoal reactive_lift_goal;
00158   reactive_lift_goal.lift = pickup_goal.lift;
00159   reactive_lift_goal.arm_name = pickup_goal.arm_name;
00160   reactive_lift_goal.target = pickup_goal.target;
00161   reactive_lift_goal.trajectory = interpolated_lift_trajectory_;
00162   reactive_lift_goal.collision_support_surface_name = pickup_goal.collision_support_surface_name;
00163 
00164   //demo_synchronizer::getClient().sync(2, "Calling fingertip reactive grasping module to execute lift");
00165   //demo_synchronizer::getClient().rviz(1, "Collision models");
00166 
00167   //give the reactive lift 1 minute to do its thing
00168   ros::Duration timeout = ros::Duration(60.0);
00169   mechInterface().reactive_lift_action_client_.client(pickup_goal.arm_name).sendGoal(reactive_lift_goal);
00170   if ( !mechInterface().reactive_lift_action_client_.client(pickup_goal.arm_name).waitForResult(timeout) )
00171   {
00172     ROS_ERROR("  Reactive lift timed out");
00173     return Result(GraspResult::LIFT_FAILED, false);
00174   }
00175   object_manipulation_msgs::ReactiveLiftResult reactive_lift_result = 
00176     *mechInterface().reactive_lift_action_client_.client(pickup_goal.arm_name).getResult();
00177   if (reactive_lift_result.manipulation_result.value != reactive_lift_result.manipulation_result.SUCCESS)
00178   {
00179     ROS_ERROR("Reactive lift failed with error code %d", reactive_lift_result.manipulation_result.value);
00180     return Result(GraspResult::LIFT_FAILED, false);
00181   }
00182   return Result(GraspResult::SUCCESS, true);
00183 }
00184 
00185 GraspResult 
00186 ReactiveGraspExecutor::lift(const object_manipulation_msgs::PickupGoal &pickup_goal)
00187 {
00188   if (pickup_goal.use_reactive_lift)
00189   {
00190     return reactiveLift(pickup_goal);
00191   }
00192   else
00193   {
00194     return nonReactiveLift(pickup_goal);
00195   }
00196 }
00197 
00198 } //namespace object_manipulator


object_manipulator
Author(s): Matei Ciocarlie and Kaijen Hsiao
autogenerated on Thu Jan 2 2014 11:39:04