00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, 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 Willow Garage, Inc. 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 * $Id: pfh.cpp 35810 2011-02-08 00:03:46Z rusu $ 00035 * 00036 */ 00037 00038 #include "pcl/point_types.h" 00039 #include "pcl/impl/instantiate.hpp" 00040 #include "pcl/features/pfh.h" 00041 #include "pcl/features/impl/pfh.hpp" 00042 00044 bool 00045 pcl::computePairFeatures (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, 00046 const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, 00047 float &f1, float &f2, float &f3, float &f4) 00048 { 00049 // Compute the Cartesian difference between the two points 00050 Eigen::Vector4f delta = p2 - p1; 00051 delta[3] = 0; 00052 00053 // Compute the Euclidean norm = || p_idx - q_idx || 00054 float distance_sqr = delta.squaredNorm (); 00055 00056 if (distance_sqr == 0) 00057 { 00058 ROS_ERROR ("Euclidean distance between points is 0!"); 00059 f1 = f2 = f3 = f4 = 0; 00060 return (false); 00061 } 00062 00063 // Estimate f4 = || delta || 00064 f4 = sqrt (distance_sqr); 00065 00066 // Create a Darboux frame coordinate system u-v-w 00067 // u = n1; v = (p_idx - q_idx) x u / || (p_idx - q_idx) x u ||; w = u x v 00068 00069 // Estimate f3 = u * delta / || delta || 00070 // delta[3] = 0 (line 59) 00071 f3 = n1.dot (delta) / f4; 00072 00073 // v = delta * u 00074 Eigen::Vector4f v = Eigen::Vector4f::Zero (); 00075 v = delta.cross3 (n1); 00076 00077 distance_sqr = v.squaredNorm (); 00078 if (distance_sqr == 0) 00079 { 00080 ROS_ERROR ("Norm of Delta x U is 0!"); 00081 f1 = f2 = f3 = f4 = 0; 00082 return (false); 00083 } 00084 00085 // Copy the q_idx normal 00086 Eigen::Vector4f nq = n2; 00087 nq[3] = 0; 00088 00089 // Normalize the vector 00090 v /= sqrt (distance_sqr); 00091 00092 // Compute delta (w) = u x v 00093 delta = n1.cross3 (v); 00094 00095 // Compute f2 = v * n2; 00096 // v[3] = 0 (line 82) 00097 f2 = v.dot (nq); 00098 00099 // Compute f1 = arctan (w * n2, u * n2) i.e. angle of n2 in the x=u, y=w coordinate system 00100 // delta[3] = 0 (line 59), nq[3] = 0 (line 97) 00101 f1 = atan2f (delta.dot (nq), n1.dot (nq)); // @todo: optimize this 00102 00103 return (true); 00104 } 00105 00106 // Instantiations of specific point types 00107 PCL_INSTANTIATE_PRODUCT(PFHEstimation, (PCL_XYZ_POINT_TYPES)(PCL_NORMAL_POINT_TYPES)((pcl::PFHSignature125))); 00108