grasp_regression_evaluator.cpp
Go to the documentation of this file.
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 // Author(s): Peter Brook
00036 
00037 #include <boost/foreach.hpp>
00038 
00039 #include "probabilistic_grasp_planner/distribution_evaluator.h"
00040 #include "probabilistic_grasp_planner/probabilistic_planner_tools.h"
00041 #include "probabilistic_grasp_planner/grasp_success_probability_computer.h"
00042 #include "probabilistic_grasp_planner/grasp_regression_evaluator.h"
00043 
00044 namespace probabilistic_grasp_planner {
00045 
00046 double GraspRegressionEvaluator::estimateProbability(const GraspWithMetadata &grasp) const
00047 {
00048   NormalDistributionEvaluator evaluator(position_bandwidth_, orientation_bandwidth_);
00049   evaluator.reset_normalization_term();
00050 
00051   double probability = 0.0;
00052 
00053   const GraspWithMetadata* closest_grasp = NULL;
00054   double closest_dist = 0.0;
00055 
00056   double cartesian_dist, rotation_dist;
00057 
00058   BOOST_FOREACH(const GraspWithMetadata &grasp_for_object, grasps_)
00059   {
00060     // Find closest grasp
00061     if (closest_grasp==NULL)
00062     {
00063       closest_grasp = &grasp_for_object;
00064 
00065       grasp.getDistance(grasp_for_object, cartesian_dist, rotation_dist);
00066 
00067       closest_dist = sqrt(pow(position_bandwidth_*cartesian_dist,2) +
00068                           pow(orientation_bandwidth_*rotation_dist,2));
00069     }
00070 
00071     grasp.getDistance(grasp_for_object, cartesian_dist, rotation_dist);
00072 
00073     double this_dist = sqrt(pow(position_bandwidth_*cartesian_dist,2) +
00074                             pow(orientation_bandwidth_*rotation_dist,2));
00075 
00076     if (this_dist < closest_dist)
00077     {
00078       closest_grasp = &grasp_for_object;
00079       closest_dist = this_dist;
00080     }
00081 
00082     //Add the weighted contribution from grasp_for_object to grasp's probability
00083     double p_dens = evaluator.evaluate(grasp_for_object, grasp);
00084     double grasp_probability = simple_computer_->getProbability(grasp_for_object);
00085     probability += p_dens*grasp_probability;
00086   }
00087 
00088   // If this is false, then all of the probabilities are zero so we should return that directly
00089   if (evaluator.get_normalization_term() != 0.0)
00090   {
00091     probability /= evaluator.get_normalization_term();
00092 
00093     double p_dens = evaluator.evaluate(*closest_grasp, grasp);
00094     double grasp_probability = simple_computer_->getProbability(*closest_grasp);
00095     double probability_from_closest_grasp = p_dens*grasp_probability;
00096 
00097     return std::min(probability, probability_from_closest_grasp);
00098   }
00099   else {
00100     return 0.0;
00101   }
00102 }
00103 
00104 } // end namespace


probabilistic_grasp_planner
Author(s): Peter Brook
autogenerated on Thu Jan 2 2014 11:41:15