range_image.cpp
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-2012, 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 
00037 #include <cstddef>
00038 #include <iostream>
00039 #include <cmath>
00040 #include <set>
00041 #include <pcl/common/eigen.h>
00042 #include <pcl/range_image/range_image.h>
00043 #include <pcl/common/transformation_from_correspondences.h>
00044 
00045 namespace pcl 
00046 {
00047 
00048 bool RangeImage::debug = false;
00049 int RangeImage::max_no_of_threads = 1;
00050 const int RangeImage::lookup_table_size = 20001;
00051 std::vector<float> RangeImage::asin_lookup_table;
00052 std::vector<float> RangeImage::atan_lookup_table;
00053 std::vector<float> RangeImage::cos_lookup_table;
00054 
00056 void 
00057 RangeImage::createLookupTables ()
00058 {
00059   if (!asin_lookup_table.empty ())
00060     return;
00061   
00062   asin_lookup_table.resize (lookup_table_size);
00063   for (int i=0; i<lookup_table_size; ++i) {
00064     float value = static_cast<float> (i-lookup_table_size/2)/static_cast<float> (lookup_table_size/2);
00065     asin_lookup_table[i] = asinf (value);
00066   }
00067   
00068   atan_lookup_table.resize (lookup_table_size);
00069   for (int i=0; i<lookup_table_size; ++i) 
00070   {
00071     float value = static_cast<float> (i-lookup_table_size/2)/static_cast<float> (lookup_table_size/2);
00072     atan_lookup_table[i] = atanf (value);
00073   }
00074   
00075   cos_lookup_table.resize (lookup_table_size);
00076   
00077   for (int i = 0; i < lookup_table_size; ++i) 
00078   {
00079     float value = static_cast<float> (i) * 2.0f * static_cast<float> (M_PI) / static_cast<float> (lookup_table_size - 1);
00080     cos_lookup_table[i] = cosf (value);
00081   }
00082 }
00083 
00084 
00085 
00087 void 
00088 RangeImage::getCoordinateFrameTransformation (RangeImage::CoordinateFrame coordinate_frame,
00089                                              Eigen::Affine3f& transformation)
00090 {
00091   switch (coordinate_frame)
00092   {
00093     case LASER_FRAME:
00094       transformation (0,0)= 0.0f; transformation (0,1)= 0.0f; transformation (0,2)=1.0f; transformation (0,3)=0.0f;
00095       transformation (1,0)=-1.0f; transformation (1,1)= 0.0f; transformation (1,2)=0.0f; transformation (1,3)=0.0f;
00096       transformation (2,0)= 0.0f; transformation (2,1)=-1.0f; transformation (2,2)=0.0f; transformation (2,3)=0.0f;
00097       transformation (3,0)= 0.0f; transformation (3,1)= 0.0f; transformation (3,2)=0.0f; transformation (3,3)=1.0f;
00098       break;
00099     case CAMERA_FRAME:
00100     default:
00101       transformation.setIdentity ();
00102       break;
00103   }
00104 }
00105 
00107 RangeImage::RangeImage () : 
00108   RangeImage::BaseClass (), 
00109   to_range_image_system_ (Eigen::Affine3f::Identity ()),
00110   to_world_system_ (Eigen::Affine3f::Identity ()),
00111   angular_resolution_x_ (0), angular_resolution_y_ (0),
00112   angular_resolution_x_reciprocal_ (0), angular_resolution_y_reciprocal_ (0),
00113   image_offset_x_ (0), image_offset_y_ (0),
00114   unobserved_point ()
00115 {
00116   createLookupTables ();
00117   reset ();
00118   unobserved_point.x = unobserved_point.y = unobserved_point.z = std::numeric_limits<float>::quiet_NaN ();
00119   unobserved_point.range = -std::numeric_limits<float>::infinity ();
00120 }
00121 
00123 RangeImage::~RangeImage ()
00124 {
00125 }
00126 
00128 void
00129 RangeImage::reset ()
00130 {
00131   is_dense = true;
00132   width = height = 0;
00133   points.clear ();
00134   to_range_image_system_.setIdentity ();
00135   to_world_system_.setIdentity ();
00136   setAngularResolution (deg2rad (0.5f));
00137   image_offset_x_ = image_offset_y_ = 0;
00138 }
00139 
00141 void
00142 RangeImage::createEmpty (float angular_resolution, const Eigen::Affine3f& sensor_pose,
00143                          RangeImage::CoordinateFrame coordinate_frame, float angle_width, float angle_height)
00144 {
00145   createEmpty (angular_resolution, angular_resolution, sensor_pose, coordinate_frame, angle_width, angle_height);
00146 }
00147 
00149 void
00150 RangeImage::createEmpty (float angular_resolution_x, float angular_resolution_y, const Eigen::Affine3f& sensor_pose,
00151                          RangeImage::CoordinateFrame coordinate_frame, float angle_width, float angle_height)
00152 {
00153   setAngularResolution(angular_resolution_x, angular_resolution_y);
00154   width  = static_cast<uint32_t> (pcl_lrint (floor (angle_width * angular_resolution_x_reciprocal_)));
00155   height = static_cast<uint32_t> (pcl_lrint (floor (angle_height * angular_resolution_y_reciprocal_)));
00156 
00157   int full_width  = static_cast<int> (pcl_lrint (floor (pcl::deg2rad (360.0f)*angular_resolution_x_reciprocal_))),
00158       full_height = static_cast<int> (pcl_lrint (floor (pcl::deg2rad (180.0f)*angular_resolution_y_reciprocal_)));
00159   image_offset_x_ = (full_width-width)/2;
00160   image_offset_y_ = (full_height-height)/2;
00161   is_dense = false;
00162   getCoordinateFrameTransformation (coordinate_frame, to_world_system_);
00163   to_world_system_ = sensor_pose * to_world_system_;
00164   to_range_image_system_ = to_world_system_.inverse (Eigen::Isometry);
00165   unsigned int size = width*height;
00166   points.clear ();
00167   points.resize (size, unobserved_point);
00168 }
00169 
00171 void 
00172 RangeImage::integrateFarRanges (const PointCloud<PointWithViewpoint>& far_ranges)
00173 {
00174   float x_real, y_real, range_of_current_point;
00175   for (PointCloud<PointWithViewpoint>::const_iterator it
00176        =far_ranges.points.begin (); it!=far_ranges.points.end (); ++it)
00177   {
00178     //if (!isFinite (*it))  // Check for NAN etc
00179       //continue;
00180     Vector3fMapConst current_point = it->getVector3fMap ();
00181     
00182     this->getImagePoint (current_point, x_real, y_real, range_of_current_point);
00183     
00184     int floor_x = static_cast<int> (pcl_lrint (floor (x_real))), 
00185         floor_y = static_cast<int> (pcl_lrint (floor (y_real))),
00186         ceil_x  = static_cast<int> (pcl_lrint (ceil (x_real))),
00187         ceil_y  = static_cast<int> (pcl_lrint (ceil (y_real)));
00188     
00189     int neighbor_x[4], neighbor_y[4];
00190     neighbor_x[0]=floor_x; neighbor_y[0]=floor_y;
00191     neighbor_x[1]=floor_x; neighbor_y[1]=ceil_y;
00192     neighbor_x[2]=ceil_x;  neighbor_y[2]=floor_y;
00193     neighbor_x[3]=ceil_x;  neighbor_y[3]=ceil_y;
00194     
00195     for (int i=0; i<4; ++i)
00196     {
00197       int x=neighbor_x[i], y=neighbor_y[i];
00198       if (!isInImage (x, y))
00199         continue;
00200       PointWithRange& image_point = getPoint (x, y);
00201       if (!pcl_isfinite (image_point.range))
00202         image_point.range = std::numeric_limits<float>::infinity ();
00203     }
00204   }
00205 }
00206 
00208 void 
00209 RangeImage::cropImage (int borderSize, int top, int right, int bottom, int left) {
00210   //MEASURE_FUNCTION_TIME;
00211   
00212   bool topIsDone=true, rightIsDone=true, bottomIsDone=true, leftIsDone=true;
00213   if (top < 0) {
00214     top=-1;
00215     topIsDone=false;
00216   }
00217   if (right < 0) 
00218   {
00219     right= static_cast<int> (width);
00220     rightIsDone=false;
00221   }
00222   if (bottom < 0) 
00223   {
00224     bottom= static_cast<int> (height);
00225     bottomIsDone=false;
00226   }
00227   if (left < 0) 
00228   {
00229     left = -1;
00230     leftIsDone = false;
00231   }
00232   
00233   // Find top border
00234   while (!topIsDone && top<=bottom) 
00235   {
00236     ++top;
00237     int lineStart = top*width;
00238     for (int x=left; x<=right && !topIsDone; ++x)
00239       if (pcl_isfinite (points[lineStart + x].range))
00240         topIsDone = true;
00241   }
00242   // Check if range image is empty
00243   if (top > bottom) 
00244   {
00245     points.clear ();
00246     width = height = 0;
00247     return;
00248   }
00249   // Find right border
00250   while (!rightIsDone) 
00251   {
00252     for (int y=top; y<=bottom && !rightIsDone; ++y)
00253       if (pcl_isfinite (points[y*width + right].range))
00254         rightIsDone = true;
00255   }
00256   // Find bottom border
00257   while (!bottomIsDone) 
00258   {
00259     --bottom;
00260     int lineStart = bottom*width;
00261     for (int x=left; x<=right && !bottomIsDone; ++x)
00262       if (pcl_isfinite (points[lineStart + x].range))
00263         bottomIsDone = true;
00264   } 
00265   // Find left border
00266   while (!leftIsDone) 
00267   {
00268     ++left;
00269     for (int y=top; y<=bottom && !leftIsDone; ++y)
00270       if (pcl_isfinite (points[y*width + left].range))
00271         leftIsDone = true;
00272   } 
00273   left-=borderSize; top-=borderSize; right+=borderSize; bottom+=borderSize;
00274   
00275   
00276   // Create copy without copying the old points - vector::swap only copies a few pointers, not the content
00277   PointCloud<PointWithRange>::VectorType tmpPoints;
00278   points.swap (tmpPoints);
00279   RangeImage oldRangeImage = *this;
00280   tmpPoints.swap (oldRangeImage.points);
00281   
00282   width = right-left+1; height = bottom-top+1;
00283   image_offset_x_ = left+oldRangeImage.image_offset_x_;
00284   image_offset_y_ = top+oldRangeImage.image_offset_y_;
00285   points.resize (width*height);
00286   
00287   // Copy points
00288   for (int y=0, oldY=top; y< static_cast<int> (height); ++y,++oldY) 
00289   {
00290     for (int x=0, oldX=left; x< static_cast<int> (width); ++x,++oldX) 
00291     {
00292       PointWithRange& currentPoint = points[y*width + x];
00293       if (oldX<0 || oldX>= static_cast<int> (oldRangeImage.width) || oldY<0 || oldY>= static_cast<int> (oldRangeImage.height)) 
00294       {
00295         currentPoint = unobserved_point;
00296         continue;
00297       }
00298       currentPoint = oldRangeImage.points[oldY*oldRangeImage.width + oldX];
00299     }
00300   }
00301 }
00302 
00304 void 
00305 RangeImage::recalculate3DPointPositions () 
00306 {
00307   for (int y = 0; y < static_cast<int> (height); ++y) 
00308   {
00309     for (int x = 0; x < static_cast<int> (width); ++x) 
00310     {
00311       PointWithRange& point = points[y*width + x];
00312       if (!pcl_isinf (point.range)) 
00313         calculate3DPoint (static_cast<float> (x), static_cast<float> (y), point.range, point);
00314     }
00315   }
00316 }
00317 
00319 float* 
00320 RangeImage::getRangesArray () const 
00321 {
00322   int arraySize = width * height;
00323   float* ranges = new float[arraySize];
00324   for (int i=0; i<arraySize; ++i)
00325     ranges[i] = points[i].range;
00326   return ranges;
00327 }
00328 
00329 
00331 void 
00332 RangeImage::getIntegralImage (float*& integral_image, int*& valid_points_num_image) const
00333 {
00334   integral_image = new float[width*height];
00335   float* integral_image_ptr = integral_image;
00336   valid_points_num_image = new int[width*height];
00337   int* valid_points_num_image_ptr = valid_points_num_image;
00338   for (int y = 0; y < static_cast<int> (height); ++y)
00339   {
00340     for (int x = 0; x < static_cast<int> (width); ++x)
00341     {
00342       float& integral_pixel = * (integral_image_ptr++);
00343       integral_pixel = getPoint (x, y).range;
00344       int& valid_points_num = * (valid_points_num_image_ptr++);
00345       valid_points_num = 1;
00346       if (pcl_isinf (integral_pixel))
00347       {
00348         integral_pixel = 0.0f;
00349         valid_points_num = 0;
00350       }
00351       float left_value=0, top_left_value=0, top_value=0;
00352       int left_valid_points=0, top_left_valid_points=0, top_valid_points=0;
00353       if (x>0)
00354       {
00355         left_value = integral_image[y*width+x-1];
00356         left_valid_points = valid_points_num_image[y*width+x-1];
00357         if (y>0)
00358         {
00359           top_left_value = integral_image[ (y-1)*width+x-1];
00360           top_left_valid_points = valid_points_num_image[ (y-1)*width+x-1];
00361         }
00362       }
00363       if (y>0)
00364       {
00365         top_value = integral_image[ (y-1)*width+x];
00366         top_valid_points = valid_points_num_image[ (y-1)*width+x];
00367       }
00368       
00369       integral_pixel += left_value + top_value - top_left_value;
00370       valid_points_num += left_valid_points + top_valid_points - top_left_valid_points;
00371     }
00372   }
00373 }
00374 
00376 void 
00377 RangeImage::getBlurredImageUsingIntegralImage (int blur_radius, float* integral_image, int* valid_points_num_image,
00378                                                RangeImage& blurred_image) const
00379 {
00380   blurred_image = *this;
00381   for (int y=0; y<int (height); ++y)
00382   {
00383     for (int x=0; x<int (width); ++x)
00384     {
00385       const PointWithRange& old_point = getPoint (x, y);
00386       PointWithRange& new_point = blurred_image.getPoint (x, y);
00387       if (!pcl_isfinite (old_point.range))
00388         continue;
00389       
00390       int top= (std::max) (-1, y-blur_radius-1), right = (std::min) (static_cast<int> (width)-1, x+blur_radius), bottom =
00391           (std::min) (static_cast<int> (height)-1, y+blur_radius), left= (std::max) (-1, x-blur_radius-1);
00392       
00393       float top_left_value=0, top_right_value=0,
00394             bottom_right_value=integral_image[bottom*width+right], bottom_left_value=0;
00395       int top_left_valid_points=0, top_right_valid_points=0,
00396           bottom_right_valid_points=valid_points_num_image[bottom*width+right], bottom_left_valid_points=0;
00397       if (left>=0)
00398       {
00399         bottom_left_value = integral_image[bottom*width+left];
00400         bottom_left_valid_points = valid_points_num_image[bottom*width+left];
00401         if (top>=0)
00402         {
00403           top_left_value = integral_image[top*width+left];
00404           top_left_valid_points = valid_points_num_image[top*width+left];
00405         }
00406       }
00407       if (top>=0)
00408       {
00409         top_right_value = integral_image[top*width+right];
00410         top_right_valid_points = valid_points_num_image[top*width+right];
00411       }
00412       int valid_points_num = bottom_right_valid_points + top_left_valid_points - bottom_left_valid_points -
00413                              top_right_valid_points;
00414       new_point.range = (bottom_right_value + top_left_value - bottom_left_value - top_right_value) / 
00415                         static_cast<float> (valid_points_num);
00416     }
00417   }
00418   blurred_image.recalculate3DPointPositions ();
00419 }
00420 
00422 void 
00423 RangeImage::getBlurredImage (int blur_radius, RangeImage& blurred_image) const
00424 {
00425   MEASURE_FUNCTION_TIME;
00426   
00427   if (blur_radius > 1)  // For a high blur radius it's faster to use integral images
00428   {
00429     float* integral_image;
00430     int* valid_points_num_image;
00431     getIntegralImage (integral_image, valid_points_num_image);
00432     getBlurredImageUsingIntegralImage (blur_radius, integral_image, valid_points_num_image, blurred_image);
00433     delete[] integral_image;
00434     delete[] valid_points_num_image;
00435     return;
00436   }
00437   
00438   blurred_image = *this;
00439   
00440   if (blur_radius==0)
00441     return;
00442   
00443   for (int y=0; y < static_cast<int> (height); ++y)
00444   {
00445     for (int x=0; x < static_cast<int> (width); ++x)
00446     {
00447       PointWithRange& new_point = blurred_image.getPoint (x, y);
00448       const PointWithRange& original_point = getPoint (x, y);
00449       if (!pcl_isfinite (original_point.range))
00450         continue;
00451       
00452       new_point.range = 0.0f;
00453       float weight_sum = 0.0f;
00454       for (int y2=y-blur_radius; y2<y+blur_radius; ++y2)
00455       {
00456         for (int x2=x-blur_radius; x2<x+blur_radius; ++x2)
00457         {
00458           if (!isValid (x2,y2))
00459             continue;
00460           new_point.range += getPoint (x2, y2).range;
00461           weight_sum += 1.0f;
00462         }
00463       }
00464       new_point.range /= weight_sum;
00465     }
00466   }
00467   blurred_image.recalculate3DPointPositions ();
00468 }
00469 
00471 void 
00472 RangeImage::setUnseenToMaxRange ()
00473 {
00474   for (unsigned int i=0; i<points.size (); ++i)
00475     if (pcl_isinf (points[i].range))
00476       points[i].range = std::numeric_limits<float>::infinity ();
00477 }
00478 
00480 void 
00481 RangeImage::getHalfImage (RangeImage& half_image) const
00482 {
00483   half_image.setAngularResolution (2.0f*angular_resolution_x_, 2.0f*angular_resolution_y_);
00484   half_image.image_offset_x_ = image_offset_x_/2;
00485   half_image.image_offset_y_ = image_offset_y_/2;
00486   half_image.width  = width/2;
00487   half_image.height = height/2;
00488   half_image.is_dense = is_dense;
00489   half_image.points.clear ();
00490   half_image.points.resize (half_image.width*half_image.height);
00491   
00492   int src_start_x = 2*half_image.image_offset_x_ - image_offset_x_,
00493       src_start_y = 2*half_image.image_offset_y_ - image_offset_y_;
00494   
00495   for (int dst_y=0; dst_y < static_cast<int> (half_image.height); ++dst_y)
00496   {
00497     for (int dst_x=0; dst_x < static_cast<int> (half_image.width); ++dst_x)
00498     {
00499       PointWithRange& dst_point = half_image.getPoint (dst_x, dst_y);
00500       dst_point=unobserved_point;
00501       int src_x_min = src_start_x + 2*dst_x,
00502           src_x_max = src_x_min + 1,
00503           src_y_min = src_start_y + 2*dst_y,
00504           src_y_max = src_y_min + 1;
00505       for (int src_x=src_x_min; src_x<=src_x_max; ++src_x)
00506       {
00507         for (int src_y=src_y_min; src_y<=src_y_max; ++src_y)
00508         {
00509           if (!isObserved (src_x, src_y))
00510             continue;
00511           const PointWithRange& src_point = getPoint (src_x, src_y);
00512           if (pcl_isfinite (dst_point.range) && src_point.range > dst_point.range)
00513             continue;
00514           dst_point = src_point;
00515         }
00516       }
00517     }
00518   }
00519 }
00520 
00522 void 
00523 RangeImage::getSubImage (int sub_image_image_offset_x, int sub_image_image_offset_y, int sub_image_width,
00524                          int sub_image_height, int combine_pixels, RangeImage& sub_image) const
00525 {
00526   sub_image.setAngularResolution (static_cast<float> (combine_pixels)*angular_resolution_x_,
00527                                   static_cast<float> (combine_pixels)*angular_resolution_y_);
00528   sub_image.image_offset_x_ = sub_image_image_offset_x;
00529   sub_image.image_offset_y_ = sub_image_image_offset_y;
00530   sub_image.width = sub_image_width;
00531   sub_image.height = sub_image_height;
00532   sub_image.is_dense = is_dense;
00533   sub_image.points.clear ();
00534   sub_image.points.resize (sub_image.width*sub_image.height);
00535   
00536   int src_start_x = combine_pixels*sub_image.image_offset_x_ - image_offset_x_,
00537       src_start_y = combine_pixels*sub_image.image_offset_y_ - image_offset_y_;
00538   
00539   for (int dst_y=0; dst_y < static_cast<int> (sub_image.height); ++dst_y)
00540   {
00541     for (int dst_x=0; dst_x < static_cast<int> (sub_image.width); ++dst_x)
00542     {
00543       PointWithRange& dst_point = sub_image.getPoint (dst_x, dst_y);
00544       dst_point=unobserved_point;
00545       int src_x_min = src_start_x + combine_pixels*dst_x,
00546           src_x_max = src_x_min + combine_pixels-1,
00547           src_y_min = src_start_y + combine_pixels*dst_y,
00548           src_y_max = src_y_min + combine_pixels-1;
00549       for (int src_x=src_x_min; src_x<=src_x_max; ++src_x)
00550       {
00551         for (int src_y=src_y_min; src_y<=src_y_max; ++src_y)
00552         {
00553           if (!isInImage (src_x, src_y))
00554             continue;
00555           const PointWithRange& src_point = getPoint (src_x, src_y);
00556           if (pcl_isfinite (dst_point.range) && src_point.range > dst_point.range)
00557             continue;
00558           dst_point = src_point;
00559         }
00560       }
00561     }
00562   }
00563 }
00564 
00565 
00567 void 
00568 RangeImage::getMinMaxRanges (float& min_range, float& max_range) const
00569 {
00570   min_range = std::numeric_limits<float>::infinity ();
00571   max_range = -std::numeric_limits<float>::infinity ();
00572   for (unsigned int i=0; i<points.size (); ++i)
00573   {
00574     float range = points[i].range;
00575     if (!pcl_isfinite (range))
00576       continue;
00577     min_range = (std::min) (min_range, range);
00578     max_range = (std::max) (max_range, range);
00579   }
00580 }
00581 
00583 void 
00584 RangeImage::change3dPointsToLocalCoordinateFrame ()
00585 {
00586   to_world_system_.setIdentity ();
00587   to_range_image_system_.setIdentity ();
00588   recalculate3DPointPositions ();
00589 }
00590 
00592 float* 
00593 RangeImage::getInterpolatedSurfaceProjection (const Eigen::Affine3f& pose, int pixel_size, float world_size) const
00594 {
00595   float max_dist = 0.5f*world_size,
00596         cell_size = world_size/float (pixel_size);
00597   float world2cell_factor = 1.0f/cell_size,
00598         world2cell_offset = 0.5f*float (pixel_size)-0.5f;
00599   float cell2world_factor = cell_size,
00600         cell2world_offset = -max_dist + 0.5f*cell_size;
00601   Eigen::Affine3f inverse_pose = pose.inverse (Eigen::Isometry);
00602   
00603   int no_of_pixels = pixel_size*pixel_size;
00604   float* surface_patch = new float[no_of_pixels];
00605   SET_ARRAY (surface_patch, -std::numeric_limits<float>::infinity (), no_of_pixels);
00606   
00607   Eigen::Vector3f position = inverse_pose.translation ();
00608   int middle_x, middle_y;
00609   getImagePoint (position, middle_x, middle_y);
00610   int min_search_radius = 2;
00611   bool still_in_range = true;
00612 
00613   for (int radius=0;  still_in_range;  ++radius) 
00614   {
00615     int x=middle_x-radius-1, y=middle_y-radius;  // Top left - 1
00616     still_in_range = radius<min_search_radius;
00617     for (int i=0; i<8*radius || (radius==0&&i==0); ++i)
00618     {
00619       if (i<=2*radius) ++x; else if (i<=4*radius) ++y; else if (i<=6*radius) --x; else --y;
00620 
00621       Eigen::Vector3f point1, point2, point3;
00622       if (!isValid (x,y) || !isValid (x+1,y+1))
00623         continue;
00624       getPoint (x, y, point1);
00625       point1 = pose*point1;
00626       if (fabs (point1[2]) > max_dist)
00627         continue;
00628       
00629       getPoint (x+1, y+1, point2);
00630       point2 = pose*point2;
00631       if (fabs (point2[2]) > max_dist)
00632         continue;
00633       
00634       for (int triangle_idx=0; triangle_idx<=1; ++triangle_idx)
00635       {
00636         if (triangle_idx==0)  // First triangle
00637         {
00638           if (!isValid (x,y+1))
00639             continue;
00640           getPoint (x, y+1, point3);
00641         }
00642         else  // Second triangle
00643         {
00644           if (!isValid (x+1,y))
00645             continue;
00646           getPoint (x+1, y, point3);
00647         }
00648         point3 = pose*point3;
00649         if (fabs (point3[2]) > max_dist)
00650           continue;
00651         
00652         // Are all the points either left, right, on top or below the bottom of the surface patch?
00653         if ( (point1[0] < -max_dist  &&  point2[0] < -max_dist  &&  point3[0] < -max_dist) ||
00654             (point1[0] >  max_dist  &&  point2[0] >  max_dist  &&  point3[0] >  max_dist) ||
00655             (point1[1] < -max_dist  &&  point2[1] < -max_dist  &&  point3[1] < -max_dist) ||
00656             (point1[1] >  max_dist  &&  point2[1] >  max_dist  &&  point3[1] >  max_dist))
00657         {
00658           continue;
00659         }
00660         
00661         still_in_range = true;
00662         
00663         // Now we have a valid triangle (point1, point2, point3) in our new patch
00664         float cell1_x = world2cell_factor*point1[0] + world2cell_offset,
00665               cell1_y = world2cell_factor*point1[1] + world2cell_offset,
00666               cell1_z = point1[2],
00667               cell2_x = world2cell_factor*point2[0] + world2cell_offset,
00668               cell2_y = world2cell_factor*point2[1] + world2cell_offset,
00669               cell2_z = point2[2],
00670               cell3_x = world2cell_factor*point3[0] + world2cell_offset,
00671               cell3_y = world2cell_factor*point3[1] + world2cell_offset,
00672               cell3_z = point3[2];
00673         
00674         int min_cell_x = (std::max) (0, int (pcl_lrint (ceil ( (std::min) (cell1_x, (std::min) (cell2_x, cell3_x)))))),
00675             max_cell_x = (std::min) (pixel_size-1, int (pcl_lrint (floor ( (std::max) (cell1_x,
00676                                                                        (std::max) (cell2_x, cell3_x)))))),
00677             min_cell_y = (std::max) (0, int (pcl_lrint (ceil ( (std::min) (cell1_y, (std::min) (cell2_y, cell3_y)))))),
00678             max_cell_y = (std::min) (pixel_size-1, int (pcl_lrint (floor ( (std::max) (cell1_y,
00679                                                                        (std::max) (cell2_y, cell3_y))))));
00680         if (max_cell_x<min_cell_x || max_cell_y<min_cell_y)
00681           continue;
00682         
00683         // We will now do the following:
00684         //   For each cell in the rectangle defined by the four values above,
00685         //   we test if it is in the original triangle (in 2D).
00686         //   If this is the case, we calculate the actual point on the 3D triangle, thereby interpolating the result
00687         //   See http://www.blackpawn.com/texts/pointinpoly/default.html
00688         Eigen::Vector2f cell1 (cell1_x, cell1_y),
00689                         cell2 (cell2_x, cell2_y),
00690                         cell3 (cell3_x, cell3_y),
00691                         v0 = cell3 - cell1,
00692                         v1 = cell2 - cell1;
00693         float dot00 = v0.dot (v0),
00694               dot01 = v0.dot (v1),
00695               dot11 = v1.dot (v1),
00696               invDenom = 1.0f / (dot00 * dot11 - dot01 * dot01);
00697         
00698         for (int cell_x=min_cell_x; cell_x<=max_cell_x; ++cell_x)
00699         {
00700           for (int cell_y=min_cell_y; cell_y<=max_cell_y; ++cell_y)
00701           {
00702             Eigen::Vector2f current_cell (cell_x, cell_y),
00703                             v2 = current_cell - cell1;
00704             float dot02 = v0.dot (v2),
00705                   dot12 = v1.dot (v2),
00706                   u = (dot11 * dot02 - dot01 * dot12) * invDenom,
00707                   v = (dot00 * dot12 - dot01 * dot02) * invDenom;
00708             bool point_in_triangle = (u > -0.01) && (v >= -0.01) && (u + v <= 1.01);
00709             
00710             if (!point_in_triangle)
00711               continue;
00712             
00713             float new_value = cell1_z + u* (cell3_z-cell1_z) + v* (cell2_z-cell1_z);
00714             
00715             float& value = surface_patch[cell_y*pixel_size + cell_x];
00716             if (pcl_isinf (value))
00717               value = new_value;
00718             else
00719               value = (std::min) (value, new_value);
00720           }
00721         }
00722       }
00723     }
00724   }
00725   
00726   // Now find out, if there should be max ranges
00727   for (int cell_y=0; cell_y<pixel_size; ++cell_y)
00728   {
00729     for (int cell_x=0; cell_x<pixel_size; ++cell_x)
00730     {
00731       int index= cell_y*pixel_size + cell_x;
00732       float& value = surface_patch[index];
00733       if (!pcl_isinf (value))
00734         continue;
00735       
00736       // Go through immediate neighbors
00737       bool is_background = false;
00738       for (int cell2_y=cell_y-1; cell2_y<=cell_y+1&&!is_background; ++cell2_y)
00739       {
00740         for (int cell2_x=cell_x-1; cell2_x<=cell_x+1; ++cell2_x)
00741         {
00742           if (cell2_x<0||cell2_x>=pixel_size||cell2_y<0||cell2_y>=pixel_size || (cell2_x==cell_x && cell2_y==cell_y))
00743             continue;
00744           float neighbor_value = surface_patch[cell2_y*pixel_size + cell2_x];
00745           if (pcl_isfinite (neighbor_value))
00746           {
00747             float cell_pos_x = static_cast<float> (cell_x) + 0.6f * static_cast<float> (cell_x - cell2_x),
00748                   cell_pos_y = static_cast<float> (cell_y) + 0.6f * static_cast<float> (cell_y - cell2_y);
00749             Eigen::Vector3f fake_point (cell2world_factor* (cell_pos_x)+cell2world_offset,
00750                                         cell2world_factor*cell_pos_y+cell2world_offset, neighbor_value);
00751             fake_point = inverse_pose*fake_point;
00752             float range_difference = getRangeDifference (fake_point);
00753             if (range_difference > max_dist)
00754             {
00755               value = std::numeric_limits<float>::infinity ();
00756               is_background = true;
00757               break;
00758             }
00759           }
00760         }
00761       }
00762       if (is_background)
00763       {
00764         // Set all -INFINITY neighbors to INFINITY
00765         for (int cell2_y=cell_y-1; cell2_y<=cell_y+1; ++cell2_y)
00766         {
00767           for (int cell2_x=cell_x-1; cell2_x<=cell_x+1; ++cell2_x)
00768           {
00769             if (cell2_x<0||cell2_x>=pixel_size||cell2_y<0||cell2_y>=pixel_size || (cell2_x==cell_x && cell2_y==cell_y))
00770               continue;
00771             int index2 = cell2_y*pixel_size + cell2_x;
00772             float& neighbor_value = surface_patch[index2];
00773             if (pcl_isinf (neighbor_value) && neighbor_value<0)
00774               neighbor_value = std::numeric_limits<float>::infinity ();
00775           }
00776         }
00777       }
00778     }
00779   }
00780   
00781   return surface_patch;
00782 }
00783 
00785 float* RangeImage::getInterpolatedSurfaceProjection (const Eigen::Vector3f& point, int pixel_size,
00786                                                      float world_size) const
00787 {
00788   Eigen::Affine3f pose = getTransformationToViewerCoordinateFrame (point);
00789   return (getInterpolatedSurfaceProjection (pose, pixel_size, world_size));
00790 }
00791 
00793 bool 
00794 RangeImage::getNormalBasedUprightTransformation (const Eigen::Vector3f& point, float max_dist,
00795                                                  Eigen::Affine3f& transformation) const
00796 {
00797   int x, y;
00798   getImagePoint (point, x, y);
00799 
00800   Eigen::Vector3f neighbor;
00801   VectorAverage3f vector_average;
00802   float max_dist_squared=max_dist*max_dist, max_dist_reciprocal=1.0f/max_dist;
00803   
00804   bool still_in_range = true;
00805   for (int radius=1;  still_in_range;  ++radius) 
00806   {
00807     int x2=x-radius-1, y2=y-radius;  // Top left - 1
00808     still_in_range = false;
00809     for (int i=0; i<8*radius; ++i)
00810     {
00811       if (i<=2*radius) ++x2; else if (i<=4*radius) ++y2; else if (i<=6*radius) --x2; else --y2;
00812       if (!isValid (x2, y2))
00813       {
00814         continue;
00815       }
00816       getPoint (x2, y2, neighbor);
00817       float distance_squared = (neighbor-point).squaredNorm ();
00818       if (distance_squared > max_dist_squared)
00819       {
00820         continue;
00821       }
00822       still_in_range = true;
00823       float distance = sqrtf (distance_squared),
00824             weight = distance*max_dist_reciprocal;
00825       vector_average.add (neighbor, weight);
00826     }
00827   }
00828   
00829   Eigen::Vector3f normal, point_on_plane;
00830   if (vector_average.getNoOfSamples () > 10)
00831   {
00832     Eigen::Vector3f eigen_values, eigen_vector2, eigen_vector3;
00833     vector_average.doPCA (eigen_values, normal, eigen_vector2, eigen_vector3);
00834     if (normal.dot ( (vector_average.getMean ()-getSensorPos ()).normalized ()) < 0.0f)
00835       normal *= -1.0f;
00836     point_on_plane = (normal.dot (vector_average.getMean ()) - normal.dot (point))*normal + point;
00837   }
00838   else
00839   {
00840     if (!getNormalForClosestNeighbors (x, y, 2, point, 15, normal, &point_on_plane, 1))
00841       return false;
00842   }
00843   getTransformationFromTwoUnitVectorsAndOrigin (Eigen::Vector3f (0.0f, 1.0f, 0.0f),
00844                                                 normal, point_on_plane, transformation);
00845   
00846   return (true);
00847 }
00848 
00850 void 
00851 RangeImage::getSurfaceAngleChangeImages (int radius, float*& angle_change_image_x, float*& angle_change_image_y) const
00852 {
00853   MEASURE_FUNCTION_TIME;
00854   int size = width*height;
00855   angle_change_image_x = new float[size];
00856   angle_change_image_y = new float[size];
00857   for (int y=0; y<int (height); ++y)
00858   {
00859     for (int x=0; x<int (width); ++x)
00860     {
00861       int index = y*width+x;
00862       getSurfaceAngleChange (x, y, radius, angle_change_image_x[index], angle_change_image_y[index]);
00863     }
00864   }
00865 }
00866 
00868 void 
00869 RangeImage::getAcutenessValueImages (int pixel_distance, float*& acuteness_value_image_x,
00870                                      float*& acuteness_value_image_y) const
00871 {
00872   MEASURE_FUNCTION_TIME;
00873   int size = width*height;
00874   acuteness_value_image_x = new float[size];
00875   acuteness_value_image_y = new float[size];
00876   for (int y=0; y<int (height); ++y)
00877   {
00878     for (int x=0; x<int (width); ++x)
00879     {
00880       int index = y*width+x;
00881       acuteness_value_image_x[index] = getAcutenessValue (x, y, x+pixel_distance, y);
00882       acuteness_value_image_y[index] = getAcutenessValue (x, y, x, y+pixel_distance);
00883     }
00884   }
00885 }
00886 
00888 float* 
00889 RangeImage::getImpactAngleImageBasedOnLocalNormals (int radius) const
00890 {
00891   MEASURE_FUNCTION_TIME;
00892   int size = width*height;
00893   float* impact_angle_image = new float[size];
00894   for (int y=0; y<int (height); ++y)
00895   {
00896     for (int x=0; x<int (width); ++x)
00897     {
00898       impact_angle_image[y*width+x] = getImpactAngleBasedOnLocalNormal (x, y, radius);
00899     }
00900   }
00901   return impact_angle_image;
00902 }
00903 
00905 void 
00906 RangeImage::getRangeImageWithSmoothedSurface (int radius, RangeImage& smoothed_range_image) const
00907 {
00908   int step_size = (std::max) (1, radius/2);
00909   int no_of_nearest_neighbors = static_cast<int> (pow (static_cast<double> (radius / step_size + 1), 2.0));
00910   
00911   smoothed_range_image = *this;
00912   Eigen::Vector3f sensor_pos = getSensorPos ();
00913   for (int y=0; y<int (height); ++y)
00914   {
00915     for (int x=0; x<int (width); ++x)
00916     {
00917       PointWithRange& point = smoothed_range_image.getPoint (x, y);
00918       if (pcl_isinf (point.range))
00919         continue;
00920       Eigen::Vector3f normal, mean, eigen_values;
00921       float used_squared_max_distance;
00922       getSurfaceInformation (x, y, radius, point.getVector3fMap (), no_of_nearest_neighbors,
00923                              step_size, used_squared_max_distance,
00924                              normal, mean, eigen_values);
00925       
00926       Eigen::Vector3f viewing_direction = (point.getVector3fMap ()-sensor_pos).normalized ();
00927       float new_range = normal.dot (mean-sensor_pos) / normal.dot (viewing_direction);
00928       point.range = new_range;
00929       calculate3DPoint (static_cast<float> (x), static_cast<float> (y), point.range, point);
00930       
00931       const PointWithRange& original_point = getPoint (x, y);
00932       float distance_squared = squaredEuclideanDistance (original_point, point);
00933       if (distance_squared > used_squared_max_distance)
00934         point = original_point;
00935     }
00936   }
00937 }
00938 
00940 void 
00941 RangeImage::extractFarRanges (const sensor_msgs::PointCloud2& point_cloud_data,
00942                               PointCloud<PointWithViewpoint>& far_ranges)
00943 {
00944   int x_idx = -1, y_idx = -1, z_idx = -1,
00945       vp_x_idx = -1, vp_y_idx = -1, vp_z_idx = -1, distance_idx = -1;
00946   for (int d = 0; d < static_cast<int> (point_cloud_data.fields.size ()); ++d)
00947   {
00948     if (point_cloud_data.fields[d].name == "x") x_idx = d;
00949     if (point_cloud_data.fields[d].name == "y") y_idx = d;
00950     if (point_cloud_data.fields[d].name == "z") z_idx = d;
00951     if (point_cloud_data.fields[d].name == "vp_x") vp_x_idx = d;
00952     if (point_cloud_data.fields[d].name == "vp_y") vp_y_idx = d;
00953     if (point_cloud_data.fields[d].name == "vp_z") vp_z_idx = d;
00954     if (point_cloud_data.fields[d].name == "distance") distance_idx = d;
00955   }
00956   
00957   if (x_idx<0 || y_idx<0 || z_idx<0 || vp_x_idx<0 || vp_y_idx<0 || vp_z_idx<0 || distance_idx<0)
00958   {
00959     return;
00960   }
00961   
00962   int point_step = point_cloud_data.point_step;
00963   const unsigned char* data = &point_cloud_data.data[0];
00964   int x_offset = point_cloud_data.fields[x_idx].offset,
00965       y_offset = point_cloud_data.fields[y_idx].offset,
00966       z_offset = point_cloud_data.fields[z_idx].offset,
00967       vp_x_offset = point_cloud_data.fields[vp_x_idx].offset,
00968       vp_y_offset = point_cloud_data.fields[vp_y_idx].offset,
00969       vp_z_offset = point_cloud_data.fields[vp_z_idx].offset,
00970       distance_offset = point_cloud_data.fields[distance_idx].offset;
00971   
00972   for (size_t point_idx = 0; point_idx < point_cloud_data.width*point_cloud_data.height; ++point_idx)
00973   {
00974     float x = *reinterpret_cast<const float*> (data+x_offset), 
00975           y = *reinterpret_cast<const float*> (data+y_offset), 
00976           z = *reinterpret_cast<const float*> (data+z_offset),
00977           vp_x = *reinterpret_cast<const float*> (data+vp_x_offset),
00978           vp_y = *reinterpret_cast<const float*> (data+vp_y_offset),
00979           vp_z = *reinterpret_cast<const float*> (data+vp_z_offset),
00980           distance = *reinterpret_cast<const float*> (data+distance_offset);
00981     data+=point_step;
00982     
00983     if (!pcl_isfinite (x) && pcl_isfinite (distance))
00984     {
00985       PointWithViewpoint point;
00986       point.x=distance; point.y=y; point.z=z;
00987       point.vp_x=vp_x; point.vp_y=vp_y; point.vp_z=vp_z;
00988       far_ranges.points.push_back (point);
00989     }
00990   }
00991   far_ranges.width= static_cast<uint32_t> (far_ranges.points.size ());  far_ranges.height = 1;
00992   far_ranges.is_dense = false;
00993 }
00994 
00995 float
00996 RangeImage::getOverlap (const RangeImage& other_range_image, const Eigen::Affine3f& relative_transformation,
00997                         int search_radius, float max_distance, int pixel_step) const
00998 {
00999   int hits_counter=0, valid_points_counter=0;
01000   
01001   float max_distance_squared = max_distance*max_distance;
01002   
01003   # pragma omp parallel for num_threads (max_no_of_threads) default (shared) schedule (dynamic, 1) \
01004                         reduction (+ : valid_points_counter) reduction (+ : hits_counter)
01005   for (int other_y=0; other_y<int (other_range_image.height); other_y+=pixel_step)
01006   {
01007     for (int other_x=0; other_x<int (other_range_image.width); other_x+=pixel_step)
01008     {
01009       const PointWithRange& point = other_range_image.getPoint (other_x, other_y);
01010       if (!pcl_isfinite (point.range))
01011         continue;
01012       ++valid_points_counter;
01013       Eigen::Vector3f transformed_point = relative_transformation * point.getVector3fMap ();
01014       int x,y;
01015       getImagePoint (transformed_point, x, y);
01016       float closest_distance = max_distance_squared;
01017       Eigen::Vector3f closest_point (0.0f, 0.0f, 0.0f);
01018       bool found_neighbor = false;
01019       for (int y2=y-pixel_step*search_radius; y2<=y+pixel_step*search_radius; y2+=pixel_step)
01020       {
01021         for (int x2=x-pixel_step*search_radius; x2<=x+pixel_step*search_radius; x2+=pixel_step)
01022         {
01023           const PointWithRange& neighbor = getPoint (x2, y2);
01024           if (!pcl_isfinite (neighbor.range))
01025             continue;
01026           float distance = (transformed_point-neighbor.getVector3fMap ()).squaredNorm ();
01027           if (distance < closest_distance)
01028           {
01029             closest_distance = distance;
01030             closest_point = neighbor.getVector3fMap ();
01031             found_neighbor = true;
01032           }
01033         }
01034       }
01035 
01036       if (found_neighbor)
01037       {
01038         ++hits_counter;
01039       }
01040     }
01041   }
01042   return static_cast<float> (hits_counter)/static_cast<float> (valid_points_counter);
01043 }
01044 
01045 }  // namespace end
01046 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:37