00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #ifndef PCL_INTEGRAL_IMAGE2D_H_
00041 #define PCL_INTEGRAL_IMAGE2D_H_
00042
00043 #include <vector>
00044
00045 namespace pcl
00046 {
00047 template <typename DataType>
00048 struct IntegralImageTypeTraits
00049 {
00050 typedef DataType Type;
00051 typedef DataType IntegralType;
00052 };
00053
00054 template <>
00055 struct IntegralImageTypeTraits<float>
00056 {
00057 typedef float Type;
00058 typedef double IntegralType;
00059 };
00060
00061 template <>
00062 struct IntegralImageTypeTraits<char>
00063 {
00064 typedef char Type;
00065 typedef int IntegralType;
00066 };
00067
00068 template <>
00069 struct IntegralImageTypeTraits<short>
00070 {
00071 typedef short Type;
00072 typedef long IntegralType;
00073 };
00074
00075 template <>
00076 struct IntegralImageTypeTraits<unsigned short>
00077 {
00078 typedef unsigned short Type;
00079 typedef unsigned long IntegralType;
00080 };
00081
00082 template <>
00083 struct IntegralImageTypeTraits<unsigned char>
00084 {
00085 typedef unsigned char Type;
00086 typedef unsigned int IntegralType;
00087 };
00088
00089 template <>
00090 struct IntegralImageTypeTraits<int>
00091 {
00092 typedef int Type;
00093 typedef long IntegralType;
00094 };
00095
00096 template <>
00097 struct IntegralImageTypeTraits<unsigned int>
00098 {
00099 typedef unsigned int Type;
00100 typedef unsigned long IntegralType;
00101 };
00102
00106 template <class DataType, unsigned Dimension>
00107 class IntegralImage2D
00108 {
00109 public:
00110 static const unsigned second_order_size = (Dimension * (Dimension + 1)) >> 1;
00111 typedef Eigen::Matrix<typename IntegralImageTypeTraits<DataType>::IntegralType, Dimension, 1> ElementType;
00112 typedef Eigen::Matrix<typename IntegralImageTypeTraits<DataType>::IntegralType, second_order_size, 1> SecondOrderType;
00113
00117 IntegralImage2D (bool compute_second_order_integral_images) :
00118 first_order_integral_image_ (),
00119 second_order_integral_image_ (),
00120 finite_values_integral_image_ (),
00121 width_ (1),
00122 height_ (1),
00123 compute_second_order_integral_images_ (compute_second_order_integral_images)
00124 {
00125 }
00126
00128 virtual
00129 ~IntegralImage2D () { }
00130
00134 void
00135 setSecondOrderComputation (bool compute_second_order_integral_images);
00136
00144 void
00145 setInput (const DataType * data,
00146 unsigned width, unsigned height, unsigned element_stride, unsigned row_stride);
00147
00154 inline ElementType
00155 getFirstOrderSum (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const;
00156
00163 inline ElementType
00164 getFirstOrderSumSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const;
00165
00172 inline SecondOrderType
00173 getSecondOrderSum (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const;
00174
00181 inline SecondOrderType
00182 getSecondOrderSumSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const;
00183
00190 inline unsigned
00191 getFiniteElementsCount (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const;
00192
00199 inline unsigned
00200 getFiniteElementsCountSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const;
00201
00202 private:
00203 typedef Eigen::Matrix<typename IntegralImageTypeTraits<DataType>::Type, Dimension, 1> InputType;
00204
00210 void
00211 computeIntegralImages (const DataType * data, unsigned row_stride, unsigned element_stride);
00212
00213 std::vector<ElementType, Eigen::aligned_allocator<ElementType> > first_order_integral_image_;
00214 std::vector<SecondOrderType, Eigen::aligned_allocator<SecondOrderType> > second_order_integral_image_;
00215 std::vector<unsigned> finite_values_integral_image_;
00216
00218 unsigned width_;
00220 unsigned height_;
00221
00223 bool compute_second_order_integral_images_;
00224 };
00225
00229 template <class DataType>
00230 class IntegralImage2D <DataType, 1>
00231 {
00232 public:
00233 static const unsigned second_order_size = 1;
00234 typedef typename IntegralImageTypeTraits<DataType>::IntegralType ElementType;
00235 typedef typename IntegralImageTypeTraits<DataType>::IntegralType SecondOrderType;
00236
00240 IntegralImage2D (bool compute_second_order_integral_images) :
00241 first_order_integral_image_ (),
00242 second_order_integral_image_ (),
00243 finite_values_integral_image_ (),
00244 width_ (1), height_ (1),
00245 compute_second_order_integral_images_ (compute_second_order_integral_images)
00246 {
00247 }
00248
00250 virtual
00251 ~IntegralImage2D () { }
00252
00260 void
00261 setInput (const DataType * data,
00262 unsigned width, unsigned height, unsigned element_stride, unsigned row_stride);
00263
00270 inline ElementType
00271 getFirstOrderSum (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const;
00272
00279 inline ElementType
00280 getFirstOrderSumSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const;
00281
00288 inline SecondOrderType
00289 getSecondOrderSum (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const;
00290
00297 inline SecondOrderType
00298 getSecondOrderSumSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const;
00299
00306 inline unsigned
00307 getFiniteElementsCount (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const;
00308
00315 inline unsigned
00316 getFiniteElementsCountSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const;
00317
00318 private:
00319
00320
00326 void
00327 computeIntegralImages (const DataType * data, unsigned row_stride, unsigned element_stride);
00328
00329 std::vector<ElementType, Eigen::aligned_allocator<ElementType> > first_order_integral_image_;
00330 std::vector<SecondOrderType, Eigen::aligned_allocator<SecondOrderType> > second_order_integral_image_;
00331 std::vector<unsigned> finite_values_integral_image_;
00332
00334 unsigned width_;
00336 unsigned height_;
00337
00339 bool compute_second_order_integral_images_;
00340 };
00341 }
00342
00343 #include <pcl/features/impl/integral_image2D.hpp>
00344
00345 #endif // PCL_INTEGRAL_IMAGE2D_H_
00346