grasp_executor.h
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): Matei Ciocarlie
00035 
00036 #ifndef _GRASP_EXECUTOR_H_
00037 #define _GRASP_EXECUTOR_H_
00038 
00039 #include <ros/ros.h>
00040 
00041 #include "object_manipulation_msgs/GraspResult.h"
00042 #include "object_manipulation_msgs/PickupGoal.h"
00043 
00044 #include "object_manipulator/tools/mechanism_interface.h"
00045 #include "object_manipulator/tools/grasp_marker_publisher.h"
00046 
00047 namespace object_manipulator {
00048 
00050 
00053 class GraspExecutor
00054 {
00055  public:
00056   object_manipulation_msgs::GraspResult Result(int result_code, bool continuation)
00057   {
00058     object_manipulation_msgs::GraspResult result;
00059     result.result_code = result_code;
00060     result.continuation_possible = continuation;
00061     return result;
00062   }
00063   
00064  protected:
00065 
00067   GraspMarkerPublisher *marker_publisher_;
00068 
00070   unsigned int marker_id_;
00071 
00073   trajectory_msgs::JointTrajectory interpolated_lift_trajectory_; 
00074 
00076   object_manipulation_msgs::GraspResult 
00077     getInterpolatedIKForLift(const object_manipulation_msgs::PickupGoal &pickup_goal,
00078                              const object_manipulation_msgs::Grasp &grasp,
00079                              const std::vector<double> &grasp_joint_angles,
00080                              trajectory_msgs::JointTrajectory &lift_trajectory);
00081 
00083   arm_navigation_msgs::OrderedCollisionOperations 
00084     collisionOperationsForLift(const object_manipulation_msgs::PickupGoal &pickup_goal);
00085 
00087   std::vector<arm_navigation_msgs::LinkPadding> 
00088     linkPaddingForLift(const object_manipulation_msgs::PickupGoal &pickup_goal);
00089 
00091   std::vector<arm_navigation_msgs::LinkPadding> 
00092     fingertipPadding(const object_manipulation_msgs::PickupGoal &pickup_goal, double pad);
00093 
00095   virtual object_manipulation_msgs::GraspResult 
00096     prepareGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal,
00097                  const object_manipulation_msgs::Grasp &grasp) = 0;
00098 
00100 
00101   virtual object_manipulation_msgs::GraspResult
00102     executeGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal,
00103                  const object_manipulation_msgs::Grasp &grasp) = 0;
00104 
00105  public:
00106 
00108   GraspExecutor(GraspMarkerPublisher *pub) : marker_publisher_(pub)
00109   {}
00110   virtual ~GraspExecutor() {}
00111   
00113   /* Returns SUCCESS if the grasp was successfully executed, UNFEASIBLE if it fails without
00114      affecting the environment (generally during move_arm stages) or FAILED if it fails and might
00115      have affected the object (generally during the final grasp stage).
00116   
00117    Calls prepareGrasp(), and if prepareGrasp() returns true, it calls executeGrasp() and returns its result.
00118   */  
00119   object_manipulation_msgs::GraspResult 
00120     checkAndExecuteGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal,
00121                          const object_manipulation_msgs::Grasp &grasp);
00122   
00124 
00127   virtual object_manipulation_msgs::GraspResult 
00128   retreat(const object_manipulation_msgs::PickupGoal &pickup_goal, const object_manipulation_msgs::Grasp &grasp)
00129   {
00130     ROS_WARN("This grasp executor has no retreat capability");
00131     return Result(object_manipulation_msgs::GraspResult::RETREAT_FAILED, false);
00132   }
00133 
00135 
00140   virtual object_manipulation_msgs::GraspResult lift(const object_manipulation_msgs::PickupGoal &pickup_goal);
00141 };
00142 
00143 } //namespace grasp_execution
00144 
00145 #endif


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