$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 #ifndef GRASP_EVALUATOR_H 00036 #define GRASP_EVALUATOR_H 00037 00038 #include <boost/shared_ptr.hpp> 00039 00040 #include <ros/ros.h> 00041 00042 #include <object_manipulation_msgs/GraspableObject.h> 00043 #include <object_manipulation_msgs/Grasp.h> 00044 00045 #include "bayesian_grasp_planner/probability_distribution.h" 00046 #include "bayesian_grasp_planner/bayesian_grasp_planner_tools.h" 00047 00048 namespace bayesian_grasp_planner { 00049 00050 class GraspGenerator; 00051 //class GraspWM; 00052 00053 class RawGraspEvaluator 00054 { 00055 protected: 00056 bool object_dependent_; //whether this evaluator cares about the 'correct' object representation 00057 00058 public: 00060 virtual double evaluate(const GraspWM &grasp, 00061 const object_manipulation_msgs::GraspableObject &object) const = 0; 00062 00064 virtual void evaluate_list(std::vector<GraspWM> &grasps, 00065 const object_manipulation_msgs::GraspableObject &object, 00066 std::vector<double> &values) 00067 { 00068 values.clear(); 00069 values.resize(grasps.size()); 00070 for (size_t grasp_ind = 0; grasp_ind < grasps.size(); grasp_ind++) 00071 { 00072 values[grasp_ind] = evaluate(grasps[grasp_ind], object); 00073 } 00074 } 00075 00077 bool is_object_dependent() 00078 { 00079 return object_dependent_; 00080 } 00081 00082 }; 00083 00084 class MultiplexEvaluator : public RawGraspEvaluator 00085 { 00086 private: 00087 std::map<int, boost::shared_ptr<RawGraspEvaluator> > eval_map_; 00088 public: 00089 MultiplexEvaluator() 00090 { 00091 object_dependent_ = true; 00092 } 00093 00094 void addEvaluator(boost::shared_ptr<RawGraspEvaluator> eval, int id) 00095 { 00096 eval_map_.insert( std::pair<int, boost::shared_ptr<RawGraspEvaluator> >(id, eval) ); 00097 } 00098 00099 double evaluate(const GraspWM &grasp, 00100 const object_manipulation_msgs::GraspableObject &object) const 00101 { 00102 int id = 0; 00103 if (object.potential_models.empty()) id = -1; //non-database object case 00104 else id = object.potential_models[0].model_id; 00105 std::map< int, boost::shared_ptr<RawGraspEvaluator> > ::const_iterator it = eval_map_.find(id); 00106 //todo: throw exception 00107 if (it == eval_map_.end()) return 0; 00108 return it->second->evaluate(grasp, object); 00109 } 00110 00111 void evaluate_list(std::vector<GraspWM> &grasps, 00112 const object_manipulation_msgs::GraspableObject &object, 00113 std::vector<double> &values) 00114 { 00115 int id = 0; 00116 if (object.potential_models.empty()) id = -1; //non-database object case 00117 else id = object.potential_models[0].model_id; 00118 std::map< int, boost::shared_ptr<RawGraspEvaluator> > ::const_iterator it = eval_map_.find(id); 00119 //todo: throw exception 00120 if (it == eval_map_.end()) 00121 { 00122 values.clear(); 00123 values.resize(grasps.size(), 0); 00124 ROS_ERROR("object %d not found in grasp evaluator map!", id); 00125 return; 00126 } 00127 it->second->evaluate_list(grasps, object, values); 00128 } 00129 }; 00130 00131 class RawGraspEvaluatorWithRegression : public RawGraspEvaluator 00132 { 00133 private: 00134 boost::shared_ptr<GraspGenerator> generator_; 00135 00136 public: 00137 RawGraspEvaluatorWithRegression (boost::shared_ptr<GraspGenerator> generator, bool object_dependent) : 00138 generator_(generator) 00139 { 00140 object_dependent_ = object_dependent; 00141 } 00142 00143 double evaluate(const GraspWM &grasp, 00144 const object_manipulation_msgs::GraspableObject &object) const; 00145 }; 00146 00147 class RawGraspEvaluatorServiceCaller : public RawGraspEvaluator 00148 { 00149 private: 00150 // calling a service is non-const, hence the mutable 00151 mutable ros::ServiceClient service_; 00152 std::string service_name_; 00153 public: 00154 RawGraspEvaluatorServiceCaller(ros::NodeHandle &nh, std::string service_name, bool object_dependent); 00155 00156 double evaluate(const GraspWM &grasp, 00157 const object_manipulation_msgs::GraspableObject &object) const; 00158 00159 void evaluate_list(std::vector<GraspWM> &grasps, 00160 const object_manipulation_msgs::GraspableObject &object, 00161 std::vector<double> &values); 00162 }; 00163 00164 00165 00166 class GraspEvaluatorProb 00167 { 00168 private: 00169 boost::shared_ptr<ProbabilityDistribution> success_distribution_; 00170 boost::shared_ptr<ProbabilityDistribution> failure_distribution_; 00171 boost::shared_ptr<RawGraspEvaluator> evaluator_; 00172 00173 public: 00174 GraspEvaluatorProb( boost::shared_ptr<ProbabilityDistribution> success_distribution, 00175 boost::shared_ptr<ProbabilityDistribution> failure_distribution, 00176 boost::shared_ptr<RawGraspEvaluator> evaluator ) : 00177 success_distribution_(success_distribution), 00178 failure_distribution_(failure_distribution), 00179 evaluator_(evaluator) {} 00180 00182 bool is_object_dependent() 00183 { 00184 return evaluator_->is_object_dependent(); 00185 } 00186 00188 void getProbabilitiesForGrasp(const GraspWM &grasp, 00189 const object_manipulation_msgs::GraspableObject &object, double &success_prob, double &failure_prob) const 00190 { 00191 double raw_score = evaluator_->evaluate(grasp, object); 00192 success_prob = success_distribution_->evaluate(raw_score); 00193 failure_prob = failure_distribution_->evaluate(raw_score); 00194 } 00195 00197 void getProbabilitiesForGraspList(std::vector<GraspWM> &grasps, 00198 const object_manipulation_msgs::GraspableObject &object, 00199 std::vector<double> &success_probs, std::vector<double> &failure_probs) const 00200 { 00201 success_probs.clear(); 00202 failure_probs.clear(); 00203 success_probs.resize(grasps.size()); 00204 failure_probs.resize(grasps.size()); 00205 std::vector<double> raw_scores; 00206 evaluator_->evaluate_list(grasps, object, raw_scores); 00207 for (size_t grasp_ind = 0; grasp_ind < grasps.size(); grasp_ind++) 00208 { 00209 success_probs[grasp_ind] = success_distribution_->evaluate(raw_scores[grasp_ind]); 00210 failure_probs[grasp_ind] = failure_distribution_->evaluate(raw_scores[grasp_ind]); 00211 } 00212 } 00213 }; 00214 00215 00216 00217 } 00218 00219 00220 #endif