integral_image2D.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: integral_image2D.h 6144 2012-07-04 22:06:28Z rusu $
00037  */
00038 
00039 #ifndef PCL_INTEGRAL_IMAGE2D_H_
00040 #define PCL_INTEGRAL_IMAGE2D_H_
00041 
00042 #include <vector>
00043 
00044 namespace pcl
00045 {
00046   template <typename DataType>
00047   struct IntegralImageTypeTraits
00048   {
00049     typedef DataType Type;
00050     typedef DataType IntegralType;
00051   };
00052 
00053   template <>
00054   struct IntegralImageTypeTraits<float>
00055   {
00056     typedef float Type;
00057     typedef double IntegralType;
00058   };
00059 
00060   template <>
00061   struct IntegralImageTypeTraits<char>
00062   {
00063     typedef char Type;
00064     typedef int IntegralType;
00065   };
00066 
00067   template <>
00068   struct IntegralImageTypeTraits<short>
00069   {
00070     typedef short Type;
00071     typedef long IntegralType;
00072   };
00073 
00074   template <>
00075   struct IntegralImageTypeTraits<unsigned short>
00076   {
00077     typedef unsigned short Type;
00078     typedef unsigned long IntegralType;
00079   };
00080 
00081   template <>
00082   struct IntegralImageTypeTraits<unsigned char>
00083   {
00084     typedef unsigned char Type;
00085     typedef unsigned int IntegralType;
00086   };
00087 
00088   template <>
00089   struct IntegralImageTypeTraits<int>
00090   {
00091     typedef int Type;
00092     typedef long IntegralType;
00093   };
00094 
00095   template <>
00096   struct IntegralImageTypeTraits<unsigned int>
00097   {
00098     typedef unsigned int Type;
00099     typedef unsigned long IntegralType;
00100   };
00101 
00105   template <class DataType, unsigned Dimension>
00106   class IntegralImage2D
00107   {
00108     public:
00109       static const unsigned second_order_size = (Dimension * (Dimension + 1)) >> 1;
00110       typedef Eigen::Matrix<typename IntegralImageTypeTraits<DataType>::IntegralType, Dimension, 1> ElementType;
00111       typedef Eigen::Matrix<typename IntegralImageTypeTraits<DataType>::IntegralType, second_order_size, 1> SecondOrderType;
00112 
00116       IntegralImage2D (bool compute_second_order_integral_images) :
00117         first_order_integral_image_ (),
00118         second_order_integral_image_ (),
00119         finite_values_integral_image_ (),
00120         width_ (1), 
00121         height_ (1), 
00122         compute_second_order_integral_images_ (compute_second_order_integral_images)
00123       {
00124       }
00125 
00127       virtual
00128       ~IntegralImage2D () { }
00129 
00133       void 
00134       setSecondOrderComputation (bool compute_second_order_integral_images);
00135 
00143       void
00144       setInput (const DataType * data,
00145                 unsigned width, unsigned height, unsigned element_stride, unsigned row_stride);
00146 
00153       inline ElementType
00154       getFirstOrderSum (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const;
00155 
00162       inline ElementType
00163       getFirstOrderSumSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const;
00164 
00171       inline SecondOrderType
00172       getSecondOrderSum (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const;
00173 
00180       inline SecondOrderType
00181       getSecondOrderSumSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const;
00182 
00189       inline unsigned
00190       getFiniteElementsCount (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const;
00191 
00198       inline unsigned
00199       getFiniteElementsCountSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const;
00200 
00201     private:
00202       typedef Eigen::Matrix<typename IntegralImageTypeTraits<DataType>::Type, Dimension, 1> InputType;
00203 
00209       void
00210       computeIntegralImages (const DataType * data, unsigned row_stride, unsigned element_stride);
00211 
00212       std::vector<ElementType, Eigen::aligned_allocator<ElementType> > first_order_integral_image_;
00213       std::vector<SecondOrderType, Eigen::aligned_allocator<SecondOrderType> > second_order_integral_image_;
00214       std::vector<unsigned> finite_values_integral_image_;
00215 
00217       unsigned width_;
00219       unsigned height_;
00220 
00222       bool compute_second_order_integral_images_;
00223    };
00224 
00228   template <class DataType>
00229   class IntegralImage2D <DataType, 1>
00230   {
00231     public:
00232       static const unsigned second_order_size = 1;
00233       typedef typename IntegralImageTypeTraits<DataType>::IntegralType ElementType;
00234       typedef typename IntegralImageTypeTraits<DataType>::IntegralType SecondOrderType;
00235 
00239       IntegralImage2D (bool compute_second_order_integral_images) : 
00240         first_order_integral_image_ (),
00241         second_order_integral_image_ (),
00242         finite_values_integral_image_ (),
00243         width_ (1), height_ (1), 
00244         compute_second_order_integral_images_ (compute_second_order_integral_images)
00245       {
00246       }
00247 
00249       virtual
00250       ~IntegralImage2D () { }
00251 
00259       void
00260       setInput (const DataType * data,
00261                 unsigned width, unsigned height, unsigned element_stride, unsigned row_stride);
00262 
00269       inline ElementType
00270       getFirstOrderSum (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const;
00271 
00278       inline ElementType
00279       getFirstOrderSumSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const;
00280 
00287       inline SecondOrderType
00288       getSecondOrderSum (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const;
00289 
00296       inline SecondOrderType
00297       getSecondOrderSumSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const;
00298 
00305       inline unsigned
00306       getFiniteElementsCount (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const;
00307 
00314       inline unsigned
00315       getFiniteElementsCountSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const;
00316 
00317   private:
00318     //  typedef typename IntegralImageTypeTraits<DataType>::Type InputType;
00319 
00325       void
00326       computeIntegralImages (const DataType * data, unsigned row_stride, unsigned element_stride);
00327 
00328       std::vector<ElementType, Eigen::aligned_allocator<ElementType> > first_order_integral_image_;
00329       std::vector<SecondOrderType, Eigen::aligned_allocator<SecondOrderType> > second_order_integral_image_;
00330       std::vector<unsigned> finite_values_integral_image_;
00331 
00333       unsigned width_;
00335       unsigned height_;
00336 
00338       bool compute_second_order_integral_images_;
00339    };
00340  }
00341 
00342 #include <pcl/features/impl/integral_image2D.hpp>
00343 
00344 #endif    // PCL_INTEGRAL_IMAGE2D_H_
00345 


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