range_image.hpp
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 
00038 #include <pcl/pcl_macros.h>
00039 #include <pcl/common/distances.h>
00040 
00041 namespace pcl
00042 {
00043 
00045 inline float
00046 RangeImage::asinLookUp (float value)
00047 {
00048   return (asin_lookup_table[
00049       static_cast<int> (
00050         static_cast<float> (pcl_lrintf ( (static_cast<float> (lookup_table_size) / 2.0f) * value)) + 
00051         static_cast<float> (lookup_table_size) / 2.0f)]);
00052 }
00053 
00055 inline float
00056 RangeImage::atan2LookUp (float y, float x)
00057 {
00058   float ret;
00059   if (fabsf (x) < fabsf (y)) 
00060   {
00061     ret = atan_lookup_table[
00062       static_cast<int> (
00063           static_cast<float> (pcl_lrintf ( (static_cast<float> (lookup_table_size) / 2.0f) * (x / y))) + 
00064           static_cast<float> (lookup_table_size) / 2.0f)];
00065     ret = static_cast<float> (x*y > 0 ? M_PI/2-ret : -M_PI/2-ret);
00066   }
00067   else
00068     ret = atan_lookup_table[
00069       static_cast<int> (
00070           static_cast<float> (pcl_lrintf ( (static_cast<float> (lookup_table_size) / 2.0f) * (y / x))) + 
00071           static_cast<float> (lookup_table_size)/2.0f)];
00072   if (x < 0)
00073     ret = static_cast<float> (y < 0 ? ret-M_PI : ret+M_PI);
00074   
00075   return (ret);
00076 }
00077 
00079 inline float
00080 RangeImage::cosLookUp (float value)
00081 {
00082   int cell_idx = static_cast<int> (pcl_lrintf ( (static_cast<float> (lookup_table_size)-1) * fabsf (value) / (2.0f * M_PI)));
00083   return (cos_lookup_table[cell_idx]);
00084 }
00085 
00087 template <typename PointCloudType> void 
00088 RangeImage::createFromPointCloud (const PointCloudType& point_cloud, float angular_resolution,
00089                                   float max_angle_width, float max_angle_height,
00090                                   const Eigen::Affine3f& sensor_pose, RangeImage::CoordinateFrame coordinate_frame,
00091                                   float noise_level, float min_range, int border_size)
00092 {
00093   createFromPointCloud (point_cloud, angular_resolution, angular_resolution, max_angle_width, max_angle_height,
00094                         sensor_pose, coordinate_frame, noise_level, min_range, border_size);
00095 }
00096 
00098 template <typename PointCloudType> void 
00099 RangeImage::createFromPointCloud (const PointCloudType& point_cloud,
00100                                   float angular_resolution_x, float angular_resolution_y,
00101                                   float max_angle_width, float max_angle_height,
00102                                   const Eigen::Affine3f& sensor_pose, RangeImage::CoordinateFrame coordinate_frame,
00103                                   float noise_level, float min_range, int border_size)
00104 {
00105   setAngularResolution (angular_resolution_x, angular_resolution_y);
00106   
00107   width  = static_cast<uint32_t> (pcl_lrint (floor (max_angle_width*angular_resolution_x_reciprocal_)));
00108   height = static_cast<uint32_t> (pcl_lrint (floor (max_angle_height*angular_resolution_y_reciprocal_)));
00109   
00110   int full_width  = static_cast<int> (pcl_lrint (floor (pcl::deg2rad (360.0f)*angular_resolution_x_reciprocal_))),
00111       full_height = static_cast<int> (pcl_lrint (floor (pcl::deg2rad (180.0f)*angular_resolution_y_reciprocal_)));
00112   image_offset_x_ = (full_width -static_cast<int> (width) )/2;
00113   image_offset_y_ = (full_height-static_cast<int> (height))/2;
00114   is_dense = false;
00115   
00116   getCoordinateFrameTransformation (coordinate_frame, to_world_system_);
00117   to_world_system_ = sensor_pose * to_world_system_;
00118   
00119   to_range_image_system_ = to_world_system_.inverse (Eigen::Isometry);
00120   //std::cout << "to_world_system_ is\n"<<to_world_system_<<"\nand to_range_image_system_ is\n"<<to_range_image_system_<<"\n\n";
00121   
00122   unsigned int size = width*height;
00123   points.clear ();
00124   points.resize (size, unobserved_point);
00125   
00126   int top=height, right=-1, bottom=-1, left=width;
00127   doZBuffer (point_cloud, noise_level, min_range, top, right, bottom, left);
00128   
00129   cropImage (border_size, top, right, bottom, left);
00130   
00131   recalculate3DPointPositions ();
00132 }
00133 
00135 template <typename PointCloudType> void
00136 RangeImage::createFromPointCloudWithKnownSize (const PointCloudType& point_cloud, float angular_resolution,
00137                                               const Eigen::Vector3f& point_cloud_center, float point_cloud_radius,
00138                                               const Eigen::Affine3f& sensor_pose, RangeImage::CoordinateFrame coordinate_frame,
00139                                               float noise_level, float min_range, int border_size)
00140 {
00141   createFromPointCloudWithKnownSize (point_cloud, angular_resolution, angular_resolution, point_cloud_center, point_cloud_radius,
00142                                      sensor_pose, coordinate_frame, noise_level, min_range, border_size);
00143 }
00144 
00146 template <typename PointCloudType> void
00147 RangeImage::createFromPointCloudWithKnownSize (const PointCloudType& point_cloud,
00148                                                float angular_resolution_x, float angular_resolution_y,
00149                                                const Eigen::Vector3f& point_cloud_center, float point_cloud_radius,
00150                                                const Eigen::Affine3f& sensor_pose, RangeImage::CoordinateFrame coordinate_frame,
00151                                                float noise_level, float min_range, int border_size)
00152 {
00153   //MEASURE_FUNCTION_TIME;
00154   
00155   //std::cout << "Starting to create range image from "<<point_cloud.points.size ()<<" points.\n";
00156   
00157   // If the sensor pose is inside of the sphere we have to calculate the image the normal way
00158   if ((point_cloud_center-sensor_pose.translation()).norm() <= point_cloud_radius) {
00159     createFromPointCloud (point_cloud, angular_resolution_x, angular_resolution_y,
00160                           pcl::deg2rad (360.0f), pcl::deg2rad (180.0f),
00161                           sensor_pose, coordinate_frame, noise_level, min_range, border_size);
00162     return;
00163   }
00164   
00165   setAngularResolution (angular_resolution_x, angular_resolution_y);
00166   
00167   getCoordinateFrameTransformation (coordinate_frame, to_world_system_);
00168   to_world_system_ = sensor_pose * to_world_system_;
00169   to_range_image_system_ = to_world_system_.inverse (Eigen::Isometry);
00170   
00171   float max_angle_size = getMaxAngleSize (sensor_pose, point_cloud_center, point_cloud_radius);
00172   int pixel_radius_x = pcl_lrint (ceil (0.5f*max_angle_size*angular_resolution_x_reciprocal_)),
00173       pixel_radius_y = pcl_lrint (ceil (0.5f*max_angle_size*angular_resolution_y_reciprocal_));
00174   width  = 2*pixel_radius_x;
00175   height = 2*pixel_radius_y;
00176   is_dense = false;
00177   
00178   image_offset_x_ = image_offset_y_ = 0;  // temporary values for getImagePoint
00179   int center_pixel_x, center_pixel_y;
00180   getImagePoint (point_cloud_center, center_pixel_x, center_pixel_y);
00181   image_offset_x_ = (std::max) (0, center_pixel_x-pixel_radius_x);
00182   image_offset_y_ = (std::max) (0, center_pixel_y-pixel_radius_y);
00183 
00184   points.clear ();
00185   points.resize (width*height, unobserved_point);
00186   
00187   int top=height, right=-1, bottom=-1, left=width;
00188   doZBuffer (point_cloud, noise_level, min_range, top, right, bottom, left);
00189   
00190   cropImage (border_size, top, right, bottom, left);
00191   
00192   recalculate3DPointPositions ();
00193 }
00194 
00196 template <typename PointCloudTypeWithViewpoints> void 
00197 RangeImage::createFromPointCloudWithViewpoints (const PointCloudTypeWithViewpoints& point_cloud,
00198                                                 float angular_resolution,
00199                                                 float max_angle_width, float max_angle_height,
00200                                                 RangeImage::CoordinateFrame coordinate_frame,
00201                                                 float noise_level, float min_range, int border_size)
00202 {
00203   createFromPointCloudWithViewpoints (point_cloud, angular_resolution, angular_resolution,
00204                                       max_angle_width, max_angle_height, coordinate_frame,
00205                                       noise_level, min_range, border_size);
00206 }
00207 
00209 template <typename PointCloudTypeWithViewpoints> void 
00210 RangeImage::createFromPointCloudWithViewpoints (const PointCloudTypeWithViewpoints& point_cloud,
00211                                                 float angular_resolution_x, float angular_resolution_y,
00212                                                 float max_angle_width, float max_angle_height,
00213                                                 RangeImage::CoordinateFrame coordinate_frame,
00214                                                 float noise_level, float min_range, int border_size)
00215 {
00216   Eigen::Vector3f average_viewpoint = getAverageViewPoint (point_cloud);
00217   Eigen::Affine3f sensor_pose = static_cast<Eigen::Affine3f> (Eigen::Translation3f (average_viewpoint));
00218   createFromPointCloud (point_cloud, angular_resolution_x, angular_resolution_y, max_angle_width, max_angle_height,
00219                         sensor_pose, coordinate_frame, noise_level, min_range, border_size);
00220 }
00221 
00223 template <typename PointCloudType> void 
00224 RangeImage::doZBuffer (const PointCloudType& point_cloud, float noise_level, float min_range, int& top, int& right, int& bottom, int& left)
00225 {
00226   typedef typename PointCloudType::PointType PointType2;
00227   const typename pcl::PointCloud<PointType2>::VectorType &points2 = point_cloud.points;
00228   
00229   unsigned int size = width*height;
00230   int* counters = new int[size];
00231   ERASE_ARRAY (counters, size);
00232   
00233   top=height; right=-1; bottom=-1; left=width;
00234   
00235   float x_real, y_real, range_of_current_point;
00236   int x, y;
00237   for (typename pcl::PointCloud<PointType2>::VectorType::const_iterator it=points2.begin (); it!=points2.end (); ++it)
00238   {
00239     if (!isFinite (*it))  // Check for NAN etc
00240       continue;
00241     Vector3fMapConst current_point = it->getVector3fMap ();
00242     
00243     this->getImagePoint (current_point, x_real, y_real, range_of_current_point);
00244     this->real2DToInt2D (x_real, y_real, x, y);
00245     
00246     if (range_of_current_point < min_range|| !isInImage (x, y))
00247       continue;
00248     //std::cout << " ("<<current_point[0]<<", "<<current_point[1]<<", "<<current_point[2]<<") falls into pixel "<<x<<","<<y<<".\n";
00249     
00250     // Do some minor interpolation by checking the three closest neighbors to the point, that are not filled yet.
00251     int floor_x = pcl_lrint (floor (x_real)), floor_y = pcl_lrint (floor (y_real)),
00252         ceil_x  = pcl_lrint (ceil (x_real)),  ceil_y  = pcl_lrint (ceil (y_real));
00253     
00254     int neighbor_x[4], neighbor_y[4];
00255     neighbor_x[0]=floor_x; neighbor_y[0]=floor_y;
00256     neighbor_x[1]=floor_x; neighbor_y[1]=ceil_y;
00257     neighbor_x[2]=ceil_x;  neighbor_y[2]=floor_y;
00258     neighbor_x[3]=ceil_x;  neighbor_y[3]=ceil_y;
00259     //std::cout << x_real<<","<<y_real<<": ";
00260     
00261     for (int i=0; i<4; ++i)
00262     {
00263       int n_x=neighbor_x[i], n_y=neighbor_y[i];
00264       //std::cout << n_x<<","<<n_y<<" ";
00265       if (n_x==x && n_y==y)
00266         continue;
00267       if (isInImage (n_x, n_y))
00268       {
00269         int neighbor_array_pos = n_y*width + n_x;
00270         if (counters[neighbor_array_pos]==0)
00271         {
00272           float& neighbor_range = points[neighbor_array_pos].range;
00273           neighbor_range = (pcl_isinf (neighbor_range) ? range_of_current_point : (std::min) (neighbor_range, range_of_current_point));
00274           top= (std::min) (top, n_y); right= (std::max) (right, n_x); bottom= (std::max) (bottom, n_y); left= (std::min) (left, n_x);
00275         }
00276       }
00277     }
00278     //std::cout <<std::endl;
00279     
00280     // The point itself
00281     int arrayPos = y*width + x;
00282     float& range_at_image_point = points[arrayPos].range;
00283     int& counter = counters[arrayPos];
00284     bool addCurrentPoint=false, replace_with_current_point=false;
00285     
00286     if (counter==0)
00287     {
00288       replace_with_current_point = true;
00289     }
00290     else
00291     {
00292       if (range_of_current_point < range_at_image_point-noise_level)
00293       {
00294         replace_with_current_point = true;
00295       }
00296       else if (fabs (range_of_current_point-range_at_image_point)<=noise_level)
00297       {
00298         addCurrentPoint = true;
00299       }
00300     }
00301     
00302     if (replace_with_current_point)
00303     {
00304       counter = 1;
00305       range_at_image_point = range_of_current_point;
00306       top= (std::min) (top, y); right= (std::max) (right, x); bottom= (std::max) (bottom, y); left= (std::min) (left, x);
00307       //std::cout << "Adding point "<<x<<","<<y<<"\n";
00308     }
00309     else if (addCurrentPoint)
00310     {
00311       ++counter;
00312       range_at_image_point += (range_of_current_point-range_at_image_point)/counter;
00313     }
00314   }
00315   
00316   delete[] counters;
00317 }
00318 
00320 void 
00321 RangeImage::getImagePoint (float x, float y, float z, float& image_x, float& image_y, float& range) const 
00322 {
00323   Eigen::Vector3f point (x, y, z);
00324   getImagePoint (point, image_x, image_y, range);
00325 }
00326 
00328 void 
00329 RangeImage::getImagePoint (float x, float y, float z, float& image_x, float& image_y) const 
00330 {
00331   float range;
00332   getImagePoint (x, y, z, image_x, image_y, range);
00333 }
00334 
00336 void 
00337 RangeImage::getImagePoint (float x, float y, float z, int& image_x, int& image_y) const 
00338 {
00339   float image_x_float, image_y_float;
00340   getImagePoint (x, y, z, image_x_float, image_y_float);
00341   real2DToInt2D (image_x_float, image_y_float, image_x, image_y);
00342 }
00343 
00345 void 
00346 RangeImage::getImagePoint (const Eigen::Vector3f& point, float& image_x, float& image_y, float& range) const 
00347 {
00348   Eigen::Vector3f transformedPoint = to_range_image_system_ * point;
00349   range = transformedPoint.norm ();
00350   float angle_x = atan2LookUp (transformedPoint[0], transformedPoint[2]),
00351         angle_y = asinLookUp (transformedPoint[1]/range);
00352   getImagePointFromAngles (angle_x, angle_y, image_x, image_y);
00353   //std::cout << " ("<<point[0]<<","<<point[1]<<","<<point[2]<<")"
00354             //<< " => ("<<transformedPoint[0]<<","<<transformedPoint[1]<<","<<transformedPoint[2]<<")"
00355             //<< " => "<<angle_x<<","<<angle_y<<" => "<<image_x<<","<<image_y<<"\n";
00356 }
00357 
00359 void 
00360 RangeImage::getImagePoint (const Eigen::Vector3f& point, int& image_x, int& image_y, float& range) const {
00361   float image_x_float, image_y_float;
00362   getImagePoint (point, image_x_float, image_y_float, range);
00363   real2DToInt2D (image_x_float, image_y_float, image_x, image_y);
00364 }
00365 
00367 void 
00368 RangeImage::getImagePoint (const Eigen::Vector3f& point, float& image_x, float& image_y) const
00369 {
00370   float range;
00371   getImagePoint (point, image_x, image_y, range);
00372 }
00373 
00375 void 
00376 RangeImage::getImagePoint (const Eigen::Vector3f& point, int& image_x, int& image_y) const
00377 {
00378   float image_x_float, image_y_float;
00379   getImagePoint (point, image_x_float, image_y_float);
00380   real2DToInt2D (image_x_float, image_y_float, image_x, image_y);
00381 }
00382 
00384 float 
00385 RangeImage::checkPoint (const Eigen::Vector3f& point, PointWithRange& point_in_image) const
00386 {
00387   int image_x, image_y;
00388   float range;
00389   getImagePoint (point, image_x, image_y, range);
00390   if (!isInImage (image_x, image_y))
00391     point_in_image = unobserved_point;
00392   else
00393     point_in_image = getPoint (image_x, image_y);
00394   return range;
00395 }
00396 
00398 float 
00399 RangeImage::getRangeDifference (const Eigen::Vector3f& point) const
00400 {
00401   int image_x, image_y;
00402   float range;
00403   getImagePoint (point, image_x, image_y, range);
00404   if (!isInImage (image_x, image_y))
00405     return -std::numeric_limits<float>::infinity ();
00406   float image_point_range = getPoint (image_x, image_y).range;
00407   if (pcl_isinf (image_point_range))
00408   {
00409     if (image_point_range > 0.0f)
00410       return std::numeric_limits<float>::infinity ();
00411     else
00412       return -std::numeric_limits<float>::infinity ();
00413   }
00414   return image_point_range - range;
00415 }
00416 
00418 void 
00419 RangeImage::getImagePointFromAngles (float angle_x, float angle_y, float& image_x, float& image_y) const
00420 {
00421   image_x = (angle_x*cosLookUp (angle_y) + static_cast<float> (M_PI))*angular_resolution_x_reciprocal_ - static_cast<float> (image_offset_x_);
00422   image_y = (angle_y + 0.5f*static_cast<float> (M_PI))*angular_resolution_y_reciprocal_ - static_cast<float> (image_offset_y_);
00423 }
00424 
00426 void 
00427 RangeImage::real2DToInt2D (float x, float y, int& xInt, int& yInt) const
00428 {
00429   xInt = static_cast<int> (pcl_lrintf (x)); 
00430   yInt = static_cast<int> (pcl_lrintf (y));
00431 }
00432 
00434 bool 
00435 RangeImage::isInImage (int x, int y) const
00436 {
00437   return (x >= 0 && x < static_cast<int> (width) && y >= 0 && y < static_cast<int> (height));
00438 }
00439 
00441 bool 
00442 RangeImage::isValid (int x, int y) const
00443 {
00444   return isInImage (x,y) && pcl_isfinite (getPoint (x,y).range);
00445 }
00446 
00448 bool 
00449 RangeImage::isValid (int index) const
00450 {
00451   return pcl_isfinite (getPoint (index).range);
00452 }
00453 
00455 bool 
00456 RangeImage::isObserved (int x, int y) const
00457 {
00458   if (!isInImage (x,y) || (pcl_isinf (getPoint (x,y).range)&&getPoint (x,y).range<0.0f))
00459     return false;
00460   return true;
00461 }
00462 
00464 bool 
00465 RangeImage::isMaxRange (int x, int y) const
00466 {
00467   float range = getPoint (x,y).range;
00468   return pcl_isinf (range) && range>0.0f;
00469 }
00470 
00472 const PointWithRange& 
00473 RangeImage::getPoint (int image_x, int image_y) const
00474 {
00475   if (!isInImage (image_x, image_y))
00476     return unobserved_point;
00477   return points[image_y*width + image_x];
00478 }
00479 
00481 const PointWithRange& 
00482 RangeImage::getPointNoCheck (int image_x, int image_y) const
00483 {
00484   return points[image_y*width + image_x];
00485 }
00486 
00488 PointWithRange& 
00489 RangeImage::getPointNoCheck (int image_x, int image_y)
00490 {
00491   return points[image_y*width + image_x];
00492 }
00493 
00495 PointWithRange& 
00496 RangeImage::getPoint (int image_x, int image_y)
00497 {
00498   return points[image_y*width + image_x];
00499 }
00500 
00501 
00503 const PointWithRange& 
00504 RangeImage::getPoint (int index) const
00505 {
00506   return points[index];
00507 }
00508 
00510 const PointWithRange&
00511 RangeImage::getPoint (float image_x, float image_y) const
00512 {
00513   int x, y;
00514   real2DToInt2D (image_x, image_y, x, y);
00515   return getPoint (x, y);
00516 }
00517 
00519 PointWithRange& 
00520 RangeImage::getPoint (float image_x, float image_y)
00521 {
00522   int x, y;
00523   real2DToInt2D (image_x, image_y, x, y);
00524   return getPoint (x, y);
00525 }
00526 
00528 void 
00529 RangeImage::getPoint (int image_x, int image_y, Eigen::Vector3f& point) const
00530 {
00531   //std::cout << getPoint (image_x, image_y)<< " - " << getPoint (image_x, image_y).getVector3fMap ()<<"\n";
00532   point = getPoint (image_x, image_y).getVector3fMap ();
00533 }
00534 
00536 void 
00537 RangeImage::getPoint (int index, Eigen::Vector3f& point) const
00538 {
00539   point = getPoint (index).getVector3fMap ();
00540 }
00541 
00543 const Eigen::Map<const Eigen::Vector3f> 
00544 RangeImage::getEigenVector3f (int x, int y) const
00545 {
00546   return getPoint (x, y).getVector3fMap ();
00547 }
00548 
00550 const Eigen::Map<const Eigen::Vector3f> 
00551 RangeImage::getEigenVector3f (int index) const
00552 {
00553   return getPoint (index).getVector3fMap ();
00554 }
00555 
00557 void 
00558 RangeImage::calculate3DPoint (float image_x, float image_y, float range, Eigen::Vector3f& point) const 
00559 {
00560   float angle_x, angle_y;
00561   //std::cout << image_x<<","<<image_y<<","<<range;
00562   getAnglesFromImagePoint (image_x, image_y, angle_x, angle_y);
00563   
00564   float cosY = cosf (angle_y);
00565   point = Eigen::Vector3f (range * sinf (angle_x) * cosY, range * sinf (angle_y), range * cosf (angle_x)*cosY);
00566   point = to_world_system_ * point;
00567 }
00568 
00570 void 
00571 RangeImage::calculate3DPoint (float image_x, float image_y, Eigen::Vector3f& point) const
00572 {
00573   const PointWithRange& point_in_image = getPoint (image_x, image_y);
00574   calculate3DPoint (image_x, image_y, point_in_image.range, point);
00575 }
00576 
00578 void 
00579 RangeImage::calculate3DPoint (float image_x, float image_y, float range, PointWithRange& point) const {
00580   point.range = range;
00581   Eigen::Vector3f tmp_point;
00582   calculate3DPoint (image_x, image_y, range, tmp_point);
00583   point.x=tmp_point[0];  point.y=tmp_point[1];  point.z=tmp_point[2];
00584 }
00585 
00587 void 
00588 RangeImage::calculate3DPoint (float image_x, float image_y, PointWithRange& point) const
00589 {
00590   const PointWithRange& point_in_image = getPoint (image_x, image_y);
00591   calculate3DPoint (image_x, image_y, point_in_image.range, point);
00592 }
00593 
00595 void 
00596 RangeImage::getAnglesFromImagePoint (float image_x, float image_y, float& angle_x, float& angle_y) const 
00597 {
00598   angle_y = (image_y+static_cast<float> (image_offset_y_))*angular_resolution_y_ - 0.5f*static_cast<float> (M_PI);
00599   float cos_angle_y = cosf (angle_y);
00600   angle_x = (cos_angle_y==0.0f ? 0.0f : ( (image_x+ static_cast<float> (image_offset_x_))*angular_resolution_x_ - static_cast<float> (M_PI))/cos_angle_y);
00601 }
00602 
00604 float 
00605 RangeImage::getImpactAngle (int x1, int y1, int x2, int y2) const
00606 {
00607   if (!isInImage (x1, y1) || !isInImage (x2,y2))
00608     return -std::numeric_limits<float>::infinity ();
00609   return getImpactAngle (getPoint (x1,y1),getPoint (x2,y2));
00610 }
00611 
00613 float 
00614 RangeImage::getImpactAngle (const PointWithRange& point1, const PointWithRange& point2) const {
00615   if ( (pcl_isinf (point1.range)&&point1.range<0) || (pcl_isinf (point2.range)&&point2.range<0))
00616     return -std::numeric_limits<float>::infinity ();
00617   
00618   float r1 = (std::min) (point1.range, point2.range),
00619         r2 = (std::max) (point1.range, point2.range);
00620   float impact_angle = static_cast<float> (0.5f * M_PI);
00621   
00622   if (pcl_isinf (r2)) 
00623   {
00624     if (r2 > 0.0f && !pcl_isinf (r1))
00625       impact_angle = 0.0f;
00626   }
00627   else if (!pcl_isinf (r1)) 
00628   {
00629     float r1Sqr = r1*r1,
00630           r2Sqr = r2*r2,
00631           dSqr  = squaredEuclideanDistance (point1, point2),
00632           d     = sqrtf (dSqr);
00633     float cos_impact_angle = (r2Sqr + dSqr - r1Sqr)/ (2.0f*r2*d);
00634     cos_impact_angle = (std::max) (0.0f, (std::min) (1.0f, cos_impact_angle));
00635     impact_angle = acosf (cos_impact_angle);  // Using the cosine rule
00636   }
00637   
00638   if (point1.range > point2.range)
00639     impact_angle = -impact_angle;
00640   
00641   return impact_angle;
00642 }
00643 
00645 float 
00646 RangeImage::getAcutenessValue (const PointWithRange& point1, const PointWithRange& point2) const
00647 {
00648   float impact_angle = getImpactAngle (point1, point2);
00649   if (pcl_isinf (impact_angle))
00650     return -std::numeric_limits<float>::infinity ();
00651   float ret = 1.0f - float (fabs (impact_angle)/ (0.5f*M_PI));
00652   if (impact_angle < 0.0f)
00653     ret = -ret;
00654   //if (fabs (ret)>1)
00655     //std::cout << PVARAC (impact_angle)<<PVARN (ret);
00656   return ret;
00657 }
00658 
00660 float 
00661 RangeImage::getAcutenessValue (int x1, int y1, int x2, int y2) const
00662 {
00663   if (!isInImage (x1, y1) || !isInImage (x2,y2))
00664     return -std::numeric_limits<float>::infinity ();
00665   return getAcutenessValue (getPoint (x1,y1), getPoint (x2,y2));
00666 }
00667 
00669 const Eigen::Vector3f 
00670 RangeImage::getSensorPos () const
00671 {
00672   return Eigen::Vector3f (to_world_system_ (0,3), to_world_system_ (1,3), to_world_system_ (2,3));
00673 }
00674 
00676 void 
00677 RangeImage::getSurfaceAngleChange (int x, int y, int radius, float& angle_change_x, float& angle_change_y) const
00678 {
00679   angle_change_x = angle_change_y = -std::numeric_limits<float>::infinity ();
00680   if (!isValid (x,y))
00681     return;
00682   Eigen::Vector3f point;
00683   getPoint (x, y, point);
00684   Eigen::Affine3f transformation = getTransformationToViewerCoordinateFrame (point);
00685   
00686   if (isObserved (x-radius, y) && isObserved (x+radius, y))
00687   {
00688     Eigen::Vector3f transformed_left;
00689     if (isMaxRange (x-radius, y))
00690       transformed_left = Eigen::Vector3f (0.0f, 0.0f, -1.0f);
00691     else
00692     {
00693       Eigen::Vector3f left;
00694       getPoint (x-radius, y, left);
00695       transformed_left = - (transformation * left);
00696       //std::cout << PVARN (transformed_left[1]);
00697       transformed_left[1] = 0.0f;
00698       transformed_left.normalize ();
00699     }
00700     
00701     Eigen::Vector3f transformed_right;
00702     if (isMaxRange (x+radius, y))
00703       transformed_right = Eigen::Vector3f (0.0f, 0.0f, 1.0f);
00704     else
00705     {
00706       Eigen::Vector3f right;
00707       getPoint (x+radius, y, right);
00708       transformed_right = transformation * right;
00709       //std::cout << PVARN (transformed_right[1]);
00710       transformed_right[1] = 0.0f;
00711       transformed_right.normalize ();
00712     }
00713     angle_change_x = transformed_left.dot (transformed_right);
00714     angle_change_x = (std::max) (0.0f, (std::min) (1.0f, angle_change_x));
00715     angle_change_x = acosf (angle_change_x);
00716   }
00717   
00718   if (isObserved (x, y-radius) && isObserved (x, y+radius))
00719   {
00720     Eigen::Vector3f transformed_top;
00721     if (isMaxRange (x, y-radius))
00722       transformed_top = Eigen::Vector3f (0.0f, 0.0f, -1.0f);
00723     else
00724     {
00725       Eigen::Vector3f top;
00726       getPoint (x, y-radius, top);
00727       transformed_top = - (transformation * top);
00728       //std::cout << PVARN (transformed_top[0]);
00729       transformed_top[0] = 0.0f;
00730       transformed_top.normalize ();
00731     }
00732     
00733     Eigen::Vector3f transformed_bottom;
00734     if (isMaxRange (x, y+radius))
00735       transformed_bottom = Eigen::Vector3f (0.0f, 0.0f, 1.0f);
00736     else
00737     {
00738       Eigen::Vector3f bottom;
00739       getPoint (x, y+radius, bottom);
00740       transformed_bottom = transformation * bottom;
00741       //std::cout << PVARN (transformed_bottom[0]);
00742       transformed_bottom[0] = 0.0f;
00743       transformed_bottom.normalize ();
00744     }
00745     angle_change_y = transformed_top.dot (transformed_bottom);
00746     angle_change_y = (std::max) (0.0f, (std::min) (1.0f, angle_change_y));
00747     angle_change_y = acosf (angle_change_y);
00748   }
00749 }
00750 
00751 
00752 //inline float RangeImage::getSurfaceChange (const PointWithRange& point, const PointWithRange& neighbor1, const PointWithRange& neighbor2) const
00753 //{
00754   //if (!pcl_isfinite (point.range) || (!pcl_isfinite (neighbor1.range)&&neighbor1.range<0) || (!pcl_isfinite (neighbor2.range)&&neighbor2.range<0))
00755     //return -std::numeric_limits<float>::infinity ();
00756   //if (pcl_isinf (neighbor1.range))
00757   //{
00758     //if (pcl_isinf (neighbor2.range))
00759       //return 0.0f;
00760     //else
00761       //return acosf ( (Eigen::Vector3f (point.x, point.y, point.z)-getSensorPos ()).normalized ().dot ( (Eigen::Vector3f (neighbor2.x, neighbor2.y, neighbor2.z)-Eigen::Vector3f (point.x, point.y, point.z)).normalized ()));
00762   //}
00763   //if (pcl_isinf (neighbor2.range))
00764     //return acosf ( (Eigen::Vector3f (point.x, point.y, point.z)-getSensorPos ()).normalized ().dot ( (Eigen::Vector3f (neighbor1.x, neighbor1.y, neighbor1.z)-Eigen::Vector3f (point.x, point.y, point.z)).normalized ()));
00765   
00766   //float d1_squared = squaredEuclideanDistance (point, neighbor1),
00767         //d1 = sqrtf (d1_squared),
00768         //d2_squared = squaredEuclideanDistance (point, neighbor2),
00769         //d2 = sqrtf (d2_squared),
00770         //d3_squared = squaredEuclideanDistance (neighbor1, neighbor2);
00771   //float cos_surface_change = (d1_squared + d2_squared - d3_squared)/ (2.0f*d1*d2),
00772         //surface_change = acosf (cos_surface_change);
00773   //if (pcl_isnan (surface_change))
00774     //surface_change = static_cast<float> (M_PI);
00776 
00777   //return surface_change;
00778 //}
00779 
00781 float 
00782 RangeImage::getMaxAngleSize (const Eigen::Affine3f& viewer_pose, const Eigen::Vector3f& center, float radius)
00783 {
00784   return 2.0f * asinf (radius/ (viewer_pose.translation ()-center).norm ());
00785 }
00786 
00788 Eigen::Vector3f 
00789 RangeImage::getEigenVector3f (const PointWithRange& point)
00790 {
00791   return Eigen::Vector3f (point.x, point.y, point.z);
00792 }
00793 
00795 void 
00796 RangeImage::get1dPointAverage (int x, int y, int delta_x, int delta_y, int no_of_points, PointWithRange& average_point) const
00797 {
00798   //std::cout << __PRETTY_FUNCTION__<<" called.\n";
00799   //MEASURE_FUNCTION_TIME;
00800   float weight_sum = 1.0f;
00801   average_point = getPoint (x,y);
00802   if (pcl_isinf (average_point.range))
00803   {
00804     if (average_point.range>0.0f)  // The first point is max range -> return a max range point
00805       return;
00806     weight_sum = 0.0f;
00807     average_point.x = average_point.y = average_point.z = average_point.range = 0.0f;
00808   }
00809   
00810   int x2=x, y2=y;
00811   Vector4fMap average_point_eigen = average_point.getVector4fMap ();
00812   //std::cout << PVARN (no_of_points);
00813   for (int step=1; step<no_of_points; ++step)
00814   {
00815     //std::cout << PVARC (step);
00816     x2+=delta_x;  y2+=delta_y;
00817     if (!isValid (x2, y2))
00818       continue;
00819     const PointWithRange& p = getPointNoCheck (x2, y2);
00820     average_point_eigen+=p.getVector4fMap (); average_point.range+=p.range;
00821     weight_sum += 1.0f;
00822   }
00823   if (weight_sum<= 0.0f)
00824   {
00825     average_point = unobserved_point;
00826     return;
00827   }
00828   float normalization_factor = 1.0f/weight_sum;
00829   average_point_eigen *= normalization_factor;
00830   average_point.range *= normalization_factor;
00831   //std::cout << PVARN (average_point);
00832 }
00833 
00835 float 
00836 RangeImage::getEuclideanDistanceSquared (int x1, int y1, int x2, int y2) const
00837 {
00838   if (!isObserved (x1,y1)||!isObserved (x2,y2))
00839     return -std::numeric_limits<float>::infinity ();
00840   const PointWithRange& point1 = getPoint (x1,y1),
00841                       & point2 = getPoint (x2,y2);
00842   if (pcl_isinf (point1.range) && pcl_isinf (point2.range))
00843     return 0.0f;
00844   if (pcl_isinf (point1.range) || pcl_isinf (point2.range))
00845     return std::numeric_limits<float>::infinity ();
00846   return squaredEuclideanDistance (point1, point2);
00847 }
00848 
00850 float 
00851 RangeImage::getAverageEuclideanDistance (int x, int y, int offset_x, int offset_y, int max_steps) const
00852 {
00853   float average_pixel_distance = 0.0f;
00854   float weight=0.0f;
00855   for (int i=0; i<max_steps; ++i)
00856   {
00857     int x1=x+i*offset_x,     y1=y+i*offset_y;
00858     int x2=x+ (i+1)*offset_x, y2=y+ (i+1)*offset_y;
00859     float pixel_distance = getEuclideanDistanceSquared (x1,y1,x2,y2);
00860     if (!pcl_isfinite (pixel_distance))
00861     {
00862       //std::cout << x<<","<<y<<"->"<<x2<<","<<y2<<": "<<pixel_distance<<"\n";
00863       if (i==0)
00864         return pixel_distance;
00865       else
00866         break;
00867     }
00868     //std::cout << x<<","<<y<<"->"<<x2<<","<<y2<<": "<<sqrtf (pixel_distance)<<"m\n";
00869     weight += 1.0f;
00870     average_pixel_distance += sqrtf (pixel_distance);
00871   }
00872   average_pixel_distance /= weight;
00873   //std::cout << x<<","<<y<<","<<offset_x<<","<<offset_y<<" => "<<average_pixel_distance<<"\n";
00874   return average_pixel_distance;
00875 }
00876 
00878 float 
00879 RangeImage::getImpactAngleBasedOnLocalNormal (int x, int y, int radius) const
00880 {
00881   if (!isValid (x,y))
00882     return -std::numeric_limits<float>::infinity ();
00883   const PointWithRange& point = getPoint (x, y);
00884   int no_of_nearest_neighbors = static_cast<int> (pow (static_cast<double> ( (radius + 1.0)), 2.0));
00885   Eigen::Vector3f normal;
00886   if (!getNormalForClosestNeighbors (x, y, radius, point, no_of_nearest_neighbors, normal, 1))
00887     return -std::numeric_limits<float>::infinity ();
00888   return deg2rad (90.0f) - acosf (normal.dot ( (getSensorPos ()-getEigenVector3f (point)).normalized ()));
00889 }
00890 
00891 
00893 bool 
00894 RangeImage::getNormal (int x, int y, int radius, Eigen::Vector3f& normal, int step_size) const
00895 {
00896   VectorAverage3f vector_average;
00897   for (int y2=y-radius; y2<=y+radius; y2+=step_size)
00898   {
00899     for (int x2=x-radius; x2<=x+radius; x2+=step_size)
00900     {
00901       if (!isInImage (x2, y2))
00902         continue;
00903       const PointWithRange& point = getPoint (x2, y2);
00904       if (!pcl_isfinite (point.range))
00905         continue;
00906       vector_average.add (Eigen::Vector3f (point.x, point.y, point.z));
00907     }
00908   }
00909   if (vector_average.getNoOfSamples () < 3)
00910     return false;
00911   Eigen::Vector3f eigen_values, eigen_vector2, eigen_vector3;
00912   vector_average.doPCA (eigen_values, normal, eigen_vector2, eigen_vector3);
00913   if (normal.dot ( (getSensorPos ()-vector_average.getMean ()).normalized ()) < 0.0f)
00914     normal *= -1.0f;
00915   return true;
00916 }
00917 
00919 float 
00920 RangeImage::getNormalBasedAcutenessValue (int x, int y, int radius) const
00921 {
00922   float impact_angle = getImpactAngleBasedOnLocalNormal (x, y, radius);
00923   if (pcl_isinf (impact_angle))
00924     return -std::numeric_limits<float>::infinity ();
00925   float ret = 1.0f - static_cast<float> ( (impact_angle / (0.5f * M_PI)));
00926   //std::cout << PVARAC (impact_angle)<<PVARN (ret);
00927   return ret;
00928 }
00929 
00931 bool 
00932 RangeImage::getNormalForClosestNeighbors (int x, int y, int radius, const PointWithRange& point,
00933                                               int no_of_nearest_neighbors, Eigen::Vector3f& normal, int step_size) const
00934 {
00935   return getNormalForClosestNeighbors (x, y, radius, Eigen::Vector3f (point.x, point.y, point.z), no_of_nearest_neighbors, normal, NULL, step_size);
00936 }
00937 
00939 bool 
00940 RangeImage::getNormalForClosestNeighbors (int x, int y, Eigen::Vector3f& normal, int radius) const
00941 {
00942   if (!isValid (x,y))
00943     return false;
00944   int no_of_nearest_neighbors = static_cast<int> (pow (static_cast<double> (radius + 1.0), 2.0));
00945   return getNormalForClosestNeighbors (x, y, radius, getPoint (x,y).getVector3fMap (), no_of_nearest_neighbors, normal);
00946 }
00947 
00948 namespace 
00949 {  // Anonymous namespace, so that this is only accessible in this file
00950   struct NeighborWithDistance 
00951   {  // local struct to help us with sorting
00952     float distance;
00953     const PointWithRange* neighbor;
00954     bool operator < (const NeighborWithDistance& other) const { return distance<other.distance;}
00955   };
00956 }
00957 
00959 bool 
00960 RangeImage::getSurfaceInformation (int x, int y, int radius, const Eigen::Vector3f& point, int no_of_closest_neighbors, int step_size,
00961                                    float& max_closest_neighbor_distance_squared,
00962                                    Eigen::Vector3f& normal, Eigen::Vector3f& mean, Eigen::Vector3f& eigen_values,
00963                                    Eigen::Vector3f* normal_all_neighbors, Eigen::Vector3f* mean_all_neighbors,
00964                                    Eigen::Vector3f* eigen_values_all_neighbors) const
00965 {
00966   max_closest_neighbor_distance_squared=0.0f;
00967   normal.setZero (); mean.setZero (); eigen_values.setZero ();
00968   if (normal_all_neighbors!=NULL)
00969     normal_all_neighbors->setZero ();
00970   if (mean_all_neighbors!=NULL)
00971     mean_all_neighbors->setZero ();
00972   if (eigen_values_all_neighbors!=NULL)
00973     eigen_values_all_neighbors->setZero ();
00974   
00975   int blocksize = static_cast<int> (pow (static_cast<double> ( (2.0 * radius + 1.0)), 2.0));
00976   
00977   PointWithRange given_point;
00978   given_point.x=point[0];  given_point.y=point[1];  given_point.z=point[2];
00979   
00980   std::vector<NeighborWithDistance> ordered_neighbors (blocksize);
00981   int neighbor_counter = 0;
00982   for (int y2=y-radius; y2<=y+radius; y2+=step_size)
00983   {
00984     for (int x2=x-radius; x2<=x+radius; x2+=step_size)
00985     {
00986       if (!isValid (x2, y2))
00987         continue;
00988       NeighborWithDistance& neighbor_with_distance = ordered_neighbors[neighbor_counter];
00989       neighbor_with_distance.neighbor = &getPoint (x2, y2);
00990       neighbor_with_distance.distance = squaredEuclideanDistance (given_point, *neighbor_with_distance.neighbor);
00991       ++neighbor_counter;
00992     }
00993   }
00994   no_of_closest_neighbors = (std::min) (neighbor_counter, no_of_closest_neighbors);
00995 
00996   std::sort (ordered_neighbors.begin (), ordered_neighbors.begin () + neighbor_counter);  // Normal sort seems to be the fastest method (faster than partial_sort)
00997   //std::stable_sort (ordered_neighbors, ordered_neighbors+neighbor_counter);
00998   //std::partial_sort (ordered_neighbors, ordered_neighbors+no_of_closest_neighbors, ordered_neighbors+neighbor_counter);
00999   
01000   max_closest_neighbor_distance_squared = ordered_neighbors[no_of_closest_neighbors-1].distance;
01001   //float max_distance_squared = max_closest_neighbor_distance_squared;
01002   float max_distance_squared = max_closest_neighbor_distance_squared*4.0f;  // Double the allowed distance value
01003   //max_closest_neighbor_distance_squared = max_distance_squared;
01004   
01005   VectorAverage3f vector_average;
01006   //for (int neighbor_idx=0; neighbor_idx<no_of_closest_neighbors; ++neighbor_idx)
01007   int neighbor_idx;
01008   for (neighbor_idx=0; neighbor_idx<neighbor_counter; ++neighbor_idx)
01009   {
01010     if (ordered_neighbors[neighbor_idx].distance > max_distance_squared)
01011       break;
01012     //std::cout << ordered_neighbors[neighbor_idx].distance<<"\n";
01013     vector_average.add (ordered_neighbors[neighbor_idx].neighbor->getVector3fMap ());
01014   }
01015   
01016   if (vector_average.getNoOfSamples () < 3)
01017     return false;
01018   //std::cout << PVARN (vector_average.getNoOfSamples ());
01019   Eigen::Vector3f eigen_vector2, eigen_vector3;
01020   vector_average.doPCA (eigen_values, normal, eigen_vector2, eigen_vector3);
01021   Eigen::Vector3f viewing_direction = (getSensorPos ()-point).normalized ();
01022   if (normal.dot (viewing_direction) < 0.0f)
01023     normal *= -1.0f;
01024   mean = vector_average.getMean ();
01025   
01026   if (normal_all_neighbors==NULL)
01027     return true;
01028   
01029   // Add remaining neighbors
01030   for (int neighbor_idx2=neighbor_idx; neighbor_idx2<neighbor_counter; ++neighbor_idx2)
01031     vector_average.add (ordered_neighbors[neighbor_idx2].neighbor->getVector3fMap ());
01032   
01033   vector_average.doPCA (*eigen_values_all_neighbors, *normal_all_neighbors, eigen_vector2, eigen_vector3);
01034   //std::cout << PVARN (vector_average.getNoOfSamples ())<<".\n";
01035   if (normal_all_neighbors->dot (viewing_direction) < 0.0f)
01036     *normal_all_neighbors *= -1.0f;
01037   *mean_all_neighbors = vector_average.getMean ();
01038   
01039   //std::cout << viewing_direction[0]<<","<<viewing_direction[1]<<","<<viewing_direction[2]<<"\n";
01040   
01041   return true;
01042 }
01043 
01045 float 
01046 RangeImage::getSquaredDistanceOfNthNeighbor (int x, int y, int radius, int n, int step_size) const
01047 {
01048   const PointWithRange& point = getPoint (x, y);
01049   if (!pcl_isfinite (point.range))
01050     return -std::numeric_limits<float>::infinity ();
01051   
01052   int blocksize = static_cast<int> (pow (static_cast<double> (2.0 * radius + 1.0), 2.0));
01053   std::vector<float> neighbor_distances (blocksize);
01054   int neighbor_counter = 0;
01055   for (int y2=y-radius; y2<=y+radius; y2+=step_size)
01056   {
01057     for (int x2=x-radius; x2<=x+radius; x2+=step_size)
01058     {
01059       if (!isValid (x2, y2) || (x2==x&&y2==y))
01060         continue;
01061       const PointWithRange& neighbor = getPointNoCheck (x2,y2);
01062       float& neighbor_distance = neighbor_distances[neighbor_counter++];
01063       neighbor_distance = squaredEuclideanDistance (point, neighbor);
01064     }
01065   }
01066   std::sort (neighbor_distances.begin (), neighbor_distances.begin () + neighbor_counter);  // Normal sort seems to be
01067                                                                       // the fastest method (faster than partial_sort)
01068   n = (std::min) (neighbor_counter, n);
01069   return neighbor_distances[n-1];
01070 }
01071 
01072 
01074 bool 
01075 RangeImage::getNormalForClosestNeighbors (int x, int y, int radius, const Eigen::Vector3f& point, int no_of_nearest_neighbors,
01076                                                      Eigen::Vector3f& normal, Eigen::Vector3f* point_on_plane, int step_size) const
01077 {
01078   Eigen::Vector3f mean, eigen_values;
01079   float used_squared_max_distance;
01080   bool ret = getSurfaceInformation (x, y, radius, point, no_of_nearest_neighbors, step_size, used_squared_max_distance,
01081                                    normal, mean, eigen_values);
01082   
01083   if (ret)
01084   {
01085     if (point_on_plane != NULL)
01086       *point_on_plane = (normal.dot (mean) - normal.dot (point))*normal + point;
01087   }
01088   return ret;
01089 }
01090 
01091 
01093 float 
01094 RangeImage::getCurvature (int x, int y, int radius, int step_size) const
01095 {
01096   VectorAverage3f vector_average;
01097   for (int y2=y-radius; y2<=y+radius; y2+=step_size)
01098   {
01099     for (int x2=x-radius; x2<=x+radius; x2+=step_size)
01100     {
01101       if (!isInImage (x2, y2))
01102         continue;
01103       const PointWithRange& point = getPoint (x2, y2);
01104       if (!pcl_isfinite (point.range))
01105         continue;
01106       vector_average.add (Eigen::Vector3f (point.x, point.y, point.z));
01107     }
01108   }
01109   if (vector_average.getNoOfSamples () < 3)
01110     return false;
01111   Eigen::Vector3f eigen_values;
01112   vector_average.doPCA (eigen_values);
01113   return eigen_values[0]/eigen_values.sum ();
01114 }
01115 
01116 
01118 template <typename PointCloudTypeWithViewpoints> Eigen::Vector3f 
01119 RangeImage::getAverageViewPoint (const PointCloudTypeWithViewpoints& point_cloud)
01120 {
01121   Eigen::Vector3f average_viewpoint (0,0,0);
01122   int point_counter = 0;
01123   for (unsigned int point_idx=0; point_idx<point_cloud.points.size (); ++point_idx)
01124   {
01125     const typename PointCloudTypeWithViewpoints::PointType& point = point_cloud.points[point_idx];
01126     if (!pcl_isfinite (point.vp_x) || !pcl_isfinite (point.vp_y) || !pcl_isfinite (point.vp_z))
01127       continue;
01128     average_viewpoint[0] += point.vp_x;
01129     average_viewpoint[1] += point.vp_y;
01130     average_viewpoint[2] += point.vp_z;
01131     ++point_counter;
01132   }
01133   average_viewpoint /= point_counter;
01134   
01135   return average_viewpoint;
01136 }
01137 
01139 bool 
01140 RangeImage::getViewingDirection (int x, int y, Eigen::Vector3f& viewing_direction) const
01141 {
01142   if (!isValid (x, y))
01143     return false;
01144   viewing_direction = (getPoint (x,y).getVector3fMap ()-getSensorPos ()).normalized ();
01145   return true;
01146 }
01147 
01149 void 
01150 RangeImage::getViewingDirection (const Eigen::Vector3f& point, Eigen::Vector3f& viewing_direction) const
01151 {
01152   viewing_direction = (point-getSensorPos ()).normalized ();
01153 }
01154 
01156 Eigen::Affine3f 
01157 RangeImage::getTransformationToViewerCoordinateFrame (const Eigen::Vector3f& point) const
01158 {
01159   Eigen::Affine3f transformation;
01160   getTransformationToViewerCoordinateFrame (point, transformation);
01161   return transformation;
01162 }
01163 
01165 void 
01166 RangeImage::getTransformationToViewerCoordinateFrame (const Eigen::Vector3f& point, Eigen::Affine3f& transformation) const
01167 {
01168   Eigen::Vector3f viewing_direction = (point-getSensorPos ()).normalized ();
01169   getTransformationFromTwoUnitVectorsAndOrigin (Eigen::Vector3f (0.0f, -1.0f, 0.0f), viewing_direction, point, transformation);
01170 }
01171 
01173 void 
01174 RangeImage::getRotationToViewerCoordinateFrame (const Eigen::Vector3f& point, Eigen::Affine3f& transformation) const
01175 {
01176   Eigen::Vector3f viewing_direction = (point-getSensorPos ()).normalized ();
01177   getTransformationFromTwoUnitVectors (Eigen::Vector3f (0.0f, -1.0f, 0.0f), viewing_direction, transformation);
01178 }
01179 
01181 inline void
01182 RangeImage::setAngularResolution (float angular_resolution)
01183 {
01184   angular_resolution_x_ = angular_resolution_y_ = angular_resolution;
01185   angular_resolution_x_reciprocal_ = angular_resolution_y_reciprocal_ = 1.0f / angular_resolution;
01186 }
01187 
01189 inline void
01190 RangeImage::setAngularResolution (float angular_resolution_x, float angular_resolution_y)
01191 {
01192   angular_resolution_x_ = angular_resolution_x;
01193   angular_resolution_x_reciprocal_ = 1.0f / angular_resolution_x_;
01194   angular_resolution_y_ = angular_resolution_y;
01195   angular_resolution_y_reciprocal_ = 1.0f / angular_resolution_y_;
01196 }
01197 
01198 inline void 
01199 RangeImage::setTransformationToRangeImageSystem (const Eigen::Affine3f& to_range_image_system)
01200 {
01201   to_range_image_system_ = to_range_image_system;
01202   to_world_system_ = to_range_image_system_.inverse ();
01203 }
01204 
01205 inline void 
01206 RangeImage::getAngularResolution (float& angular_resolution_x, float& angular_resolution_y) const
01207 {  
01208   angular_resolution_x = angular_resolution_x_;
01209   angular_resolution_y = angular_resolution_y_;
01210 }
01211 
01212 }  // namespace end


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