Extract obstacle borders from range images, meaning positions where there is a transition from foreground to background. More...
#include <range_image_border_extractor.h>

Classes | |
| struct | LocalSurface |
| Stores some information extracted from the neighborhood of a point. More... | |
| struct | Parameters |
| Parameters used in this class. More... | |
| struct | ShadowBorderIndices |
| Stores the indices of the shadow border corresponding to obstacle borders. More... | |
Public Types | |
| typedef Feature < PointWithRange, BorderDescription > | BaseClass |
| typedef boost::shared_ptr < const RangeImageBorderExtractor > | ConstPtr |
| typedef boost::shared_ptr < RangeImageBorderExtractor > | Ptr |
Public Member Functions | |
| void | clearData () |
| Erase all data calculated for the current range image. | |
| void | compute (PointCloudOut &output) |
| float * | getAnglesImageForBorderDirections () |
| Get the 2D directions in the range image from the border directions - probably mainly useful for visualization. | |
| float * | getAnglesImageForSurfaceChangeDirections () |
| Get the 2D directions in the range image from the surface change directions - probably mainly useful for visualization. | |
| PointCloudOut & | getBorderDescriptions () |
| Eigen::Vector3f ** | getBorderDirections () |
| float * | getBorderScoresBottom () |
| float * | getBorderScoresLeft () |
| float * | getBorderScoresRight () |
| float * | getBorderScoresTop () |
| Parameters & | getParameters () |
| const RangeImage & | getRangeImage () const |
| ShadowBorderIndices ** | getShadowBorderInformations () |
| Eigen::Vector3f * | getSurfaceChangeDirections () |
| float * | getSurfaceChangeScores () |
| LocalSurface ** | getSurfaceStructure () |
| bool | hasRangeImage () const |
| RangeImageBorderExtractor (const RangeImage *range_image=NULL) | |
| void | setRangeImage (const RangeImage *range_image) |
| Provide a pointer to the range image. | |
| virtual | ~RangeImageBorderExtractor () |
Static Public Member Functions | |
| static float | getObstacleBorderAngle (const BorderTraits &border_traits) |
| Take the information from BorderTraits to calculate the local direction of the border. | |
Protected Member Functions | |
| void | blurSurfaceChanges () |
| Apply a blur to the surface change images. | |
| void | calculateBorderDirection (int x, int y) |
| Calculate the 3D direction of the border just using the border traits at this position (facing away from the obstacle) | |
| void | calculateBorderDirections () |
| Call calculateBorderDirection for every point and average the result over parameters_.pixel_radius_border_direction. | |
| bool | calculateMainPrincipalCurvature (int x, int y, int radius, float &magnitude, Eigen::Vector3f &main_direction) const |
| Calculate the main principal curvature (the largest eigenvalue and corresponding eigenvector for the normals in the area) in the given point. | |
| void | calculateSurfaceChanges () |
| Uses either the border or principal curvature to define a score how much the surface changes in a point (1 for a border) and what the main direction of that change is. | |
| bool | changeScoreAccordingToShadowBorderValue (int x, int y, int offset_x, int offset_y, float *border_scores, float *border_scores_other_direction, int &shadow_border_idx) const |
| Find the best corresponding shadow border and lower score according to the shadow borders value. | |
| bool | checkIfMaximum (int x, int y, int offset_x, int offset_y, float *border_scores, int shadow_border_idx) const |
| Check if a potential border point is a maximum regarding the border score. | |
| bool | checkPotentialBorder (int x, int y, int offset_x, int offset_y, float *border_scores_left, float *border_scores_right, int &shadow_border_idx) const |
| Check if a potential border point has a corresponding shadow border. | |
| void | classifyBorders () |
| Classify the pixels in the range image according to the different classes defined below in enum BorderClass. minImpactAngle (in radians) defines how flat the angle at which a surface was seen can be. | |
| virtual void | computeFeature (PointCloudOut &output) |
| Implementation of abstract derived function. | |
| void | extractBorderScoreImages () |
| Get images representing the probability that the corresponding pixels are borders in that direction (see getBorderScores... ()) | |
| void | extractLocalSurfaceStructure () |
| Extract local plane information in every point (see getSurfaceStructure ()) | |
| void | findAndEvaluateShadowBorders () |
| Find the best corresponding shadow border and lower score according to the shadow borders value. | |
| bool | get3dDirection (const BorderDescription &border_description, Eigen::Vector3f &direction, const LocalSurface *local_surface=NULL) |
| Calculate a 3d direction from a border point by projecting the direction in the range image - returns false if direction could not be calculated. | |
| float | getNeighborDistanceChangeScore (const LocalSurface &local_surface, int x, int y, int offset_x, int offset_y, int pixel_radius=1) const |
| Calculate a border score based on how distant the neighbor is, compared to the closest neighbors /param local_surface /param x /param y /param offset_x /param offset_y /param pixel_radius (defaults to 1) /return the resulting border score. | |
| float | getNormalBasedBorderScore (const LocalSurface &local_surface, int x, int y, int offset_x, int offset_y) const |
| Calculate a border score based on how much the neighbor is away from the local surface plane. | |
| float | updatedScoreAccordingToNeighborValues (int x, int y, const float *border_scores) const |
| Returns a new score for the given pixel that is >= the original value, based on the neighbors values. | |
| float * | updatedScoresAccordingToNeighborValues (const float *border_scores) const |
| For all pixels, returns a new score that is >= the original value, based on the neighbors values. | |
| void | updateScoresAccordingToNeighborValues () |
| Replace all border score values with updates according to updatedScoreAccordingToNeighborValues. | |
Protected Attributes | |
| PointCloudOut * | border_descriptions_ |
| Eigen::Vector3f ** | border_directions_ |
| float * | border_scores_bottom_ |
| float * | border_scores_left_ |
| float * | border_scores_right_ |
| float * | border_scores_top_ |
| Parameters | parameters_ |
| const RangeImage * | range_image_ |
| int | range_image_size_during_extraction_ |
| ShadowBorderIndices ** | shadow_border_informations_ |
| Eigen::Vector3f * | surface_change_directions_ |
| float * | surface_change_scores_ |
| LocalSurface ** | surface_structure_ |
Extract obstacle borders from range images, meaning positions where there is a transition from foreground to background.
Definition at line 59 of file range_image_border_extractor.h.
Reimplemented from pcl::Feature< PointWithRange, BorderDescription >.
Definition at line 65 of file range_image_border_extractor.h.
| typedef boost::shared_ptr<const RangeImageBorderExtractor> pcl::RangeImageBorderExtractor::ConstPtr |
Reimplemented from pcl::Feature< PointWithRange, BorderDescription >.
Definition at line 63 of file range_image_border_extractor.h.
| typedef boost::shared_ptr<RangeImageBorderExtractor> pcl::RangeImageBorderExtractor::Ptr |
Reimplemented from pcl::Feature< PointWithRange, BorderDescription >.
Definition at line 62 of file range_image_border_extractor.h.
| pcl::RangeImageBorderExtractor::RangeImageBorderExtractor | ( | const RangeImage * | range_image = NULL | ) |
Constructor
Definition at line 56 of file range_image_border_extractor.cpp.
Destructor
Definition at line 65 of file range_image_border_extractor.cpp.
| void pcl::RangeImageBorderExtractor::blurSurfaceChanges | ( | ) | [protected] |
Apply a blur to the surface change images.
Definition at line 593 of file range_image_border_extractor.cpp.
| void pcl::RangeImageBorderExtractor::calculateBorderDirection | ( | int | x, |
| int | y | ||
| ) | [inline, protected] |
Calculate the 3D direction of the border just using the border traits at this position (facing away from the obstacle)
| x | the x-coordinate of the input position |
| y | the y-coordinate of the input position |
Definition at line 165 of file range_image_border_extractor.hpp.
| void pcl::RangeImageBorderExtractor::calculateBorderDirections | ( | ) | [protected] |
Call calculateBorderDirection for every point and average the result over parameters_.pixel_radius_border_direction.
Definition at line 462 of file range_image_border_extractor.cpp.
| bool pcl::RangeImageBorderExtractor::calculateMainPrincipalCurvature | ( | int | x, |
| int | y, | ||
| int | radius, | ||
| float & | magnitude, | ||
| Eigen::Vector3f & | main_direction | ||
| ) | const [inline, protected] |
Calculate the main principal curvature (the largest eigenvalue and corresponding eigenvector for the normals in the area) in the given point.
| x | the x-coordinate of the input point |
| y | the y-coordinate of the input point |
| radius | the pixel radius that is used to find neighboring points |
| magnitude | the resulting magnitude |
| main_direction | the resulting direction |
Definition at line 315 of file range_image_border_extractor.hpp.
| void pcl::RangeImageBorderExtractor::calculateSurfaceChanges | ( | ) | [protected] |
Uses either the border or principal curvature to define a score how much the surface changes in a point (1 for a border) and what the main direction of that change is.
Definition at line 544 of file range_image_border_extractor.cpp.
| bool pcl::RangeImageBorderExtractor::changeScoreAccordingToShadowBorderValue | ( | int | x, |
| int | y, | ||
| int | offset_x, | ||
| int | offset_y, | ||
| float * | border_scores, | ||
| float * | border_scores_other_direction, | ||
| int & | shadow_border_idx | ||
| ) | const [inline, protected] |
Find the best corresponding shadow border and lower score according to the shadow borders value.
| x | |
| y | |
| offset_x | |
| offset_y | |
| border_scores | |
| border_scores_other_direction | |
| shadow_border_idx |
Definition at line 183 of file range_image_border_extractor.hpp.
| bool pcl::RangeImageBorderExtractor::checkIfMaximum | ( | int | x, |
| int | y, | ||
| int | offset_x, | ||
| int | offset_y, | ||
| float * | border_scores, | ||
| int | shadow_border_idx | ||
| ) | const [inline, protected] |
Check if a potential border point is a maximum regarding the border score.
| x | the x-coordinate of the input point |
| y | the y-coordinate of the input point |
| offset_x | |
| offset_y | |
| border_scores | |
| shadow_border_idx |
Definition at line 292 of file range_image_border_extractor.hpp.
| bool pcl::RangeImageBorderExtractor::checkPotentialBorder | ( | int | x, |
| int | y, | ||
| int | offset_x, | ||
| int | offset_y, | ||
| float * | border_scores_left, | ||
| float * | border_scores_right, | ||
| int & | shadow_border_idx | ||
| ) | const [inline, protected] |
Check if a potential border point has a corresponding shadow border.
| x | the x-coordinate of the input point |
| y | the y-coordinate of the input point |
| offset_x | |
| offset_y | |
| border_scores_left | |
| border_scores_right | |
| shadow_border_idx |
Definition at line 261 of file range_image_border_extractor.hpp.
| void pcl::RangeImageBorderExtractor::classifyBorders | ( | ) | [protected] |
Classify the pixels in the range image according to the different classes defined below in enum BorderClass. minImpactAngle (in radians) defines how flat the angle at which a surface was seen can be.
Definition at line 355 of file range_image_border_extractor.cpp.
Erase all data calculated for the current range image.
Definition at line 80 of file range_image_border_extractor.cpp.
| void pcl::RangeImageBorderExtractor::compute | ( | PointCloudOut & | output | ) |
Overwrite the compute function of the base class
Reimplemented from pcl::Feature< PointWithRange, BorderDescription >.
Definition at line 683 of file range_image_border_extractor.cpp.
| void pcl::RangeImageBorderExtractor::computeFeature | ( | PointCloudOut & | output | ) | [protected, virtual] |
Implementation of abstract derived function.
Implements pcl::Feature< PointWithRange, BorderDescription >.
Definition at line 656 of file range_image_border_extractor.cpp.
| void pcl::RangeImageBorderExtractor::extractBorderScoreImages | ( | ) | [protected] |
Get images representing the probability that the corresponding pixels are borders in that direction (see getBorderScores... ())
Definition at line 154 of file range_image_border_extractor.cpp.
| void pcl::RangeImageBorderExtractor::extractLocalSurfaceStructure | ( | ) | [protected] |
Extract local plane information in every point (see getSurfaceStructure ())
Definition at line 107 of file range_image_border_extractor.cpp.
| void pcl::RangeImageBorderExtractor::findAndEvaluateShadowBorders | ( | ) | [protected] |
Find the best corresponding shadow border and lower score according to the shadow borders value.
Definition at line 228 of file range_image_border_extractor.cpp.
| bool pcl::RangeImageBorderExtractor::get3dDirection | ( | const BorderDescription & | border_description, |
| Eigen::Vector3f & | direction, | ||
| const LocalSurface * | local_surface = NULL |
||
| ) | [inline, protected] |
Calculate a 3d direction from a border point by projecting the direction in the range image - returns false if direction could not be calculated.
| border_description | |
| direction | |
| local_surface |
Definition at line 123 of file range_image_border_extractor.hpp.
Get the 2D directions in the range image from the border directions - probably mainly useful for visualization.
Definition at line 278 of file range_image_border_extractor.cpp.
Get the 2D directions in the range image from the surface change directions - probably mainly useful for visualization.
Definition at line 313 of file range_image_border_extractor.cpp.
Definition at line 170 of file range_image_border_extractor.h.
| Eigen::Vector3f** pcl::RangeImageBorderExtractor::getBorderDirections | ( | ) | [inline] |
Definition at line 176 of file range_image_border_extractor.h.
| float* pcl::RangeImageBorderExtractor::getBorderScoresBottom | ( | ) | [inline] |
Definition at line 164 of file range_image_border_extractor.h.
| float* pcl::RangeImageBorderExtractor::getBorderScoresLeft | ( | ) | [inline] |
Definition at line 155 of file range_image_border_extractor.h.
| float* pcl::RangeImageBorderExtractor::getBorderScoresRight | ( | ) | [inline] |
Definition at line 158 of file range_image_border_extractor.h.
| float* pcl::RangeImageBorderExtractor::getBorderScoresTop | ( | ) | [inline] |
Definition at line 161 of file range_image_border_extractor.h.
| float pcl::RangeImageBorderExtractor::getNeighborDistanceChangeScore | ( | const LocalSurface & | local_surface, |
| int | x, | ||
| int | y, | ||
| int | offset_x, | ||
| int | offset_y, | ||
| int | pixel_radius = 1 |
||
| ) | const [inline, protected] |
Calculate a border score based on how distant the neighbor is, compared to the closest neighbors /param local_surface /param x /param y /param offset_x /param offset_y /param pixel_radius (defaults to 1) /return the resulting border score.
Definition at line 70 of file range_image_border_extractor.hpp.
| float pcl::RangeImageBorderExtractor::getNormalBasedBorderScore | ( | const LocalSurface & | local_surface, |
| int | x, | ||
| int | y, | ||
| int | offset_x, | ||
| int | offset_y | ||
| ) | const [inline, protected] |
Calculate a border score based on how much the neighbor is away from the local surface plane.
| local_surface | |
| x | |
| y | |
| offset_x | |
| offset_y |
| float pcl::RangeImageBorderExtractor::getObstacleBorderAngle | ( | const BorderTraits & | border_traits | ) | [inline, static] |
Take the information from BorderTraits to calculate the local direction of the border.
| border_traits | contains the information needed to calculate the border angle |
Definition at line 45 of file range_image_border_extractor.hpp.
| Parameters& pcl::RangeImageBorderExtractor::getParameters | ( | ) | [inline] |
Definition at line 146 of file range_image_border_extractor.h.
| const RangeImage& pcl::RangeImageBorderExtractor::getRangeImage | ( | ) | const [inline] |
Definition at line 152 of file range_image_border_extractor.h.
Definition at line 173 of file range_image_border_extractor.h.
| Eigen::Vector3f* pcl::RangeImageBorderExtractor::getSurfaceChangeDirections | ( | ) | [inline] |
Definition at line 182 of file range_image_border_extractor.h.
| float* pcl::RangeImageBorderExtractor::getSurfaceChangeScores | ( | ) | [inline] |
Definition at line 179 of file range_image_border_extractor.h.
| LocalSurface** pcl::RangeImageBorderExtractor::getSurfaceStructure | ( | ) | [inline] |
Definition at line 167 of file range_image_border_extractor.h.
| bool pcl::RangeImageBorderExtractor::hasRangeImage | ( | ) | const [inline] |
Definition at line 149 of file range_image_border_extractor.h.
| void pcl::RangeImageBorderExtractor::setRangeImage | ( | const RangeImage * | range_image | ) |
Provide a pointer to the range image.
| range_image | a pointer to the range_image |
Definition at line 72 of file range_image_border_extractor.cpp.
| float pcl::RangeImageBorderExtractor::updatedScoreAccordingToNeighborValues | ( | int | x, |
| int | y, | ||
| const float * | border_scores | ||
| ) | const [inline, protected] |
Returns a new score for the given pixel that is >= the original value, based on the neighbors values.
| x | the x-coordinate of the input pixel |
| y | the y-coordinate of the input pixel |
| border_scores | the input border scores |
Definition at line 229 of file range_image_border_extractor.hpp.
| float * pcl::RangeImageBorderExtractor::updatedScoresAccordingToNeighborValues | ( | const float * | border_scores | ) | const [protected] |
For all pixels, returns a new score that is >= the original value, based on the neighbors values.
| border_scores | the input border scores |
Definition at line 194 of file range_image_border_extractor.cpp.
| void pcl::RangeImageBorderExtractor::updateScoresAccordingToNeighborValues | ( | ) | [protected] |
Replace all border score values with updates according to updatedScoreAccordingToNeighborValues.
Definition at line 206 of file range_image_border_extractor.cpp.
Definition at line 192 of file range_image_border_extractor.h.
Eigen::Vector3f** pcl::RangeImageBorderExtractor::border_directions_ [protected] |
Definition at line 194 of file range_image_border_extractor.h.
float * pcl::RangeImageBorderExtractor::border_scores_bottom_ [protected] |
Definition at line 190 of file range_image_border_extractor.h.
float* pcl::RangeImageBorderExtractor::border_scores_left_ [protected] |
Definition at line 190 of file range_image_border_extractor.h.
float * pcl::RangeImageBorderExtractor::border_scores_right_ [protected] |
Definition at line 190 of file range_image_border_extractor.h.
float * pcl::RangeImageBorderExtractor::border_scores_top_ [protected] |
Definition at line 190 of file range_image_border_extractor.h.
Definition at line 187 of file range_image_border_extractor.h.
const RangeImage* pcl::RangeImageBorderExtractor::range_image_ [protected] |
Definition at line 188 of file range_image_border_extractor.h.
Definition at line 189 of file range_image_border_extractor.h.
Definition at line 193 of file range_image_border_extractor.h.
Eigen::Vector3f* pcl::RangeImageBorderExtractor::surface_change_directions_ [protected] |
Definition at line 197 of file range_image_border_extractor.h.
float* pcl::RangeImageBorderExtractor::surface_change_scores_ [protected] |
Definition at line 196 of file range_image_border_extractor.h.
Definition at line 191 of file range_image_border_extractor.h.