norms.hpp
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 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  */
00035 
00036 #include <pcl/pcl_macros.h>
00037 
00038 namespace pcl
00039 {
00040 
00041 template <typename FloatVectorT> inline float
00042 selectNorm (FloatVectorT a, FloatVectorT b, int dim, NormType norm_type)
00043 {
00044   // {L1, L2_SQR, L2, LINF, JM, B, SUBLINEAR, CS, DIV, PF, K, KL, HIK};
00045   switch (norm_type)
00046   {
00047     case (L1):
00048         return L1_Norm (a, b, dim);
00049     case (L2_SQR):
00050         return L2_Norm_SQR (a, b, dim);
00051     case (L2):
00052         return L2_Norm  (a, b, dim);
00053     case (LINF):
00054         return Linf_Norm (a, b, dim);
00055     case (JM):
00056         return JM_Norm  (a, b, dim);
00057     case (B):
00058         return B_Norm  (a, b, dim);
00059     case (SUBLINEAR):
00060         return Sublinear_Norm (a, b, dim);
00061     case (CS):
00062         return CS_Norm (a, b, dim);
00063     case (DIV):
00064         return Div_Norm (a, b, dim);
00065     case (KL):
00066         return KL_Norm (a, b, dim);
00067     case (HIK):
00068         return HIK_Norm (a, b, dim);
00069 
00070     case (PF):
00071     case (K):
00072     default:
00073       PCL_ERROR ("[pcl::selectNorm] For PF and K norms you have to explicitly call the method, as they need additional parameters\n");
00074       return -1;
00075   }
00076 }
00077 
00078 
00079 template <typename FloatVectorT> inline float
00080 L1_Norm (FloatVectorT a, FloatVectorT b, int dim)
00081 {
00082   float norm = 0.0f;
00083   for (int i = 0; i < dim; ++i)
00084     norm += fabsf(a[i] - b[i]);
00085   return norm;
00086 }
00087 
00088 
00089 template <typename FloatVectorT> inline float
00090 L2_Norm_SQR (FloatVectorT a, FloatVectorT b, int dim)
00091 {
00092   float norm = 0.0;
00093   for (int i = 0; i < dim; ++i)
00094   {
00095     float diff  =  a[i] - b[i];
00096     norm += diff*diff;
00097   }
00098   return norm;
00099 }
00100 
00101 
00102 template <typename FloatVectorT> inline float
00103 L2_Norm (FloatVectorT a, FloatVectorT b, int dim)
00104 {
00105   return sqrtf(L2_Norm_SQR(a, b, dim));
00106 }
00107 
00108 
00109 template <typename FloatVectorT> inline float
00110 Linf_Norm (FloatVectorT a, FloatVectorT b, int dim)
00111 {
00112   float norm = 0.0;
00113   for (int i = 0; i < dim; ++i)
00114     norm = (std::max)(fabsf(a[i] - b[i]), norm);
00115   return norm;
00116 }
00117 
00118 
00119 template <typename FloatVectorT> inline float
00120 JM_Norm (FloatVectorT a, FloatVectorT b, int dim)
00121 {
00122   float norm = 0.0;
00123 
00124   for (int i = 0; i < dim; ++i)
00125     norm += (sqrtf (a[i]) - sqrtf (b[i])) * (sqrtf (a[i]) - sqrtf (b[i]));
00126 
00127   return sqrtf (norm);
00128 }
00129 
00130 
00131 template <typename FloatVectorT> inline float
00132 B_Norm (FloatVectorT a, FloatVectorT b, int dim)
00133 {
00134   float norm = 0.0, result;
00135 
00136   for (int i = 0; i < dim; ++i)
00137     norm += sqrtf (a[i] * b[i]);
00138 
00139   if (norm > 0)
00140     result = -logf (norm);
00141   else
00142     result = 0;
00143 
00144   return result;
00145 }
00146 
00147 
00148 template <typename FloatVectorT> inline float
00149 Sublinear_Norm (FloatVectorT a, FloatVectorT b, int dim)
00150 {
00151   float norm = 0.0;
00152 
00153   for (int i = 0; i < dim; ++i)
00154     norm += sqrtf (fabsf (a[i] - b[i]));
00155 
00156   return norm;
00157 }
00158 
00159 
00160 template <typename FloatVectorT> inline float
00161 CS_Norm (FloatVectorT a, FloatVectorT b, int dim)
00162 {
00163   float norm = 0.0;
00164 
00165   for (int i = 0; i < dim; ++i)
00166     if ((a[i] + b[i]) != 0)
00167       norm += (a[i] - b[i]) * (a[i] - b[i]) / (a[i] + b[i]);
00168     else
00169       norm += 0;
00170   return norm;
00171 }
00172 
00173 
00174 template <typename FloatVectorT> inline float
00175 Div_Norm (FloatVectorT a, FloatVectorT b, int dim)
00176 {
00177   float norm = 0.0;
00178 
00179   for (int i = 0; i < dim; ++i)
00180     if ((a[i] / b[i]) > 0)
00181       norm += (a[i] - b[i]) * logf (a[i] / b[i]);
00182     else
00183       norm += 0;
00184   return norm;
00185 }
00186 
00187 
00188 template <typename FloatVectorT> inline float
00189 PF_Norm (FloatVectorT a, FloatVectorT b, int dim, float P1, float P2)
00190 {
00191   float norm = 0.0;
00192 
00193   for (int i = 0; i < dim; ++i)
00194     norm += (P1 * a[i] - P2 * b[i]) * (P1 * a[i] - P2 * b[i]);
00195   return sqrtf (norm);
00196 }
00197 
00198 
00199 template <typename FloatVectorT> inline float
00200 K_Norm (FloatVectorT a, FloatVectorT b, int dim, float P1, float P2)
00201 {
00202   float norm = 0.0;
00203 
00204   for (int i = 0; i < dim; ++i)
00205     norm += fabsf (P1 * a[i] - P2 * b[i]);
00206   return norm;
00207 }
00208 
00209 
00210 template <typename FloatVectorT> inline float
00211 KL_Norm (FloatVectorT a, FloatVectorT b, int dim)
00212 {
00213   float norm = 0.0;
00214 
00215   for (int i = 0; i < dim; ++i)
00216     if ( (b[i] != 0) && ((a[i] / b[i]) > 0) )
00217       norm += a[i] * logf (a[i] / b[i]);
00218     else
00219       norm += 0;
00220   return norm;
00221 }
00222 
00223 
00224 template <typename FloatVectorT> inline float
00225 HIK_Norm(FloatVectorT a, FloatVectorT b, int dim)
00226 {
00227   float norm = 0.0f;
00228   for (int i = 0; i < dim; ++i)
00229     norm += (std::min)(a[i], b[i]);
00230   return norm;
00231 }
00232 
00233 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:54