$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 // Author(s): Peter Brook 00036 00037 #include <tf/transform_datatypes.h> 00038 00039 //#define PROF_ENABLED 00040 //#include <profiling/profiling.h> 00041 00042 #include <Eigen/Core> 00043 // For inverse 00044 #include <Eigen/LU> 00045 00046 #include "probabilistic_grasp_planner/probabilistic_planner_tools.h" 00047 #include "probabilistic_grasp_planner/distribution_evaluator.h" 00048 00049 using namespace Eigen; 00050 00051 namespace probabilistic_grasp_planner { 00052 00056 double NormalDistributionEvaluator::evaluate_position(const GraspWithMetadata &gstar,const GraspWithMetadata &grasp) 00057 { 00058 00059 Vector3d mean(gstar.tool_point_pose_.getOrigin().m_floats); 00060 Vector3d x(grasp.tool_point_pose_.getOrigin().m_floats); 00061 Vector3d delta(x-mean); 00062 Matrix3d covariance = Matrix3d::Zero(); 00063 covariance(0,0) = covariance(1,1) = covariance(2,2) = pow(position_sigma_,2); 00064 00065 double ex = exp(-0.5*(delta.transpose() * covariance.inverse() * delta)(0,0)); 00066 //double coeff = 1.0/(pow(M_2_PI, 1.5)*pow(covariance.determinant(),0.5)); gets normalized out anyway 00067 return ex; 00068 } 00069 00073 double NormalDistributionEvaluator::evaluate_orientation(const GraspWithMetadata &gstar,const GraspWithMetadata &grasp) 00074 { 00075 double cos_angle = gstar.tool_point_pose_.getRotation().dot(grasp.tool_point_pose_.getRotation()); 00076 double ex = exp(orientation_concentration_ * pow(cos_angle,2)); 00077 double normalization = exp(orientation_concentration_); 00078 return ex / normalization; 00079 } 00080 00081 double NormalDistributionEvaluator::evaluate(const GraspWithMetadata &gstar,const GraspWithMetadata &grasp) 00082 { 00083 double value =evaluate_position(gstar, grasp)*evaluate_orientation(gstar, grasp); 00084 normalization_term_ += value; 00085 return value; 00086 } 00087 00088 double PolarNormalDistributionEvaluator::evaluate(const GraspWithMetadata &gstar,const GraspWithMetadata &grasp) 00089 { 00090 double m_r = 0.0; 00091 double position_stddev = 0.01; //1cm stddev 00092 double m_theta = 0.0; 00093 double orientation_stddev = 0.174; // 10 degrees stddev 00094 00095 /* 00096 * Compute "probability" (actually likelihood or probability density) of getting this grasp given that gstar was 00097 * commanded. 00098 * 00099 * The this value is the product of the likelihood for the positioning error and the likelihood for the 00100 * orientation error. 00101 */ 00102 00103 double cartesian_distance = 0; 00104 double rotation_distance = 0; 00105 gstar.getDistance(grasp,cartesian_distance, rotation_distance); 00106 00107 double p_position = exp(-pow((cartesian_distance-m_r),2)/(2*pow(position_stddev,2))); 00108 00109 double p_orientation = exp(-pow((rotation_distance-m_theta),2)/(2*pow(orientation_stddev,2))); 00110 00111 double pose_probability = p_position*p_orientation; 00112 00113 normalization_term_ += pose_probability; 00114 return pose_probability; 00115 } 00116 00117 } // namespace