range_image_border_extractor.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 <iostream>
00038 using std::cout;
00039 using std::cerr;
00040 #include <map>
00041 #include <set>
00042 #include <cmath>
00043 #include <Eigen/Geometry>
00044 #include <pcl/pcl_macros.h>
00045 #include <pcl/common/common_headers.h>
00046 #include <pcl/range_image/range_image.h>
00047 #include <pcl/point_cloud.h>
00048 #include <pcl/common/vector_average.h>
00049 #include <pcl/features/range_image_border_extractor.h>
00050 
00051 namespace pcl 
00052 {
00053 
00055 RangeImageBorderExtractor::RangeImageBorderExtractor(const RangeImage* range_image) : BaseClass(),
00056   parameters_ (), range_image_(range_image), range_image_size_during_extraction_(0),
00057   border_scores_left_(NULL), border_scores_right_(NULL), border_scores_top_(NULL), border_scores_bottom_(NULL),
00058   surface_structure_(NULL), border_descriptions_(NULL), shadow_border_informations_(NULL), border_directions_(NULL),
00059   surface_change_scores_(NULL), surface_change_directions_(NULL)
00060 {
00061 }
00062 
00064 RangeImageBorderExtractor::~RangeImageBorderExtractor()
00065 {
00066   clearData ();
00067 }
00068 
00070 void 
00071 RangeImageBorderExtractor::setRangeImage (const RangeImage* range_image)
00072 {
00073   clearData ();
00074   range_image_ = range_image;
00075 }
00076 
00078 void 
00079 RangeImageBorderExtractor::clearData ()
00080 {
00081   delete[] border_scores_left_;    border_scores_left_   = NULL;
00082   delete[] border_scores_right_;   border_scores_right_  = NULL;
00083   delete[] border_scores_top_;     border_scores_top_    = NULL;
00084   delete[] border_scores_bottom_;  border_scores_bottom_ = NULL;
00085   //cout << PVARC(range_image_size_during_extraction_)<<PVARN((void*)this);
00086   for (int i=0; i<range_image_size_during_extraction_; ++i)
00087   {
00088     if (surface_structure_!=NULL)
00089       delete surface_structure_[i];
00090     if (shadow_border_informations_!=NULL)
00091       delete shadow_border_informations_[i];
00092     if (border_directions_!=NULL)
00093       delete border_directions_[i];
00094   }
00095   delete[] surface_structure_; surface_structure_ = NULL;
00096   delete border_descriptions_; border_descriptions_ = NULL;
00097   delete[] shadow_border_informations_; shadow_border_informations_ = NULL;
00098   delete[] border_directions_; border_directions_ = NULL;
00099   
00100   delete[] surface_change_scores_;  surface_change_scores_ = NULL;
00101   delete[] surface_change_directions_;  surface_change_directions_ = NULL;
00102 }
00103 
00105 void 
00106 RangeImageBorderExtractor::extractLocalSurfaceStructure ()
00107 {
00108   if (surface_structure_ != NULL)
00109     return;
00110   //cerr << __PRETTY_FUNCTION__<<" called (this="<<(void*)this<<").\n";
00111   //MEASURE_FUNCTION_TIME;
00112   
00113   int width  = range_image_->width,
00114       height = range_image_->height;
00115   range_image_size_during_extraction_ = width*height;
00116   int array_size = range_image_size_during_extraction_;
00117   surface_structure_ = new LocalSurface*[array_size];
00118   int step_size = (std::max)(1, parameters_.pixel_radius_plane_extraction/2);
00119   //cout << PVARN(step_size);
00120   int no_of_nearest_neighbors = static_cast<int> (pow (static_cast<double> (parameters_.pixel_radius_plane_extraction/step_size + 1), 2.0));
00121   
00122 # pragma omp parallel for num_threads(parameters_.max_no_of_threads) default(shared) schedule(dynamic, 10)
00123   for (int y=0; y<height; ++y)
00124   {
00125     for (int x=0; x<width; ++x)
00126     {
00127       int index = y*width + x;
00128       LocalSurface*& local_surface = surface_structure_[index];
00129       local_surface = NULL;
00130       if (!range_image_->isValid(index))
00131         continue;
00132       local_surface = new LocalSurface;
00133       Eigen::Vector3f point;
00134       range_image_->getPoint(x, y, point);
00135       //cout << PVARN(point);
00136       if (!range_image_->getSurfaceInformation(x, y, parameters_.pixel_radius_plane_extraction, point,
00137                                   no_of_nearest_neighbors, step_size, local_surface->max_neighbor_distance_squared,
00138                                   local_surface->normal_no_jumps, local_surface->neighborhood_mean_no_jumps,
00139                                   local_surface->eigen_values_no_jumps,  &local_surface->normal,
00140                                   &local_surface->neighborhood_mean, &local_surface->eigen_values))
00141       {
00142         delete local_surface;
00143         local_surface = NULL;
00144       }
00145       
00146       //cout << x<<","<<y<<": ("<<local_surface->normal_no_jumps[0]<<","<<local_surface->normal_no_jumps[1]<<","<<local_surface->normal_no_jumps[2]<<")\n";
00147     }
00148   }
00149 }
00150 
00152 void 
00153 RangeImageBorderExtractor::extractBorderScoreImages ()
00154 {
00155   if (border_scores_left_ != NULL)
00156     return;
00157   
00158   extractLocalSurfaceStructure();
00159   
00160   //MEASURE_FUNCTION_TIME;
00161   
00162   int width  = range_image_->width,
00163       height = range_image_->height,
00164       size   = width*height;
00165   border_scores_left_   = new float[size];
00166   border_scores_right_  = new float[size];
00167   border_scores_top_    = new float[size];
00168   border_scores_bottom_ = new float[size];
00169   
00170 # pragma omp parallel for num_threads(parameters_.max_no_of_threads) default(shared) schedule(dynamic, 10)
00171   for (int y=0; y<height; ++y) {
00172     for (int x=0; x<width; ++x) {
00173       int index = y*width + x;
00174       float& left=border_scores_left_[index]; float& right=border_scores_right_[index];
00175       float& top=border_scores_top_[index]; float& bottom=border_scores_bottom_[index]; 
00176       LocalSurface* local_surface_ptr = surface_structure_[index];
00177       if (local_surface_ptr==NULL)
00178       {
00179         left=right=top=bottom = 0.0f;
00180         continue;
00181       }
00182       
00183       left   = getNeighborDistanceChangeScore(*local_surface_ptr, x, y, -1,  0, parameters_.pixel_radius_borders);
00184       right  = getNeighborDistanceChangeScore(*local_surface_ptr, x, y,  1,  0, parameters_.pixel_radius_borders);
00185       top    = getNeighborDistanceChangeScore(*local_surface_ptr, x, y,  0, -1, parameters_.pixel_radius_borders);
00186       bottom = getNeighborDistanceChangeScore(*local_surface_ptr, x, y,  0,  1, parameters_.pixel_radius_borders);
00187     }
00188   }
00189 }
00190 
00192 float* 
00193 RangeImageBorderExtractor::updatedScoresAccordingToNeighborValues (const float* border_scores) const
00194 {
00195   float* new_scores = new float[range_image_->width*range_image_->height];
00196   float* new_scores_ptr = new_scores;
00197   for (int y=0; y < static_cast<int> (range_image_->height); ++y) 
00198     for (int x=0; x < static_cast<int> (range_image_->width); ++x) 
00199       *(new_scores_ptr++) = updatedScoreAccordingToNeighborValues(x, y, border_scores);
00200   return (new_scores);
00201 }
00202 
00204 void 
00205 RangeImageBorderExtractor::updateScoresAccordingToNeighborValues ()
00206 {
00207   extractBorderScoreImages();
00208   
00209   //MEASURE_FUNCTION_TIME;
00210   
00211   float* left_with_propagated_neighbors = updatedScoresAccordingToNeighborValues(border_scores_left_);
00212   delete[] border_scores_left_;
00213   border_scores_left_ = left_with_propagated_neighbors;
00214   float* right_with_propagated_neighbors = updatedScoresAccordingToNeighborValues(border_scores_right_);
00215   delete[] border_scores_right_;
00216   border_scores_right_ = right_with_propagated_neighbors;
00217   float* top_with_propagated_neighbors = updatedScoresAccordingToNeighborValues(border_scores_top_);
00218   delete[] border_scores_top_;
00219   border_scores_top_ = top_with_propagated_neighbors;
00220   float* bottom_with_propagated_neighbors = updatedScoresAccordingToNeighborValues(border_scores_bottom_);
00221   delete[] border_scores_bottom_;
00222   border_scores_bottom_ = bottom_with_propagated_neighbors;
00223 }
00224  
00226 void 
00227 RangeImageBorderExtractor::findAndEvaluateShadowBorders ()
00228 {
00229   if (shadow_border_informations_ != NULL)
00230     return;
00231   
00232   if (border_scores_left_==NULL)
00233   {
00234     std::cerr << __PRETTY_FUNCTION__<<": border score images not available!\n";
00235   }
00236   
00237   //MEASURE_FUNCTION_TIME;
00238   
00239   int width  = range_image_->width,
00240       height = range_image_->height;
00241   shadow_border_informations_ = new ShadowBorderIndices*[width*height];
00242   for (int y = 0; y < static_cast<int> (height); ++y) 
00243   {
00244     for (int x = 0; x < static_cast<int> (width); ++x) 
00245     {
00246       int index = y*width+x;
00247       ShadowBorderIndices*& shadow_border_indices = shadow_border_informations_[index];
00248       shadow_border_indices = NULL;
00249       int shadow_border_idx;
00250       
00251       if (changeScoreAccordingToShadowBorderValue(x, y, -1, 0, border_scores_left_, border_scores_right_, shadow_border_idx))
00252       {
00253         shadow_border_indices = (shadow_border_indices==NULL ? new ShadowBorderIndices : shadow_border_indices);
00254         shadow_border_indices->left = shadow_border_idx;
00255       }
00256       if (changeScoreAccordingToShadowBorderValue(x, y, 1, 0, border_scores_right_, border_scores_left_, shadow_border_idx))
00257       {
00258         shadow_border_indices = (shadow_border_indices==NULL ? new ShadowBorderIndices : shadow_border_indices);
00259         shadow_border_indices->right = shadow_border_idx;
00260       }
00261       if (changeScoreAccordingToShadowBorderValue(x, y, 0, -1, border_scores_top_, border_scores_bottom_, shadow_border_idx))
00262       {
00263         shadow_border_indices = (shadow_border_indices==NULL ? new ShadowBorderIndices : shadow_border_indices);
00264         shadow_border_indices->top = shadow_border_idx;
00265       }
00266       if (changeScoreAccordingToShadowBorderValue(x, y, 0, 1, border_scores_bottom_, border_scores_top_, shadow_border_idx))
00267       {
00268         shadow_border_indices = (shadow_border_indices==NULL ? new ShadowBorderIndices : shadow_border_indices);
00269         shadow_border_indices->bottom = shadow_border_idx;
00270       }
00271     }
00272   }
00273 }
00274 
00276 float* 
00277 RangeImageBorderExtractor::getAnglesImageForBorderDirections ()
00278 {
00279   calculateBorderDirections();
00280   
00281   int width  = range_image_->width,
00282       height = range_image_->height,
00283       array_size = width*height;
00284   float* angles_image = new float[array_size];
00285   
00286   for (int y=0; y<height; ++y)
00287   {
00288     for (int x=0; x<width; ++x)
00289     {
00290       int index = y*width + x;
00291       float& angle = angles_image[index];
00292       angle = -std::numeric_limits<float>::infinity ();
00293       const Eigen::Vector3f* border_direction_ptr = border_directions_[index];
00294       if (border_direction_ptr == NULL)
00295         continue;
00296       const Eigen::Vector3f& border_direction = *border_direction_ptr;
00297       const PointWithRange& point = range_image_->getPoint(index);
00298       
00299       float border_direction_in_image_x, border_direction_in_image_y;
00300       float tmp_factor = point.range*range_image_->getAngularResolution();
00301       range_image_->getImagePoint(point.x+tmp_factor*border_direction[0], point.y+tmp_factor*border_direction[1], point.z+tmp_factor*border_direction[2],
00302                                 border_direction_in_image_x, border_direction_in_image_y);
00303       border_direction_in_image_x -= static_cast<float> (x);  border_direction_in_image_y -= static_cast<float> (y);
00304       angle = atan2f (border_direction_in_image_y, border_direction_in_image_x);
00305     }
00306   }
00307   return angles_image;
00308 }
00309 
00311 float* 
00312 RangeImageBorderExtractor::getAnglesImageForSurfaceChangeDirections ()
00313 {
00314   //MEASURE_FUNCTION_TIME;
00315   
00316   calculateSurfaceChanges();
00317   
00318   int width  = range_image_->width,
00319       height = range_image_->height,
00320       array_size = width*height;
00321   float* angles_image = new float[array_size];
00322   
00323   for (int y=0; y<height; ++y)
00324   {
00325     for (int x=0; x<width; ++x)
00326     {
00327       int index = y*width + x;
00328       float& angle = angles_image[index];
00329       angle = -std::numeric_limits<float>::infinity ();
00330       float surface_change_score = surface_change_scores_[index];
00331       if (surface_change_score <= 0.1f)
00332         continue;
00333       const Eigen::Vector3f& direction = surface_change_directions_[index];
00334       const PointWithRange& point = range_image_->getPoint(index);
00335       
00336       float border_direction_in_image_x, border_direction_in_image_y;
00337       float tmp_factor = point.range*range_image_->getAngularResolution();
00338       range_image_->getImagePoint(point.x+tmp_factor*direction[0], point.y+tmp_factor*direction[1], point.z+tmp_factor*direction[2],
00339                                 border_direction_in_image_x, border_direction_in_image_y);
00340       border_direction_in_image_x -= static_cast<float> (x);  border_direction_in_image_y -= static_cast<float> (y);
00341       angle = atan2f (border_direction_in_image_y, border_direction_in_image_x);
00342       if (angle <= deg2rad (-90.0f))
00343         angle += static_cast<float> (M_PI);
00344       else if (angle > deg2rad (90.0f))
00345         angle -= static_cast<float> (M_PI);
00346     }
00347   }
00348   return (angles_image);
00349 }
00350 
00351 
00353 void 
00354 RangeImageBorderExtractor::classifyBorders ()
00355 {
00356   if (border_descriptions_ != NULL)
00357     return;
00358   
00359   // Get local plane approximations
00360   extractLocalSurfaceStructure();
00361   
00362   // Get scores for every point, describing how probable a border in that direction is
00363   extractBorderScoreImages();
00364   
00365   // Propagate values to neighboring pixels
00366   updateScoresAccordingToNeighborValues();
00367   
00368   // Change border score according to the existence of a shadow border
00369   findAndEvaluateShadowBorders();
00370   
00371   int width  = range_image_->width,
00372       height = range_image_->height,
00373       size   = width*height;
00374   
00375   BorderDescription initial_border_description;
00376   initial_border_description.traits = 0;
00377   border_descriptions_ = new PointCloudOut;
00378   border_descriptions_->width = width;
00379   border_descriptions_->height = height;
00380   border_descriptions_->is_dense = true;
00381   border_descriptions_->points.resize(size, initial_border_description);
00382   
00383   for (int y = 0; y < static_cast<int> (height); ++y) 
00384   {
00385     for (int x = 0; x < static_cast<int> (width); ++x) 
00386     {
00387       int index = y*width+x;
00388       BorderDescription& border_description = border_descriptions_->points[index];
00389       border_description.x = x;
00390       border_description.y = y;
00391       BorderTraits& border_traits = border_description.traits;
00392       
00393       ShadowBorderIndices* shadow_border_indices = shadow_border_informations_[index];
00394       if (shadow_border_indices == NULL)
00395         continue;
00396       
00397       int shadow_border_index = shadow_border_indices->left;
00398       if (shadow_border_index >= 0 && checkIfMaximum(x, y, -1, 0, border_scores_left_, shadow_border_index))
00399       {
00400         BorderTraits& shadow_traits = border_descriptions_->points[shadow_border_index].traits;
00401         border_traits[BORDER_TRAIT__OBSTACLE_BORDER] = border_traits[BORDER_TRAIT__OBSTACLE_BORDER_LEFT] = true;
00402         shadow_traits[BORDER_TRAIT__SHADOW_BORDER] = shadow_traits[BORDER_TRAIT__SHADOW_BORDER_RIGHT] = true;
00403         for (int index3=index-1; index3>shadow_border_index; --index3)
00404         {
00405           BorderTraits& veil_point = border_descriptions_->points[index3].traits;
00406           veil_point[BORDER_TRAIT__VEIL_POINT] = veil_point[BORDER_TRAIT__VEIL_POINT_RIGHT] = true;
00407         }
00408       }
00409       
00410       shadow_border_index = shadow_border_indices->right;
00411       if (shadow_border_index >= 0 && checkIfMaximum(x, y, 1, 0, border_scores_right_, shadow_border_index))
00412       {
00413         BorderTraits& shadow_traits = border_descriptions_->points[shadow_border_index].traits;
00414         border_traits[BORDER_TRAIT__OBSTACLE_BORDER] = border_traits[BORDER_TRAIT__OBSTACLE_BORDER_RIGHT] = true;
00415         shadow_traits[BORDER_TRAIT__SHADOW_BORDER] = shadow_traits[BORDER_TRAIT__SHADOW_BORDER_LEFT] = true;
00416         for (int index3=index+1; index3<shadow_border_index; ++index3)
00417         {
00418           BorderTraits& veil_point = border_descriptions_->points[index3].traits;
00419           veil_point[BORDER_TRAIT__VEIL_POINT] = veil_point[BORDER_TRAIT__VEIL_POINT_LEFT] = true;
00420         }
00421       }
00422       
00423       shadow_border_index = shadow_border_indices->top;
00424       if (shadow_border_index >= 0 && checkIfMaximum(x, y, 0, -1, border_scores_top_, shadow_border_index))
00425       {
00426         BorderTraits& shadow_traits = border_descriptions_->points[shadow_border_index].traits;
00427         border_traits[BORDER_TRAIT__OBSTACLE_BORDER] = border_traits[BORDER_TRAIT__OBSTACLE_BORDER_TOP] = true;
00428         shadow_traits[BORDER_TRAIT__SHADOW_BORDER] = shadow_traits[BORDER_TRAIT__SHADOW_BORDER_BOTTOM] = true;
00429         for (int index3=index-width; index3>shadow_border_index; index3-=width)
00430         {
00431           //cout << "Adding veil point at "<<(index3-index)%width<<","<<(index3-index)/width<<".\n";
00432           BorderTraits& veil_point = border_descriptions_->points[index3].traits;
00433           veil_point[BORDER_TRAIT__VEIL_POINT] = veil_point[BORDER_TRAIT__VEIL_POINT_BOTTOM] = true;
00434         }
00435       }
00436       
00437       shadow_border_index = shadow_border_indices->bottom;
00438       if (shadow_border_index >= 0 && checkIfMaximum(x, y, 0, 1, border_scores_bottom_, shadow_border_index))
00439       {
00440         BorderTraits& shadow_traits = border_descriptions_->points[shadow_border_index].traits;
00441         border_traits[BORDER_TRAIT__OBSTACLE_BORDER] = border_traits[BORDER_TRAIT__OBSTACLE_BORDER_BOTTOM] = true;
00442         shadow_traits[BORDER_TRAIT__SHADOW_BORDER] = shadow_traits[BORDER_TRAIT__SHADOW_BORDER_TOP] = true;
00443         for (int index3=index+width; index3<shadow_border_index; index3+=width)
00444         {
00445           //cout << "Adding veil point at "<<(index3-index)%width<<","<<(index3-index)/width<<".\n";
00446           BorderTraits& veil_point = border_descriptions_->points[index3].traits;
00447           veil_point[BORDER_TRAIT__VEIL_POINT] = veil_point[BORDER_TRAIT__VEIL_POINT_TOP] = true;
00448         }
00449       }
00450       
00451       //if (border_traits[BORDER_TRAIT__OBSTACLE_BORDER])
00452       //{
00453         //border_points.push_back(&border_description);
00454       //}
00455     }
00456   }
00457 }
00458 
00460 void 
00461 RangeImageBorderExtractor::calculateBorderDirections ()
00462 {
00463   if (border_directions_!=NULL)
00464     return;
00465   classifyBorders();
00466   
00467   //MEASURE_FUNCTION_TIME;
00468   
00469   int width  = range_image_->width,
00470       height = range_image_->height,
00471       size   = width*height;
00472   border_directions_ = new Eigen::Vector3f*[size];
00473   for (int y=0; y<height; ++y)
00474   {
00475     for (int x=0; x<width; ++x)
00476     {
00477       calculateBorderDirection(x, y);
00478     }
00479   }
00480   
00481   Eigen::Vector3f** average_border_directions = new Eigen::Vector3f*[size];
00482   int radius = parameters_.pixel_radius_border_direction;
00483   int minimum_weight = radius+1;
00484   float min_cos_angle=cosf(deg2rad(120.0f));
00485   for (int y=0; y<height; ++y)
00486   {
00487     for (int x=0; x<width; ++x)
00488     {
00489       int index = y*width + x;
00490       Eigen::Vector3f*& average_border_direction = average_border_directions[index];
00491       average_border_direction = NULL;
00492       const Eigen::Vector3f* border_direction = border_directions_[index];
00493       if (border_direction==NULL)
00494         continue;
00495       average_border_direction = new Eigen::Vector3f(*border_direction);
00496       float weight_sum = 1.0f;
00497       for (int y2=(std::max)(0, y-radius); y2<=(std::min)(y+radius, height-1); ++y2)
00498       {
00499         for (int x2=(std::max)(0, x-radius); x2<=(std::min)(x+radius, width-1); ++x2)
00500         {
00501           int index2 = y2*width + x2;
00502           const Eigen::Vector3f* neighbor_border_direction = border_directions_[index2];
00503           if (neighbor_border_direction==NULL || index2==index)
00504             continue;
00505           
00506           // Oposite directions?
00507           float cos_angle = neighbor_border_direction->dot(*border_direction);
00508           if (cos_angle<min_cos_angle)
00509           {
00510             //cout << "Reject. "<<PVARC(min_cos_angle)<<PVARC(cos_angle)<<PVARAN(acosf(cos_angle));
00511             continue;
00512           }
00513           //else
00514             //cout << "No reject\n";
00515           
00516           // Border in between?
00517           float border_between_points_score = getNeighborDistanceChangeScore(*surface_structure_[index], x, y, x2-x,  y2-y, 1);
00518           if (fabsf(border_between_points_score) >= 0.95f*parameters_.minimum_border_probability)
00519             continue;
00520           
00521           *average_border_direction += *neighbor_border_direction;
00522           weight_sum += 1.0f;
00523         }
00524       }
00525       if (pcl_lrint (weight_sum) < minimum_weight)
00526       {
00527         delete average_border_direction;
00528         average_border_direction=NULL;
00529       }
00530       else
00531         average_border_direction->normalize();
00532     }
00533   }
00534   
00535   for (int i=0; i<size; ++i)
00536     delete border_directions_[i];
00537   delete[] border_directions_;
00538   border_directions_ = average_border_directions;
00539 }
00540 
00542 void 
00543 RangeImageBorderExtractor::calculateSurfaceChanges ()
00544 {
00545   if (surface_change_scores_!=NULL)
00546     return;
00547   
00548   calculateBorderDirections();
00549   
00550   //MEASURE_FUNCTION_TIME;
00551   
00552   int width  = range_image_->width,
00553       height = range_image_->height,
00554       size   = width*height;
00555   surface_change_scores_ = new float[size];
00556   surface_change_directions_ = new Eigen::Vector3f[size];
00557 # pragma omp parallel for num_threads(parameters_.max_no_of_threads) default(shared) schedule(dynamic, 10)
00558   for (int y=0; y<height; ++y)
00559   {
00560     for (int x=0; x<width; ++x)
00561     {
00562       int index = y*width + x;
00563       float& surface_change_score = surface_change_scores_[index];
00564       surface_change_score = 0.0f;
00565       Eigen::Vector3f& surface_change_direction = surface_change_directions_[index];
00566       surface_change_direction.setZero();
00567       
00568       const BorderTraits& border_traits = border_descriptions_->points[index].traits;
00569       if (border_traits[BORDER_TRAIT__VEIL_POINT] || border_traits[BORDER_TRAIT__SHADOW_BORDER])
00570         continue;
00571       if (border_directions_[index]!=NULL)
00572       {
00573         surface_change_score = 1.0f;
00574         surface_change_direction = *border_directions_[index];
00575       }
00576       else
00577       {
00578         if (!calculateMainPrincipalCurvature(x, y, parameters_.pixel_radius_principal_curvature,
00579                                              surface_change_score, surface_change_direction))
00580         {
00581           surface_change_score = 0.0f;
00582           continue;
00583         }
00584       }
00585     }
00586   }
00587   //blurSurfaceChanges();
00588 }
00589 
00591 void 
00592 RangeImageBorderExtractor::blurSurfaceChanges ()
00593 {
00594   int blur_radius = 1;
00595   if (blur_radius==0)
00596     return;
00597   
00598   const RangeImage& range_image = *range_image_;
00599   
00600   Eigen::Vector3f* blurred_directions = new Eigen::Vector3f[range_image.width*range_image.height];
00601   float* blurred_scores = new float[range_image.width*range_image.height];
00602   for (int y=0; y<int(range_image.height); ++y)
00603   {
00604     for (int x=0; x<int(range_image.width); ++x)
00605     {
00606       int index = y*range_image.width + x;
00607       Eigen::Vector3f& new_point = blurred_directions[index];
00608       new_point.setZero();
00609       float& new_score = blurred_scores[index];
00610       new_score = 0.0f;
00611       if (!range_image.isValid(index))
00612         continue;
00613       const BorderTraits& border_traits = border_descriptions_->points[index].traits;
00614       if (border_traits[BORDER_TRAIT__VEIL_POINT] || border_traits[BORDER_TRAIT__SHADOW_BORDER])
00615         continue;
00616       const Eigen::Vector3f& point = surface_change_directions_[index];
00617       float counter = 0.0f;
00618       for (int y2=y-blur_radius; y2<y+blur_radius; ++y2)
00619       {
00620         for (int x2=x-blur_radius; x2<x+blur_radius; ++x2)
00621         {
00622           if (!range_image.isInImage(x2,y2))
00623             continue;
00624           int index2 = y2*range_image.width + x2;
00625           float score = surface_change_scores_[index2];
00626           //if (score == 0.0f)
00627             //continue;
00628             //
00629           if (score > 0.0f)
00630           {
00631             Eigen::Vector3f& neighbor = surface_change_directions_[index2];
00632             //if (fabs(neighbor.norm()-1) > 1e-4)
00633               //cerr<<PVARN(neighbor)<<PVARN(score);
00634             if (point.dot(neighbor)<0.0f)
00635               neighbor *= -1.0f;
00636             new_point += score*neighbor;
00637           }
00638           new_score += score;
00639           counter += 1.0f;
00640         }
00641       }
00642       new_point.normalize();
00643       if (counter > 0.0f)
00644         new_score /= counter;
00645     }
00646   }
00647   delete[] surface_change_directions_;
00648   surface_change_directions_ = blurred_directions;
00649   delete[] surface_change_scores_;
00650   surface_change_scores_ = blurred_scores;
00651 }
00652 
00654 void 
00655 RangeImageBorderExtractor::computeFeature (PointCloudOut& output)
00656 {
00657   output.points.clear();
00658   
00659   if (indices_)
00660   {
00661     std::cerr << __PRETTY_FUNCTION__
00662               << ": Sorry, usage of indices for the extraction is not supported for range image border extraction (yet).\n\n";
00663     output.width = output.height = 0;
00664     output.points.clear ();
00665     return;
00666   }
00667   
00668   if (range_image_==NULL)
00669   {
00670     std::cerr << __PRETTY_FUNCTION__
00671               << ": RangeImage is not set. Sorry, the border extraction works on range images, not on normal point clouds."
00672               << " Use setRangeImage(...).\n\n";
00673     output.width = output.height = 0;
00674     output.points.clear ();
00675     return;
00676   }
00677   output = getBorderDescriptions ();
00678 }
00679 
00681 void 
00682 RangeImageBorderExtractor::compute (PointCloudOut& output)
00683 {
00684   computeFeature (output);
00685 }
00686 
00687 }  // namespace end


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