00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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 namespace pcl
00042 {
00043
00044
00045 class RangeImage;
00046 template <typename PointType>
00047 class PointCloud;
00048
00053 class RangeImageBorderExtractor : public Feature<PointWithRange,BorderDescription>
00054 {
00055 public:
00056
00057 typedef Feature<PointWithRange,BorderDescription> BaseClass;
00058
00059
00061 struct LocalSurface
00062 {
00063 Eigen::Vector3f normal;
00064 Eigen::Vector3f neighborhood_mean;
00065 Eigen::Vector3f eigen_values;
00066 Eigen::Vector3f normal_no_jumps;
00067 Eigen::Vector3f neighborhood_mean_no_jumps;
00068 Eigen::Vector3f eigen_values_no_jumps;
00069 float max_neighbor_distance_squared;
00070 };
00072 struct ShadowBorderIndices {
00073 ShadowBorderIndices () : left (-1), right (-1), top (-1), bottom (-1) {}
00074 int left, right, top, bottom;
00075 };
00077 struct Parameters
00078 {
00079 Parameters () : pixel_radius_borders (3), pixel_radius_plane_extraction (2), pixel_radius_border_direction (2),
00080 minimum_border_probability (0.8), pixel_radius_principal_curvature (2) {}
00081 int pixel_radius_borders;
00082 int pixel_radius_plane_extraction;
00083 int pixel_radius_border_direction;
00084 float minimum_border_probability;
00085 int pixel_radius_principal_curvature;
00086 };
00087
00088
00092 static inline float
00093 getObstacleBorderAngle (const BorderTraits& border_traits);
00094
00095
00097 RangeImageBorderExtractor (const RangeImage* range_image=NULL);
00099 ~RangeImageBorderExtractor ();
00100
00101
00105 void
00106 setRangeImage (const RangeImage* range_image);
00107
00109 void
00110 clearData ();
00111
00115 float*
00116 getAnglesImageForBorderDirections ();
00117
00121 float*
00122 getAnglesImageForSurfaceChangeDirections ();
00123
00125 void
00126 compute (PointCloudOut& output);
00127
00128
00129 Parameters&
00130 getParameters () { return parameters_; }
00131
00132 bool
00133 hasRangeImage () const { return range_image_ != NULL; }
00134
00135 const RangeImage&
00136 getRangeImage () const { return *range_image_; }
00137
00138 float*
00139 getBorderScoresLeft () { extractBorderScoreImages (); return border_scores_left_; }
00140
00141 float*
00142 getBorderScoresRight () { extractBorderScoreImages (); return border_scores_right_; }
00143
00144 float*
00145 getBorderScoresTop () { extractBorderScoreImages (); return border_scores_top_; }
00146
00147 float*
00148 getBorderScoresBottom () { extractBorderScoreImages (); return border_scores_bottom_; }
00149
00150 LocalSurface**
00151 getSurfaceStructure () { extractLocalSurfaceStructure (); return surface_structure_; }
00152
00153 PointCloudOut&
00154 getBorderDescriptions () { classifyBorders (); return *border_descriptions_; }
00155
00156 ShadowBorderIndices**
00157 getShadowBorderInformations () { findAndEvaluateShadowBorders (); return shadow_border_informations_; }
00158
00159 Eigen::Vector3f**
00160 getBorderDirections () { calculateBorderDirections (); return border_directions_; }
00161
00162 float*
00163 getSurfaceChangeScores () { calculateSurfaceChanges (); return surface_change_scores_; }
00164
00165 Eigen::Vector3f*
00166 getSurfaceChangeDirections () { calculateSurfaceChanges (); return surface_change_directions_; }
00167
00168
00169 protected:
00170
00171 Parameters parameters_;
00172 const RangeImage* range_image_;
00173 float* border_scores_left_, * border_scores_right_, * border_scores_top_, * border_scores_bottom_;
00174 LocalSurface** surface_structure_;
00175 PointCloudOut* border_descriptions_;
00176 ShadowBorderIndices** shadow_border_informations_;
00177 Eigen::Vector3f** border_directions_;
00178
00179 float* surface_change_scores_;
00180 Eigen::Vector3f* surface_change_directions_;
00181
00182
00183
00193 inline float
00194 getNeighborDistanceChangeScore (const LocalSurface& local_surface, int x, int y,
00195 int offset_x, int offset_y, int pixel_radius=1) const;
00196
00205 inline float
00206 getNormalBasedBorderScore (const LocalSurface& local_surface, int x, int y,
00207 int offset_x, int offset_y) const;
00208
00219 inline bool
00220 changeScoreAccordingToShadowBorderValue (int x, int y, int offset_x, int offset_y, float* border_scores,
00221 float* border_scores_other_direction, int& shadow_border_idx) const;
00222
00229 inline float
00230 updatedScoreAccordingToNeighborValues (int x, int y, const float* border_scores) const;
00231
00236 float*
00237 updatedScoresAccordingToNeighborValues (const float* border_scores) const;
00238
00240 void
00241 updateScoresAccordingToNeighborValues ();
00242
00253 inline bool
00254 checkPotentialBorder (int x, int y, int offset_x, int offset_y, float* border_scores_left,
00255 float* border_scores_right, int& shadow_border_idx) const;
00256
00266 inline bool
00267 checkIfMaximum (int x, int y, int offset_x, int offset_y, float* border_scores, int shadow_border_idx) const;
00268
00270 void
00271 findAndEvaluateShadowBorders ();
00272
00274 void
00275 extractLocalSurfaceStructure ();
00276
00280 void
00281 extractBorderScoreImages ();
00282
00286 void
00287 classifyBorders ();
00288
00294 inline void
00295 calculateBorderDirection (int x, int y);
00296
00300 void
00301 calculateBorderDirections ();
00302
00310 inline bool
00311 get3dDirection (const BorderDescription& border_description, Eigen::Vector3f& direction,
00312 const LocalSurface* local_surface=NULL);
00313
00322 inline bool
00323 calculateMainPrincipalCurvature (int x, int y, int radius, float& magnitude,
00324 Eigen::Vector3f& main_direction) const;
00325
00328 void
00329 calculateSurfaceChanges ();
00330
00332 void
00333 blurSurfaceChanges ();
00334
00336 virtual void
00337 computeFeature (PointCloudOut &output);
00338 };
00339
00340 }
00341
00342 #include "pcl/features/range_image_border_extractor.hpp"
00343
00344 #endif //#ifndef PCL_RANGE_IMAGE_BORDER_EXTRACTOR_H_