orr_octree_zprojection.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  */
00038 
00039 /*
00040  * orr_octree_zprojection.cpp
00041  *
00042  *  Created on: Nov 17, 2012
00043  *      Author: papazov
00044  */
00045 
00046 #include <pcl/recognition/ransac_based/orr_octree_zprojection.h>
00047 #include <vector>
00048 
00049 using namespace std;
00050 
00051 //=========================================================================================================================================
00052 
00053 void
00054 pcl::recognition::ORROctreeZProjection::clear ()
00055 {
00056   if ( pixels_ )
00057   {
00058     for ( int i = 0 ; i < num_pixels_x_ ; ++i )
00059     {
00060       // Delete pixel by pixel
00061       for ( int j = 0 ; j < num_pixels_y_ ; ++j )
00062         if ( pixels_[i][j] )
00063           delete pixels_[i][j];
00064 
00065       // Delete the whole row
00066       delete[] pixels_[i];
00067     }
00068 
00069     delete[] pixels_;
00070     pixels_ = NULL;
00071   }
00072 
00073   if ( sets_ )
00074   {
00075     for ( int i = 0 ; i < num_pixels_x_ ; ++i )
00076     {
00077       for ( int j = 0 ; j < num_pixels_y_ ; ++j )
00078         if ( sets_[i][j] )
00079           delete sets_[i][j];
00080 
00081       delete[] sets_[i];
00082     }
00083 
00084     delete[] sets_;
00085     sets_ = NULL;
00086   }
00087 
00088   full_sets_.clear ();
00089   full_pixels_.clear ();
00090 }
00091 
00092 //=========================================================================================================================================
00093 
00094 void
00095 pcl::recognition::ORROctreeZProjection::build (const ORROctree& input, float eps_front, float eps_back)
00096 {
00097   this->clear();
00098 
00099   // Compute the bounding box of the full leaves
00100   const vector<ORROctree::Node*>& full_leaves = input.getFullLeaves ();
00101   vector<ORROctree::Node*>::const_iterator fl_it = full_leaves.begin ();
00102   float full_leaves_bounds[4];
00103 
00104   if ( full_leaves.empty() )
00105     return;
00106 
00107   // The initialization run
00108   full_leaves_bounds[0] = (*fl_it)->getBounds ()[0];
00109   full_leaves_bounds[1] = (*fl_it)->getBounds ()[1];
00110   full_leaves_bounds[2] = (*fl_it)->getBounds ()[2];
00111   full_leaves_bounds[3] = (*fl_it)->getBounds ()[3];
00112 
00113   for ( ++fl_it ; fl_it != full_leaves.end () ; ++fl_it )
00114   {
00115     if ( (*fl_it)->getBounds ()[0] < full_leaves_bounds[0] ) full_leaves_bounds[0] = (*fl_it)->getBounds ()[0];
00116     if ( (*fl_it)->getBounds ()[1] > full_leaves_bounds[1] ) full_leaves_bounds[1] = (*fl_it)->getBounds ()[1];
00117     if ( (*fl_it)->getBounds ()[2] < full_leaves_bounds[2] ) full_leaves_bounds[2] = (*fl_it)->getBounds ()[2];
00118     if ( (*fl_it)->getBounds ()[3] > full_leaves_bounds[3] ) full_leaves_bounds[3] = (*fl_it)->getBounds ()[3];
00119   }
00120 
00121   // Make some initializations
00122   pixel_size_ = input.getVoxelSize();
00123   inv_pixel_size_ = 1.0f/pixel_size_;
00124 
00125   bounds_[0] = full_leaves_bounds[0]; bounds_[1] = full_leaves_bounds[1];
00126   bounds_[2] = full_leaves_bounds[2]; bounds_[3] = full_leaves_bounds[3];
00127 
00128   extent_x_ = full_leaves_bounds[1] - full_leaves_bounds[0];
00129   extent_y_ = full_leaves_bounds[3] - full_leaves_bounds[2];
00130 
00131   num_pixels_x_ = static_cast<int> (extent_x_/pixel_size_ + 0.5f); // we do not need to round, but it's safer due to numerical errors
00132   num_pixels_y_ = static_cast<int> (extent_y_/pixel_size_ + 0.5f);
00133   num_pixels_   = num_pixels_x_*num_pixels_y_;
00134 
00135   int i, j;
00136 
00137   // Allocate and initialize memory for the pixels and the sets
00138   pixels_ = new Pixel**[num_pixels_x_];
00139   sets_ = new Set**[num_pixels_x_];
00140 
00141   for ( i = 0 ; i < num_pixels_x_ ; ++i )
00142   {
00143     pixels_[i] = new Pixel*[num_pixels_y_];
00144     sets_[i] = new Set*[num_pixels_y_];
00145 
00146     for ( j = 0 ; j < num_pixels_y_ ; ++j )
00147     {
00148       pixels_[i][j] = NULL;
00149       sets_[i][j] = NULL;
00150     }
00151   }
00152 
00153   int pixel_id = 0;
00154 
00155   // Project the octree full leaves onto the xy-plane
00156   for ( fl_it = full_leaves.begin () ; fl_it != full_leaves.end () ; ++fl_it )
00157   {
00158     this->getPixelCoordinates ((*fl_it)->getCenter(), i, j);
00159     // If there is no set/pixel and at this position -> create one
00160     if ( sets_[i][j] == NULL )
00161     {
00162       pixels_[i][j] = new Pixel (pixel_id++);
00163       sets_[i][j] = new Set (i, j);
00164       full_pixels_.push_back (pixels_[i][j]);
00165       full_sets_.push_back (sets_[i][j]);
00166     }
00167 
00168     // Insert the full octree leaf at the right position in the set
00169     sets_[i][j]->insert (*fl_it);
00170   }
00171 
00172   int len, maxlen, id_z1, id_z2;
00173   float cur_min, best_min, cur_max, best_max;
00174 
00175   // Now, at each occupied (i, j) position, get the longest connected component consisting of neighboring full leaves
00176   for ( list<Set*>::iterator current_set = full_sets_.begin () ; current_set != full_sets_.end () ; ++current_set )
00177   {
00178     // Get the first node in the set
00179     set<ORROctree::Node*, bool(*)(ORROctree::Node*,ORROctree::Node*)>::iterator node = (*current_set)->get_nodes ().begin ();
00180     // Initialize
00181     cur_min = best_min = (*node)->getBounds ()[4];
00182     cur_max = best_max = (*node)->getBounds ()[5];
00183     id_z1 = (*node)->getData ()->get3dIdZ ();
00184     maxlen = len = 1;
00185 
00186     // Find the longest 1D "connected component" at the current (i, j) position
00187     for ( ++node ; node != (*current_set)->get_nodes ().end () ; ++node, id_z1 = id_z2 )
00188     {
00189       id_z2 = (*node)->getData ()->get3dIdZ ();
00190       cur_max = (*node)->getBounds()[5];
00191 
00192       if ( id_z2 - id_z1 > 1 ) // This connected component is over
00193       {
00194         // Start a new connected component
00195         cur_min = (*node)->getBounds ()[4];
00196         len = 1;
00197       }
00198       else // This connected component is still ongoing
00199       {
00200         ++len;
00201         if ( len > maxlen )
00202         {
00203           // This connected component is the longest one
00204           maxlen = len;
00205           best_min = cur_min;
00206           best_max = cur_max;
00207         }
00208       }
00209     }
00210 
00211     i = (*current_set)->get_x ();
00212     j = (*current_set)->get_y ();
00213 
00214     pixels_[i][j]->set_z1 (best_min - eps_front);
00215     pixels_[i][j]->set_z2 (best_max  + eps_back);
00216   }
00217 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:27:30