Surface normal estimation on organized data using integral images. More...
#include <integral_image_normal.h>
Public Types | |
enum | BorderPolicy { BORDER_POLICY_IGNORE, BORDER_POLICY_MIRROR } |
Different types of border handling. More... | |
typedef boost::shared_ptr < const IntegralImageNormalEstimation < PointInT, PointOutT > > | ConstPtr |
enum | NormalEstimationMethod { COVARIANCE_MATRIX, AVERAGE_3D_GRADIENT, AVERAGE_DEPTH_CHANGE, SIMPLE_3D_GRADIENT } |
Different normal estimation methods. More... | |
typedef Feature< PointInT, PointOutT >::PointCloudIn | PointCloudIn |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
typedef boost::shared_ptr < IntegralImageNormalEstimation < PointInT, PointOutT > > | Ptr |
Public Member Functions | |
void | computePointNormal (const int pos_x, const int pos_y, const unsigned point_index, PointOutT &normal) |
Computes the normal at the specified position. | |
void | computePointNormalMirror (const int pos_x, const int pos_y, const unsigned point_index, PointOutT &normal) |
Computes the normal at the specified position with mirroring for border handling. | |
float * | getDistanceMap () |
Returns a pointer to the distance map which was computed internally. | |
void | getViewPoint (float &vpx, float &vpy, float &vpz) |
Get the viewpoint. | |
IntegralImageNormalEstimation () | |
Constructor. | |
void | setBorderPolicy (const BorderPolicy border_policy) |
Sets the policy for handling borders. | |
void | setDepthDependentSmoothing (bool use_depth_dependent_smoothing) |
Set whether to use depth depending smoothing or not. | |
virtual void | setInputCloud (const typename PointCloudIn::ConstPtr &cloud) |
Provide a pointer to the input dataset (overwrites the PCLBase::setInputCloud method) | |
void | setMaxDepthChangeFactor (float max_depth_change_factor) |
The depth change threshold for computing object borders. | |
void | setNormalEstimationMethod (NormalEstimationMethod normal_estimation_method) |
Set the normal estimation method. The current implemented algorithms are: | |
void | setNormalSmoothingSize (float normal_smoothing_size) |
Set the normal smoothing size. | |
void | setRectSize (const int width, const int height) |
Set the regions size which is considered for normal estimation. | |
void | setViewPoint (float vpx, float vpy, float vpz) |
Set the viewpoint. | |
void | useSensorOriginAsViewPoint () |
sets whether the sensor origin or a user given viewpoint should be used. After this method, the normal estimation method uses the sensor origin of the input cloud. to use a user defined view point, use the method setViewPoint | |
virtual | ~IntegralImageNormalEstimation () |
Destructor. | |
Protected Member Functions | |
void | computeFeature (PointCloudOut &output) |
Computes the normal for the complete cloud. | |
void | initData () |
Initialize the data structures, based on the normal estimation method chosen. | |
Private Member Functions | |
void | flipNormalTowardsViewpoint (const PointInT &point, float vp_x, float vp_y, float vp_z, float &nx, float &ny, float &nz) |
Flip (in place) the estimated normal of a point towards a given viewpoint. | |
void | initAverage3DGradientMethod () |
Internal initialization method for AVERAGE_3D_GRADIENT estimation. | |
void | initAverageDepthChangeMethod () |
Internal initialization method for AVERAGE_DEPTH_CHANGE estimation. | |
bool | initCompute () |
This method should get called before starting the actual computation. | |
void | initCovarianceMatrixMethod () |
Internal initialization method for COVARIANCE_MATRIX estimation. | |
void | initSimple3DGradientMethod () |
Internal initialization method for SIMPLE_3D_GRADIENT estimation. | |
Private Attributes | |
BorderPolicy | border_policy_ |
The policy for handling borders. | |
float * | depth_data_ |
float * | diff_x_ |
float * | diff_y_ |
float * | distance_map_ |
float | distance_threshold_ |
bool | init_average_3d_gradient_ |
True when a dataset has been received and the average 3d gradient data has been initialized. | |
bool | init_covariance_matrix_ |
True when a dataset has been received and the covariance_matrix data has been initialized. | |
bool | init_depth_change_ |
True when a dataset has been received and the depth change data has been initialized. | |
bool | init_simple_3d_gradient_ |
True when a dataset has been received and the simple 3d gradient data has been initialized. | |
IntegralImage2D< float, 1 > | integral_image_depth_ |
IntegralImage2D< float, 3 > | integral_image_DX_ |
IntegralImage2D< float, 3 > | integral_image_DY_ |
IntegralImage2D< float, 3 > | integral_image_XYZ_ |
float | max_depth_change_factor_ |
Threshold for detecting depth discontinuities. | |
NormalEstimationMethod | normal_estimation_method_ |
The normal estimation method to use. Currently, 3 implementations are provided: | |
float | normal_smoothing_size_ |
int | rect_height_ |
int | rect_height_2_ |
int | rect_height_4_ |
int | rect_width_ |
int | rect_width_2_ |
int | rect_width_4_ |
bool | use_depth_dependent_smoothing_ |
Smooth data based on depth (true/false). | |
bool | use_sensor_origin_ |
float | vpx_ |
Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit from NormalEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0. | |
float | vpy_ |
float | vpz_ |
Surface normal estimation on organized data using integral images.
Definition at line 56 of file integral_image_normal.h.
typedef boost::shared_ptr<const IntegralImageNormalEstimation<PointInT, PointOutT> > pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::ConstPtr |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
Definition at line 65 of file integral_image_normal.h.
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::PointCloudIn |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
Definition at line 93 of file integral_image_normal.h.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::PointCloudOut |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
Definition at line 94 of file integral_image_normal.h.
typedef boost::shared_ptr<IntegralImageNormalEstimation<PointInT, PointOutT> > pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::Ptr |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
Definition at line 64 of file integral_image_normal.h.
enum pcl::IntegralImageNormalEstimation::BorderPolicy |
Different types of border handling.
Definition at line 68 of file integral_image_normal.h.
enum pcl::IntegralImageNormalEstimation::NormalEstimationMethod |
Different normal estimation methods.
Definition at line 85 of file integral_image_normal.h.
pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::IntegralImageNormalEstimation | ( | ) | [inline] |
Constructor.
Definition at line 97 of file integral_image_normal.h.
pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::~IntegralImageNormalEstimation | ( | ) | [virtual] |
Destructor.
Definition at line 46 of file integral_image_normal.hpp.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [protected, virtual] |
Computes the normal for the complete cloud.
[out] | output | the resultant normals |
Implements pcl::Feature< PointInT, PointOutT >.
Definition at line 722 of file integral_image_normal.hpp.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::computePointNormal | ( | const int | pos_x, |
const int | pos_y, | ||
const unsigned | point_index, | ||
PointOutT & | normal | ||
) |
Computes the normal at the specified position.
[in] | pos_x | x position (pixel) |
[in] | pos_y | y position (pixel) |
[in] | point_index | the position index of the point |
[out] | normal | the output estimated normal |
Definition at line 207 of file integral_image_normal.hpp.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::computePointNormalMirror | ( | const int | pos_x, |
const int | pos_y, | ||
const unsigned | point_index, | ||
PointOutT & | normal | ||
) |
Computes the normal at the specified position with mirroring for border handling.
[in] | pos_x | x position (pixel) |
[in] | pos_y | y position (pixel) |
[in] | point_index | the position index of the point |
[out] | normal | the output estimated normal |
Definition at line 462 of file integral_image_normal.hpp.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::flipNormalTowardsViewpoint | ( | const PointInT & | point, |
float | vp_x, | ||
float | vp_y, | ||
float | vp_z, | ||
float & | nx, | ||
float & | ny, | ||
float & | nz | ||
) | [inline, private] |
Flip (in place) the estimated normal of a point towards a given viewpoint.
point | a given point |
vp_x | the X coordinate of the viewpoint |
vp_y | the X coordinate of the viewpoint |
vp_z | the X coordinate of the viewpoint |
nx | the resultant X component of the plane normal |
ny | the resultant Y component of the plane normal |
nz | the resultant Z component of the plane normal |
Definition at line 329 of file integral_image_normal.h.
float* pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::getDistanceMap | ( | ) | [inline] |
Returns a pointer to the distance map which was computed internally.
Definition at line 247 of file integral_image_normal.h.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::getViewPoint | ( | float & | vpx, |
float & | vpy, | ||
float & | vpz | ||
) | [inline] |
Get the viewpoint.
[out] | vpx | x-coordinate of the view point |
[out] | vpy | y-coordinate of the view point |
[out] | vpz | z-coordinate of the view point |
Definition at line 275 of file integral_image_normal.h.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::initAverage3DGradientMethod | ( | ) | [private] |
Internal initialization method for AVERAGE_3D_GRADIENT estimation.
Definition at line 141 of file integral_image_normal.hpp.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::initAverageDepthChangeMethod | ( | ) | [private] |
Internal initialization method for AVERAGE_DEPTH_CHANGE estimation.
Definition at line 190 of file integral_image_normal.hpp.
bool pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::initCompute | ( | ) | [private, virtual] |
This method should get called before starting the actual computation.
Reimplemented from pcl::Feature< PointInT, PointOutT >.
Definition at line 1003 of file integral_image_normal.hpp.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::initCovarianceMatrixMethod | ( | ) | [private] |
Internal initialization method for COVARIANCE_MATRIX estimation.
Definition at line 123 of file integral_image_normal.hpp.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::initData | ( | ) | [protected] |
Initialize the data structures, based on the normal estimation method chosen.
Definition at line 56 of file integral_image_normal.hpp.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::initSimple3DGradientMethod | ( | ) | [private] |
Internal initialization method for SIMPLE_3D_GRADIENT estimation.
Definition at line 105 of file integral_image_normal.hpp.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::setBorderPolicy | ( | const BorderPolicy | border_policy | ) | [inline] |
Sets the policy for handling borders.
[in] | border_policy | the border policy. |
Definition at line 142 of file integral_image_normal.h.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::setDepthDependentSmoothing | ( | bool | use_depth_dependent_smoothing | ) | [inline] |
Set whether to use depth depending smoothing or not.
[in] | use_depth_dependent_smoothing | decides whether the smoothing is depth dependent |
Definition at line 213 of file integral_image_normal.h.
virtual void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::setInputCloud | ( | const typename PointCloudIn::ConstPtr & | cloud | ) | [inline, virtual] |
Provide a pointer to the input dataset (overwrites the PCLBase::setInputCloud method)
[in] | cloud | the const boost shared pointer to a PointCloud message |
Definition at line 222 of file integral_image_normal.h.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::setMaxDepthChangeFactor | ( | float | max_depth_change_factor | ) | [inline] |
The depth change threshold for computing object borders.
[in] | max_depth_change_factor | the depth change threshold for computing object borders based on depth changes |
Definition at line 170 of file integral_image_normal.h.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::setNormalEstimationMethod | ( | NormalEstimationMethod | normal_estimation_method | ) | [inline] |
Set the normal estimation method. The current implemented algorithms are:
[in] | normal_estimation_method | the method used for normal estimation |
Definition at line 204 of file integral_image_normal.h.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::setNormalSmoothingSize | ( | float | normal_smoothing_size | ) | [inline] |
Set the normal smoothing size.
[in] | normal_smoothing_size | factor which influences the size of the area used to smooth normals (depth dependent if useDepthDependentSmoothing is true) |
Definition at line 180 of file integral_image_normal.h.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::setRectSize | ( | const int | width, |
const int | height | ||
) |
Set the regions size which is considered for normal estimation.
[in] | width | the width of the search rectangle |
[in] | height | the height of the search rectangle |
Definition at line 93 of file integral_image_normal.hpp.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::setViewPoint | ( | float | vpx, |
float | vpy, | ||
float | vpz | ||
) | [inline] |
Set the viewpoint.
vpx | the X coordinate of the viewpoint |
vpy | the Y coordinate of the viewpoint |
vpz | the Z coordinate of the viewpoint |
Definition at line 258 of file integral_image_normal.h.
void pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::useSensorOriginAsViewPoint | ( | ) | [inline] |
sets whether the sensor origin or a user given viewpoint should be used. After this method, the normal estimation method uses the sensor origin of the input cloud. to use a user defined view point, use the method setViewPoint
Definition at line 287 of file integral_image_normal.h.
BorderPolicy pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::border_policy_ [private] |
The policy for handling borders.
Definition at line 359 of file integral_image_normal.h.
float* pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::depth_data_ [private] |
depth data
Definition at line 388 of file integral_image_normal.h.
float* pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::diff_x_ [private] |
derivatives in x-direction
Definition at line 383 of file integral_image_normal.h.
float* pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::diff_y_ [private] |
derivatives in y-direction
Definition at line 385 of file integral_image_normal.h.
float* pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::distance_map_ [private] |
distance map
Definition at line 391 of file integral_image_normal.h.
float pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::distance_threshold_ [private] |
the threshold used to detect depth discontinuities
Definition at line 371 of file integral_image_normal.h.
bool pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::init_average_3d_gradient_ [private] |
True when a dataset has been received and the average 3d gradient data has been initialized.
Definition at line 406 of file integral_image_normal.h.
bool pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::init_covariance_matrix_ [private] |
True when a dataset has been received and the covariance_matrix data has been initialized.
Definition at line 403 of file integral_image_normal.h.
bool pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::init_depth_change_ [private] |
True when a dataset has been received and the depth change data has been initialized.
Definition at line 412 of file integral_image_normal.h.
bool pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::init_simple_3d_gradient_ [private] |
True when a dataset has been received and the simple 3d gradient data has been initialized.
Definition at line 409 of file integral_image_normal.h.
IntegralImage2D<float, 1> pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::integral_image_depth_ [private] |
integral image
Definition at line 378 of file integral_image_normal.h.
IntegralImage2D<float, 3> pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::integral_image_DX_ [private] |
integral image in x-direction
Definition at line 374 of file integral_image_normal.h.
IntegralImage2D<float, 3> pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::integral_image_DY_ [private] |
integral image in y-direction
Definition at line 376 of file integral_image_normal.h.
IntegralImage2D<float, 3> pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::integral_image_XYZ_ [private] |
integral image xyz
Definition at line 380 of file integral_image_normal.h.
float pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::max_depth_change_factor_ [private] |
Threshold for detecting depth discontinuities.
Definition at line 397 of file integral_image_normal.h.
NormalEstimationMethod pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::normal_estimation_method_ [private] |
The normal estimation method to use. Currently, 3 implementations are provided:
Definition at line 356 of file integral_image_normal.h.
float pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::normal_smoothing_size_ [private] |
Definition at line 400 of file integral_image_normal.h.
int pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::rect_height_ [private] |
The height of the neighborhood region used for computing the normal.
Definition at line 366 of file integral_image_normal.h.
int pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::rect_height_2_ [private] |
Definition at line 367 of file integral_image_normal.h.
int pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::rect_height_4_ [private] |
Definition at line 368 of file integral_image_normal.h.
int pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::rect_width_ [private] |
The width of the neighborhood region used for computing the normal.
Definition at line 362 of file integral_image_normal.h.
int pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::rect_width_2_ [private] |
Definition at line 363 of file integral_image_normal.h.
int pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::rect_width_4_ [private] |
Definition at line 364 of file integral_image_normal.h.
bool pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::use_depth_dependent_smoothing_ [private] |
Smooth data based on depth (true/false).
Definition at line 394 of file integral_image_normal.h.
bool pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::use_sensor_origin_ [private] |
whether the sensor origin of the input cloud or a user given viewpoint should be used.
Definition at line 419 of file integral_image_normal.h.
float pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::vpx_ [private] |
Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit from NormalEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0.
Definition at line 416 of file integral_image_normal.h.
float pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::vpy_ [private] |
Definition at line 416 of file integral_image_normal.h.
float pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::vpz_ [private] |
Definition at line 416 of file integral_image_normal.h.