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 #ifndef PCL_INTEGRAL_IMAGE2D_IMPL_H_
00040 #define PCL_INTEGRAL_IMAGE2D_IMPL_H_
00041
00042 #include <cstddef>
00043
00045 template <typename DataType, unsigned Dimension> void
00046 pcl::IntegralImage2D<DataType, Dimension>::setSecondOrderComputation (bool compute_second_order_integral_images)
00047 {
00048 compute_second_order_integral_images_ = compute_second_order_integral_images;
00049 }
00050
00052 template <typename DataType, unsigned Dimension> void
00053 pcl::IntegralImage2D<DataType, Dimension>::setInput (const DataType * data, unsigned width,unsigned height, unsigned element_stride, unsigned row_stride)
00054 {
00055 if ((width + 1) * (height + 1) > first_order_integral_image_.size () )
00056 {
00057 width_ = width;
00058 height_ = height;
00059 first_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
00060 finite_values_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
00061 if (compute_second_order_integral_images_)
00062 second_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
00063 }
00064 computeIntegralImages (data, row_stride, element_stride);
00065 }
00066
00068 template <typename DataType, unsigned Dimension> typename pcl::IntegralImage2D<DataType, Dimension>::ElementType
00069 pcl::IntegralImage2D<DataType, Dimension>::getFirstOrderSum (
00070 unsigned start_x, unsigned start_y, unsigned width, unsigned height) const
00071 {
00072 const unsigned upper_left_idx = start_y * (width_ + 1) + start_x;
00073 const unsigned upper_right_idx = upper_left_idx + width;
00074 const unsigned lower_left_idx = (start_y + height) * (width_ + 1) + start_x;
00075 const unsigned lower_right_idx = lower_left_idx + width;
00076
00077 return (first_order_integral_image_[lower_right_idx] + first_order_integral_image_[upper_left_idx] -
00078 first_order_integral_image_[upper_right_idx] - first_order_integral_image_[lower_left_idx] );
00079 }
00080
00082 template <typename DataType, unsigned Dimension> typename pcl::IntegralImage2D<DataType, Dimension>::SecondOrderType
00083 pcl::IntegralImage2D<DataType, Dimension>::getSecondOrderSum (
00084 unsigned start_x, unsigned start_y, unsigned width, unsigned height) const
00085 {
00086 const unsigned upper_left_idx = start_y * (width_ + 1) + start_x;
00087 const unsigned upper_right_idx = upper_left_idx + width;
00088 const unsigned lower_left_idx = (start_y + height) * (width_ + 1) + start_x;
00089 const unsigned lower_right_idx = lower_left_idx + width;
00090
00091 return (second_order_integral_image_[lower_right_idx] + second_order_integral_image_[upper_left_idx] -
00092 second_order_integral_image_[upper_right_idx] - second_order_integral_image_[lower_left_idx] );
00093 }
00094
00096 template <typename DataType, unsigned Dimension> unsigned
00097 pcl::IntegralImage2D<DataType, Dimension>::getFiniteElementsCount (
00098 unsigned start_x, unsigned start_y, unsigned width, unsigned height) const
00099 {
00100 const unsigned upper_left_idx = start_y * (width_ + 1) + start_x;
00101 const unsigned upper_right_idx = upper_left_idx + width;
00102 const unsigned lower_left_idx = (start_y + height) * (width_ + 1) + start_x;
00103 const unsigned lower_right_idx = lower_left_idx + width;
00104
00105 return (finite_values_integral_image_[lower_right_idx] + finite_values_integral_image_[upper_left_idx] -
00106 finite_values_integral_image_[upper_right_idx] - finite_values_integral_image_[lower_left_idx] );
00107 }
00108
00110 template <typename DataType, unsigned Dimension> typename pcl::IntegralImage2D<DataType, Dimension>::ElementType
00111 pcl::IntegralImage2D<DataType, Dimension>::getFirstOrderSumSE (
00112 unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const
00113 {
00114 const unsigned upper_left_idx = start_y * (width_ + 1) + start_x;
00115 const unsigned upper_right_idx = start_y * (width_ + 1) + end_x;
00116 const unsigned lower_left_idx = end_y * (width_ + 1) + start_x;
00117 const unsigned lower_right_idx = end_y * (width_ + 1) + end_x;
00118
00119 return (first_order_integral_image_[lower_right_idx] + first_order_integral_image_[upper_left_idx] -
00120 first_order_integral_image_[upper_right_idx] - first_order_integral_image_[lower_left_idx] );
00121 }
00122
00124 template <typename DataType, unsigned Dimension> typename pcl::IntegralImage2D<DataType, Dimension>::SecondOrderType
00125 pcl::IntegralImage2D<DataType, Dimension>::getSecondOrderSumSE (
00126 unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const
00127 {
00128 const unsigned upper_left_idx = start_y * (width_ + 1) + start_x;
00129 const unsigned upper_right_idx = start_y * (width_ + 1) + end_x;
00130 const unsigned lower_left_idx = end_y * (width_ + 1) + start_x;
00131 const unsigned lower_right_idx = end_y * (width_ + 1) + end_x;
00132
00133 return (second_order_integral_image_[lower_right_idx] + second_order_integral_image_[upper_left_idx] -
00134 second_order_integral_image_[upper_right_idx] - second_order_integral_image_[lower_left_idx] );
00135 }
00136
00138 template <typename DataType, unsigned Dimension> unsigned
00139 pcl::IntegralImage2D<DataType, Dimension>::getFiniteElementsCountSE (
00140 unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const
00141 {
00142 const unsigned upper_left_idx = start_y * (width_ + 1) + start_x;
00143 const unsigned upper_right_idx = start_y * (width_ + 1) + end_x;
00144 const unsigned lower_left_idx = end_y * (width_ + 1) + start_x;
00145 const unsigned lower_right_idx = end_y * (width_ + 1) + end_x;
00146
00147 return (finite_values_integral_image_[lower_right_idx] + finite_values_integral_image_[upper_left_idx] -
00148 finite_values_integral_image_[upper_right_idx] - finite_values_integral_image_[lower_left_idx] );
00149 }
00150
00152 template <typename DataType, unsigned Dimension> void
00153 pcl::IntegralImage2D<DataType, Dimension>::computeIntegralImages (
00154 const DataType *data, unsigned row_stride, unsigned element_stride)
00155 {
00156 ElementType* previous_row = &first_order_integral_image_[0];
00157 ElementType* current_row = previous_row + (width_ + 1);
00158 memset (previous_row, 0, sizeof (ElementType) * (width_ + 1));
00159
00160 unsigned* count_previous_row = &finite_values_integral_image_[0];
00161 unsigned* count_current_row = count_previous_row + (width_ + 1);
00162 memset (count_previous_row, 0, sizeof (unsigned) * (width_ + 1));
00163
00164 if (!compute_second_order_integral_images_)
00165 {
00166 for (unsigned rowIdx = 0; rowIdx < height_; ++rowIdx, data += row_stride,
00167 previous_row = current_row, current_row += (width_ + 1),
00168 count_previous_row = count_current_row, count_current_row += (width_ + 1))
00169 {
00170 current_row [0].setZero ();
00171 count_current_row [0] = 0;
00172 for (unsigned colIdx = 0, valIdx = 0; colIdx < width_; ++colIdx, valIdx += element_stride)
00173 {
00174 current_row [colIdx + 1] = previous_row [colIdx + 1] + current_row [colIdx] - previous_row [colIdx];
00175 count_current_row [colIdx + 1] = count_previous_row [colIdx + 1] + count_current_row [colIdx] - count_previous_row [colIdx];
00176 const InputType* element = reinterpret_cast <const InputType*> (&data [valIdx]);
00177 if (pcl_isfinite (element->sum ()))
00178 {
00179 current_row [colIdx + 1] += element->template cast<typename IntegralImageTypeTraits<DataType>::IntegralType>();
00180 ++(count_current_row [colIdx + 1]);
00181 }
00182 }
00183 }
00184 }
00185 else
00186 {
00187 SecondOrderType* so_previous_row = &second_order_integral_image_[0];
00188 SecondOrderType* so_current_row = so_previous_row + (width_ + 1);
00189 memset (so_previous_row, 0, sizeof (SecondOrderType) * (width_ + 1));
00190
00191 SecondOrderType so_element;
00192 for (unsigned rowIdx = 0; rowIdx < height_; ++rowIdx, data += row_stride,
00193 previous_row = current_row, current_row += (width_ + 1),
00194 count_previous_row = count_current_row, count_current_row += (width_ + 1),
00195 so_previous_row = so_current_row, so_current_row += (width_ + 1))
00196 {
00197 current_row [0].setZero ();
00198 so_current_row [0].setZero ();
00199 count_current_row [0] = 0;
00200 for (unsigned colIdx = 0, valIdx = 0; colIdx < width_; ++colIdx, valIdx += element_stride)
00201 {
00202 current_row [colIdx + 1] = previous_row [colIdx + 1] + current_row [colIdx] - previous_row [colIdx];
00203 so_current_row [colIdx + 1] = so_previous_row [colIdx + 1] + so_current_row [colIdx] - so_previous_row [colIdx];
00204 count_current_row [colIdx + 1] = count_previous_row [colIdx + 1] + count_current_row [colIdx] - count_previous_row [colIdx];
00205
00206 const InputType* element = reinterpret_cast <const InputType*> (&data [valIdx]);
00207 if (pcl_isfinite (element->sum ()))
00208 {
00209 current_row [colIdx + 1] += element->template cast<typename IntegralImageTypeTraits<DataType>::IntegralType>();
00210 ++(count_current_row [colIdx + 1]);
00211 for (unsigned myIdx = 0, elIdx = 0; myIdx < Dimension; ++myIdx)
00212 for (unsigned mxIdx = myIdx; mxIdx < Dimension; ++mxIdx, ++elIdx)
00213 so_current_row [colIdx + 1][elIdx] += (*element)[myIdx] * (*element)[mxIdx];
00214 }
00215 }
00216 }
00217 }
00218 }
00219
00221
00222 template <typename DataType> void
00223 pcl::IntegralImage2D<DataType, 1>::setInput (const DataType * data, unsigned width,unsigned height, unsigned element_stride, unsigned row_stride)
00224 {
00225 if ((width + 1) * (height + 1) > first_order_integral_image_.size () )
00226 {
00227 width_ = width;
00228 height_ = height;
00229 first_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
00230 finite_values_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
00231 if (compute_second_order_integral_images_)
00232 second_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
00233 }
00234 computeIntegralImages (data, row_stride, element_stride);
00235 }
00236
00238 template <typename DataType> typename pcl::IntegralImage2D<DataType, 1>::ElementType
00239 pcl::IntegralImage2D<DataType, 1>::getFirstOrderSum (
00240 unsigned start_x, unsigned start_y, unsigned width, unsigned height) const
00241 {
00242 const unsigned upper_left_idx = start_y * (width_ + 1) + start_x;
00243 const unsigned upper_right_idx = upper_left_idx + width;
00244 const unsigned lower_left_idx = (start_y + height) * (width_ + 1) + start_x;
00245 const unsigned lower_right_idx = lower_left_idx + width;
00246
00247 return (first_order_integral_image_[lower_right_idx] + first_order_integral_image_[upper_left_idx] -
00248 first_order_integral_image_[upper_right_idx] - first_order_integral_image_[lower_left_idx] );
00249 }
00250
00252 template <typename DataType> typename pcl::IntegralImage2D<DataType, 1>::SecondOrderType
00253 pcl::IntegralImage2D<DataType, 1>::getSecondOrderSum (
00254 unsigned start_x, unsigned start_y, unsigned width, unsigned height) const
00255 {
00256 const unsigned upper_left_idx = start_y * (width_ + 1) + start_x;
00257 const unsigned upper_right_idx = upper_left_idx + width;
00258 const unsigned lower_left_idx = (start_y + height) * (width_ + 1) + start_x;
00259 const unsigned lower_right_idx = lower_left_idx + width;
00260
00261 return (second_order_integral_image_[lower_right_idx] + second_order_integral_image_[upper_left_idx] -
00262 second_order_integral_image_[upper_right_idx] - second_order_integral_image_[lower_left_idx] );
00263 }
00264
00266 template <typename DataType> unsigned
00267 pcl::IntegralImage2D<DataType, 1>::getFiniteElementsCount (
00268 unsigned start_x, unsigned start_y, unsigned width, unsigned height) const
00269 {
00270 const unsigned upper_left_idx = start_y * (width_ + 1) + start_x;
00271 const unsigned upper_right_idx = upper_left_idx + width;
00272 const unsigned lower_left_idx = (start_y + height) * (width_ + 1) + start_x;
00273 const unsigned lower_right_idx = lower_left_idx + width;
00274
00275 return (finite_values_integral_image_[lower_right_idx] + finite_values_integral_image_[upper_left_idx] -
00276 finite_values_integral_image_[upper_right_idx] - finite_values_integral_image_[lower_left_idx] );
00277 }
00278
00280 template <typename DataType> typename pcl::IntegralImage2D<DataType, 1>::ElementType
00281 pcl::IntegralImage2D<DataType, 1>::getFirstOrderSumSE (
00282 unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const
00283 {
00284 const unsigned upper_left_idx = start_y * (width_ + 1) + start_x;
00285 const unsigned upper_right_idx = start_y * (width_ + 1) + end_x;
00286 const unsigned lower_left_idx = end_y * (width_ + 1) + start_x;
00287 const unsigned lower_right_idx = end_y * (width_ + 1) + end_x;
00288
00289 return (first_order_integral_image_[lower_right_idx] + first_order_integral_image_[upper_left_idx] -
00290 first_order_integral_image_[upper_right_idx] - first_order_integral_image_[lower_left_idx] );
00291 }
00292
00294 template <typename DataType> typename pcl::IntegralImage2D<DataType, 1>::SecondOrderType
00295 pcl::IntegralImage2D<DataType, 1>::getSecondOrderSumSE (
00296 unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const
00297 {
00298 const unsigned upper_left_idx = start_y * (width_ + 1) + start_x;
00299 const unsigned upper_right_idx = start_y * (width_ + 1) + end_x;
00300 const unsigned lower_left_idx = end_y * (width_ + 1) + start_x;
00301 const unsigned lower_right_idx = end_y * (width_ + 1) + end_x;
00302
00303 return (second_order_integral_image_[lower_right_idx] + second_order_integral_image_[upper_left_idx] -
00304 second_order_integral_image_[upper_right_idx] - second_order_integral_image_[lower_left_idx] );
00305 }
00306
00308 template <typename DataType> unsigned
00309 pcl::IntegralImage2D<DataType, 1>::getFiniteElementsCountSE (
00310 unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const
00311 {
00312 const unsigned upper_left_idx = start_y * (width_ + 1) + start_x;
00313 const unsigned upper_right_idx = start_y * (width_ + 1) + end_x;
00314 const unsigned lower_left_idx = end_y * (width_ + 1) + start_x;
00315 const unsigned lower_right_idx = end_y * (width_ + 1) + end_x;
00316
00317 return (finite_values_integral_image_[lower_right_idx] + finite_values_integral_image_[upper_left_idx] -
00318 finite_values_integral_image_[upper_right_idx] - finite_values_integral_image_[lower_left_idx] );
00319 }
00320
00322 template <typename DataType> void
00323 pcl::IntegralImage2D<DataType, 1>::computeIntegralImages (
00324 const DataType *data, unsigned row_stride, unsigned element_stride)
00325 {
00326 ElementType* previous_row = &first_order_integral_image_[0];
00327 ElementType* current_row = previous_row + (width_ + 1);
00328 memset (previous_row, 0, sizeof (ElementType) * (width_ + 1));
00329
00330 unsigned* count_previous_row = &finite_values_integral_image_[0];
00331 unsigned* count_current_row = count_previous_row + (width_ + 1);
00332 memset (count_previous_row, 0, sizeof (unsigned) * (width_ + 1));
00333
00334 if (!compute_second_order_integral_images_)
00335 {
00336 for (unsigned rowIdx = 0; rowIdx < height_; ++rowIdx, data += row_stride,
00337 previous_row = current_row, current_row += (width_ + 1),
00338 count_previous_row = count_current_row, count_current_row += (width_ + 1))
00339 {
00340 current_row [0] = 0.0;
00341 count_current_row [0] = 0;
00342 for (unsigned colIdx = 0, valIdx = 0; colIdx < width_; ++colIdx, valIdx += element_stride)
00343 {
00344 current_row [colIdx + 1] = previous_row [colIdx + 1] + current_row [colIdx] - previous_row [colIdx];
00345 count_current_row [colIdx + 1] = count_previous_row [colIdx + 1] + count_current_row [colIdx] - count_previous_row [colIdx];
00346 if (pcl_isfinite (data [valIdx]))
00347 {
00348 current_row [colIdx + 1] += data [valIdx];
00349 ++(count_current_row [colIdx + 1]);
00350 }
00351 }
00352 }
00353 }
00354 else
00355 {
00356 SecondOrderType* so_previous_row = &second_order_integral_image_[0];
00357 SecondOrderType* so_current_row = so_previous_row + (width_ + 1);
00358 memset (so_previous_row, 0, sizeof (SecondOrderType) * (width_ + 1));
00359
00360 for (unsigned rowIdx = 0; rowIdx < height_; ++rowIdx, data += row_stride,
00361 previous_row = current_row, current_row += (width_ + 1),
00362 count_previous_row = count_current_row, count_current_row += (width_ + 1),
00363 so_previous_row = so_current_row, so_current_row += (width_ + 1))
00364 {
00365 current_row [0] = 0.0;
00366 so_current_row [0] = 0.0;
00367 count_current_row [0] = 0;
00368 for (unsigned colIdx = 0, valIdx = 0; colIdx < width_; ++colIdx, valIdx += element_stride)
00369 {
00370 current_row [colIdx + 1] = previous_row [colIdx + 1] + current_row [colIdx] - previous_row [colIdx];
00371 so_current_row [colIdx + 1] = so_previous_row [colIdx + 1] + so_current_row [colIdx] - so_previous_row [colIdx];
00372 count_current_row [colIdx + 1] = count_previous_row [colIdx + 1] + count_current_row [colIdx] - count_previous_row [colIdx];
00373 if (pcl_isfinite (data[valIdx]))
00374 {
00375 current_row [colIdx + 1] += data[valIdx];
00376 so_current_row [colIdx + 1] += data[valIdx] * data[valIdx];
00377 ++(count_current_row [colIdx + 1]);
00378 }
00379 }
00380 }
00381 }
00382 }
00383 #endif // PCL_INTEGRAL_IMAGE2D_IMPL_H_
00384