range_image_border_extractor.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #ifndef PCL_RANGE_IMAGE_BORDER_EXTRACTOR_H_
00036 #define PCL_RANGE_IMAGE_BORDER_EXTRACTOR_H_
00037 
00038 #include <pcl/point_types.h>
00039 #include <pcl/features/feature.h>
00040 
00041 #if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3
00042 #pragma GCC diagnostic ignored "-Weffc++"
00043 #endif
00044 namespace pcl
00045 {
00046   // FORWARD DECLARATIONS:
00047   class RangeImage;
00048   template <typename PointType>
00049   class PointCloud;
00050 
00056   class PCL_EXPORTS RangeImageBorderExtractor : public Feature<PointWithRange,BorderDescription>
00057   {
00058     public:
00059       // =====TYPEDEFS=====
00060       typedef Feature<PointWithRange,BorderDescription> BaseClass;
00061       
00062       // =====PUBLIC STRUCTS=====
00064       struct LocalSurface
00065       {
00066         LocalSurface () : 
00067           normal (), neighborhood_mean (), eigen_values (), normal_no_jumps (), 
00068           neighborhood_mean_no_jumps (), eigen_values_no_jumps (), max_neighbor_distance_squared () {}
00069 
00070         Eigen::Vector3f normal;
00071         Eigen::Vector3f neighborhood_mean;
00072         Eigen::Vector3f eigen_values;
00073         Eigen::Vector3f normal_no_jumps;
00074         Eigen::Vector3f neighborhood_mean_no_jumps;
00075         Eigen::Vector3f eigen_values_no_jumps;
00076         float max_neighbor_distance_squared;
00077       };
00078       
00080       struct ShadowBorderIndices 
00081       {
00082         ShadowBorderIndices () : left (-1), right (-1), top (-1), bottom (-1) {}
00083         int left, right, top, bottom;
00084       };
00085 
00087       struct Parameters
00088       {
00089         Parameters () : max_no_of_threads(1), pixel_radius_borders (3), pixel_radius_plane_extraction (2), pixel_radius_border_direction (2), 
00090                        minimum_border_probability (0.8f), pixel_radius_principal_curvature (2) {}
00091         int max_no_of_threads;
00092         int pixel_radius_borders;
00093         int pixel_radius_plane_extraction;
00094         int pixel_radius_border_direction;
00095         float minimum_border_probability;
00096         int pixel_radius_principal_curvature;
00097       };
00098       
00099       // =====STATIC METHODS=====
00103       static inline float
00104       getObstacleBorderAngle (const BorderTraits& border_traits);
00105       
00106       // =====CONSTRUCTOR & DESTRUCTOR=====
00108       RangeImageBorderExtractor (const RangeImage* range_image=NULL);
00110       ~RangeImageBorderExtractor ();
00111       
00112       // =====METHODS=====
00116       void
00117       setRangeImage (const RangeImage* range_image);
00118       
00120       void
00121       clearData ();
00122        
00126       float*
00127       getAnglesImageForBorderDirections ();
00128 
00132       float*
00133       getAnglesImageForSurfaceChangeDirections ();
00134       
00136       void
00137       compute (PointCloudOut& output);
00138       
00139       // =====GETTER=====
00140       Parameters&
00141       getParameters () { return (parameters_); }
00142 
00143       bool
00144       hasRangeImage () const { return range_image_ != NULL; }
00145 
00146       const RangeImage&
00147       getRangeImage () const { return *range_image_; }
00148 
00149       float*
00150       getBorderScoresLeft ()   { extractBorderScoreImages (); return border_scores_left_; }
00151 
00152       float*
00153       getBorderScoresRight ()  { extractBorderScoreImages (); return border_scores_right_; }
00154 
00155       float*
00156       getBorderScoresTop ()    { extractBorderScoreImages (); return border_scores_top_; }
00157 
00158       float*
00159       getBorderScoresBottom () { extractBorderScoreImages (); return border_scores_bottom_; }
00160 
00161       LocalSurface**
00162       getSurfaceStructure () { extractLocalSurfaceStructure (); return surface_structure_; }
00163 
00164       PointCloudOut&
00165       getBorderDescriptions () { classifyBorders (); return *border_descriptions_; }
00166 
00167       ShadowBorderIndices**
00168       getShadowBorderInformations () { findAndEvaluateShadowBorders (); return shadow_border_informations_; }
00169 
00170       Eigen::Vector3f**
00171       getBorderDirections () { calculateBorderDirections (); return border_directions_; }
00172 
00173       float*
00174       getSurfaceChangeScores () { calculateSurfaceChanges (); return surface_change_scores_; }
00175 
00176       Eigen::Vector3f*
00177       getSurfaceChangeDirections () { calculateSurfaceChanges (); return surface_change_directions_; }
00178       
00179       
00180     protected:
00181       // =====PROTECTED MEMBER VARIABLES=====
00182       Parameters parameters_;
00183       const RangeImage* range_image_;
00184       int range_image_size_during_extraction_;
00185       float* border_scores_left_, * border_scores_right_, * border_scores_top_, * border_scores_bottom_;
00186       LocalSurface** surface_structure_;
00187       PointCloudOut* border_descriptions_;
00188       ShadowBorderIndices** shadow_border_informations_;
00189       Eigen::Vector3f** border_directions_;
00190       
00191       float* surface_change_scores_;
00192       Eigen::Vector3f* surface_change_directions_;
00193       
00194       
00195       // =====PROTECTED METHODS=====
00205       inline float
00206       getNeighborDistanceChangeScore (const LocalSurface& local_surface, int x, int y, 
00207                                       int offset_x, int offset_y, int pixel_radius=1) const;
00208       
00217       inline float
00218       getNormalBasedBorderScore (const LocalSurface& local_surface, int x, int y, 
00219                                  int offset_x, int offset_y) const;
00220       
00231       inline bool
00232       changeScoreAccordingToShadowBorderValue (int x, int y, int offset_x, int offset_y, float* border_scores,
00233                                                float* border_scores_other_direction, int& shadow_border_idx) const;
00234       
00241       inline float
00242       updatedScoreAccordingToNeighborValues (int x, int y, const float* border_scores) const;
00243 
00248       float*
00249       updatedScoresAccordingToNeighborValues (const float* border_scores) const;
00250 
00252       void
00253       updateScoresAccordingToNeighborValues ();
00254       
00265       inline bool
00266       checkPotentialBorder (int x, int y, int offset_x, int offset_y, float* border_scores_left,
00267                             float* border_scores_right, int& shadow_border_idx) const;
00268 
00278       inline bool
00279       checkIfMaximum (int x, int y, int offset_x, int offset_y, float* border_scores, int shadow_border_idx) const;
00280       
00282       void
00283       findAndEvaluateShadowBorders ();
00284       
00286       void
00287       extractLocalSurfaceStructure ();
00288       
00292       void
00293       extractBorderScoreImages ();
00294       
00298       void
00299       classifyBorders ();
00300       
00306       inline void
00307       calculateBorderDirection (int x, int y);
00308       
00312       void
00313       calculateBorderDirections ();
00314       
00322       inline bool
00323       get3dDirection (const BorderDescription& border_description, Eigen::Vector3f& direction,
00324                       const LocalSurface* local_surface=NULL);
00325       
00334       inline bool
00335       calculateMainPrincipalCurvature (int x, int y, int radius, float& magnitude,
00336                                        Eigen::Vector3f& main_direction) const;
00337       
00340       void
00341       calculateSurfaceChanges ();
00342 
00344       void
00345       blurSurfaceChanges ();
00346       
00348       virtual void
00349       computeFeature (PointCloudOut &output);
00350 
00351     private:
00355       void 
00356       computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf>&) {}
00357   };
00358 }  // namespace end
00359 #if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3
00360 #pragma GCC diagnostic warning "-Weffc++"
00361 #endif
00362 
00363 #include <pcl/features/impl/range_image_border_extractor.hpp>  // Definitions of templated and inline functions
00364 
00365 #endif  //#ifndef PCL_RANGE_IMAGE_BORDER_EXTRACTOR_H_


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