Public Types | Public Member Functions | Protected Types | Protected Member Functions | Private Attributes
pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT > Class Template Reference

BOARDLocalReferenceFrameEstimation implements the BOrder Aware Repeatable Directions algorithm for local reference frame estimation as described here: More...

#include <board.h>

Inheritance diagram for pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const
BOARDLocalReferenceFrameEstimation
< PointInT, PointNT, PointOutT > > 
ConstPtr
typedef boost::shared_ptr
< BOARDLocalReferenceFrameEstimation
< PointInT, PointNT, PointOutT > > 
Ptr

Public Member Functions

 BOARDLocalReferenceFrameEstimation ()
 Constructor.
int getCheckMarginArraySize () const
 Gets the number of slices in which is divided the margin for the search of missing regions.
bool getFindHoles () const
 Gets whether holes in the margin of the support, for each point, are searched and accounted for in the estimation of the Reference Frame or not.
float getHoleSizeProbThresh () const
 Given the angle width of a hole in the support margin, gets the minimum percentage of a circumference this angle must cover to be considered a missing region in the support and hence used for the estimation of the Reference Frame.
float getMarginThresh () const
 Gets the percentage of the search radius (or tangent radius if set) after which a point is considered part of the support margin.
float getSteepThresh () const
 Gets the minimum steepness that the normals of the points situated on the borders of the hole, with reference to the normal of the best point found by the algorithm, must have in order to be considered in the calculation of the Reference Frame.
float getTangentRadius () const
 Get the maximum distance of the points used to estimate the x_axis and y_axis of the BOARD Reference Frame for a given point.
void setCheckMarginArraySize (int size)
 Sets the number of slices in which is divided the margin for the search of missing regions.
void setFindHoles (bool find_holes)
 Sets whether holes in the margin of the support, for each point, are searched and accounted for in the estimation of the Reference Frame or not.
void setHoleSizeProbThresh (float prob_thresh)
 Given the angle width of a hole in the support margin, sets the minimum percentage of a circumference this angle must cover to be considered a missing region in the support and hence used for the estimation of the Reference Frame.
void setMarginThresh (float margin_thresh)
 Sets the percentage of the search radius (or tangent radius if set) after which a point is considered part of the support margin.
void setSteepThresh (float steep_thresh)
 Sets the minimum steepness that the normals of the points situated on the borders of the hole, with reference to the normal of the best point found by the algorithm, must have in order to be considered in the calculation of the Reference Frame.
void setTangentRadius (float radius)
 Set the maximum distance of the points used to estimate the x_axis and y_axis of the BOARD Reference Frame for a given point.
virtual ~BOARDLocalReferenceFrameEstimation ()
 Empty destructor.

Protected Types

typedef Feature< PointInT,
PointOutT >::PointCloudIn 
PointCloudIn
typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut

Protected Member Functions

bool areEquals (float val1, float val2, float zero_float_eps=1E-8f) const
 Check if val1 and val2 are equals.
virtual void computeFeature (PointCloudOut &output)
 Abstract feature estimation method.
float computePointLRF (const int &index, Eigen::Matrix3f &lrf)
 Estimate the LRF descriptor for a given point based on its spatial neighborhood of 3D points with normals.
void directedOrthogonalAxis (Eigen::Vector3f const &axis, Eigen::Vector3f const &axis_origin, Eigen::Vector3f const &point, Eigen::Vector3f &directed_ortho_axis)
 Given an axis (with origin axis_origin), return the orthogonal axis directed to point.
float getAngleBetweenUnitVectors (Eigen::Vector3f const &v1, Eigen::Vector3f const &v2, Eigen::Vector3f const &axis)
 return the angle (in radians) that rotate v1 to v2 with respect to axis .
void normalDisambiguation (pcl::PointCloud< PointNT > const &normals_cloud, std::vector< int > const &normal_indices, Eigen::Vector3f &normal)
 Disambiguates a normal direction using adjacent normals.
void planeFitting (Eigen::Matrix< float, Eigen::Dynamic, 3 > const &points, Eigen::Vector3f &center, Eigen::Vector3f &norm)
 Compute Least Square Plane Fitting in a set of 3D points.
void projectPointOnPlane (Eigen::Vector3f const &point, Eigen::Vector3f const &origin_point, Eigen::Vector3f const &plane_normal, Eigen::Vector3f &projected_point)
 Given a plane (origin and normal) and a point, return the projection of x on plane.
void randomOrthogonalAxis (Eigen::Vector3f const &axis, Eigen::Vector3f &rand_ortho_axis)
 Given an axis, return a random orthogonal axis.
void resetData ()

Private Attributes

std::vector< bool > check_margin_array_
int check_margin_array_size_
 Number of slices that divide the support in order to determine if a missing region is present.
bool find_holes_
 If true, check if support is complete or has missing regions because it is too near to mesh borders.
float hole_size_prob_thresh_
 Threshold used to determine a missing region.
std::vector< float > margin_array_max_angle_
std::vector< float > margin_array_max_angle_normal_
std::vector< float > margin_array_min_angle_
std::vector< float > margin_array_min_angle_normal_
float margin_thresh_
 Threshold that define if a support point is near the margins.
float steep_thresh_
 Threshold that defines if a missing region contains a point with the most different normal.
float tangent_radius_
 Radius used to find tangent axis.

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
class pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >

BOARDLocalReferenceFrameEstimation implements the BOrder Aware Repeatable Directions algorithm for local reference frame estimation as described here:

Author:
Alioscia Petrelli (original), Tommaso Cavallari (PCL port)

Definition at line 59 of file board.h.


Member Typedef Documentation

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
typedef boost::shared_ptr<const BOARDLocalReferenceFrameEstimation<PointInT, PointNT, PointOutT> > pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::ConstPtr

Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.

Definition at line 63 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::PointCloudIn [protected]

Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.

Definition at line 239 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::PointCloudOut [protected]

Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.

Definition at line 240 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
typedef boost::shared_ptr<BOARDLocalReferenceFrameEstimation<PointInT, PointNT, PointOutT> > pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::Ptr

Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.

Definition at line 62 of file board.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::BOARDLocalReferenceFrameEstimation ( ) [inline]

Constructor.

Definition at line 66 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
virtual pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::~BOARDLocalReferenceFrameEstimation ( ) [inline, virtual]

Empty destructor.

Definition at line 84 of file board.h.


Member Function Documentation

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
bool pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::areEquals ( float  val1,
float  val2,
float  zero_float_eps = 1E-8f 
) const [inline, protected]

Check if val1 and val2 are equals.

Parameters:
[in]val1first number to check.
[in]val2second number to check.
[in]zero_float_epsepsilon
Returns:
true if val1 is equal to val2, false otherwise.

Definition at line 333 of file board.h.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::computeFeature ( PointCloudOut output) [protected, virtual]

Abstract feature estimation method.

Parameters:
[out]outputthe resultant features

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 596 of file board.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
float pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::computePointLRF ( const int &  index,
Eigen::Matrix3f &  lrf 
) [protected]

Estimate the LRF descriptor for a given point based on its spatial neighborhood of 3D points with normals.

Parameters:
[in]indexthe index of the point in input_
[out]lrfthe resultant local reference frame

Definition at line 197 of file board.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::directedOrthogonalAxis ( Eigen::Vector3f const &  axis,
Eigen::Vector3f const &  axis_origin,
Eigen::Vector3f const &  point,
Eigen::Vector3f &  directed_ortho_axis 
) [protected]

Given an axis (with origin axis_origin), return the orthogonal axis directed to point.

Note:
axis must be normalized.
Parameters:
[in]axisthe axis
[in]axis_originthe axis_origin
[in]pointthe point towards which the resulting axis is directed
[out]directed_ortho_axisthe directed orthogonal axis calculated

Definition at line 49 of file board.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
float pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::getAngleBetweenUnitVectors ( Eigen::Vector3f const &  v1,
Eigen::Vector3f const &  v2,
Eigen::Vector3f const &  axis 
) [protected]

return the angle (in radians) that rotate v1 to v2 with respect to axis .

Parameters:
[in]v1the first vector
[in]v2the second vector
[in]axisthe rotation axis. Axis must be normalized and orthogonal to plane defined by v1 and v2.
Returns:
angle

Definition at line 84 of file board.hpp.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
int pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::getCheckMarginArraySize ( ) const [inline]

Gets the number of slices in which is divided the margin for the search of missing regions.

Returns:
the number of margin slices.

Definition at line 180 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
bool pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::getFindHoles ( ) const [inline]

Gets whether holes in the margin of the support, for each point, are searched and accounted for in the estimation of the Reference Frame or not.

Returns:
The search for holes in the support is enabled/disabled.

Definition at line 125 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
float pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::getHoleSizeProbThresh ( ) const [inline]

Given the angle width of a hole in the support margin, gets the minimum percentage of a circumference this angle must cover to be considered a missing region in the support and hence used for the estimation of the Reference Frame.

Returns:
the minimum percentage of a circumference after which a hole is considered in the calculation

Definition at line 202 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
float pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::getMarginThresh ( ) const [inline]

Gets the percentage of the search radius (or tangent radius if set) after which a point is considered part of the support margin.

Returns:
The percentage of the search radius after which a point is considered a margin point.

Definition at line 145 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
float pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::getSteepThresh ( ) const [inline]

Gets the minimum steepness that the normals of the points situated on the borders of the hole, with reference to the normal of the best point found by the algorithm, must have in order to be considered in the calculation of the Reference Frame.

Returns:
threshold that defines if a missing region contains a point with the most different normal.

Definition at line 224 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
float pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::getTangentRadius ( ) const [inline]

Get the maximum distance of the points used to estimate the x_axis and y_axis of the BOARD Reference Frame for a given point.

Returns:
The search radius for x and y axes. If set to 0 the parameter given with setRadiusSearch is used.

Definition at line 103 of file board.h.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::normalDisambiguation ( pcl::PointCloud< PointNT > const &  normals_cloud,
std::vector< int > const &  normal_indices,
Eigen::Vector3f &  normal 
) [protected]

Disambiguates a normal direction using adjacent normals.

Parameters:
[in]normals_clouda cloud of normals used for the calculation
[in]normal_indicesthe indices of the normals in the cloud that should to be used for the calculation
[in,out]normalthe normal to disambiguate, the calculation is performed in place

Definition at line 172 of file board.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::planeFitting ( Eigen::Matrix< float, Eigen::Dynamic, 3 > const &  points,
Eigen::Vector3f &  center,
Eigen::Vector3f &  norm 
) [protected]

Compute Least Square Plane Fitting in a set of 3D points.

Parameters:
[in]pointsMatrix(nPoints,3) of 3D points coordinates
[out]centercentroid of the distribution of points that belongs to the fitted plane
[out]normnormal to the fitted plane

Definition at line 131 of file board.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::projectPointOnPlane ( Eigen::Vector3f const &  point,
Eigen::Vector3f const &  origin_point,
Eigen::Vector3f const &  plane_normal,
Eigen::Vector3f &  projected_point 
) [protected]

Given a plane (origin and normal) and a point, return the projection of x on plane.

Equivalent to vtkPlane::ProjectPoint()

Parameters:
[in]pointthe point to project
[in]origin_pointa point belonging to the plane
[in]plane_normalnormal of the plane
[out]projected_pointthe projection of the point on the plane

Definition at line 67 of file board.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::randomOrthogonalAxis ( Eigen::Vector3f const &  axis,
Eigen::Vector3f &  rand_ortho_axis 
) [protected]

Given an axis, return a random orthogonal axis.

Parameters:
[in]axisinput axis
[out]rand_ortho_axisan axis orthogonal to the input axis and whose direction is random

Definition at line 100 of file board.hpp.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::resetData ( ) [inline, protected]

Definition at line 243 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::setCheckMarginArraySize ( int  size) [inline]

Sets the number of slices in which is divided the margin for the search of missing regions.

Parameters:
[in]sizethe number of margin slices.

Definition at line 155 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::setFindHoles ( bool  find_holes) [inline]

Sets whether holes in the margin of the support, for each point, are searched and accounted for in the estimation of the Reference Frame or not.

Parameters:
[in]find_holesEnable/Disable the search for holes in the support.

Definition at line 114 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::setHoleSizeProbThresh ( float  prob_thresh) [inline]

Given the angle width of a hole in the support margin, sets the minimum percentage of a circumference this angle must cover to be considered a missing region in the support and hence used for the estimation of the Reference Frame.

Parameters:
[in]prob_threshthe minimum percentage of a circumference after which a hole is considered in the calculation

Definition at line 191 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::setMarginThresh ( float  margin_thresh) [inline]

Sets the percentage of the search radius (or tangent radius if set) after which a point is considered part of the support margin.

Parameters:
[in]margin_threshthe percentage of the search radius after which a point is considered a margin point.

Definition at line 135 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::setSteepThresh ( float  steep_thresh) [inline]

Sets the minimum steepness that the normals of the points situated on the borders of the hole, with reference to the normal of the best point found by the algorithm, must have in order to be considered in the calculation of the Reference Frame.

Parameters:
[in]steep_threshthreshold that defines if a missing region contains a point with the most different normal.

Definition at line 213 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
void pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::setTangentRadius ( float  radius) [inline]

Set the maximum distance of the points used to estimate the x_axis and y_axis of the BOARD Reference Frame for a given point.

Parameters:
[in]radiusThe search radius for x and y axes. If not set or set to 0 the parameter given with setRadiusSearch is used.

Definition at line 93 of file board.h.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
std::vector<bool> pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::check_margin_array_ [private]

Definition at line 357 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
int pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::check_margin_array_size_ [private]

Number of slices that divide the support in order to determine if a missing region is present.

Definition at line 349 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
bool pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::find_holes_ [private]

If true, check if support is complete or has missing regions because it is too near to mesh borders.

Definition at line 343 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
float pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::hole_size_prob_thresh_ [private]

Threshold used to determine a missing region.

Definition at line 352 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
std::vector<float> pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::margin_array_max_angle_ [private]

Definition at line 359 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
std::vector<float> pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::margin_array_max_angle_normal_ [private]

Definition at line 361 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
std::vector<float> pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::margin_array_min_angle_ [private]

Definition at line 358 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
std::vector<float> pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::margin_array_min_angle_normal_ [private]

Definition at line 360 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
float pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::margin_thresh_ [private]

Threshold that define if a support point is near the margins.

Definition at line 346 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
float pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::steep_thresh_ [private]

Threshold that defines if a missing region contains a point with the most different normal.

Definition at line 355 of file board.h.

template<typename PointInT, typename PointNT, typename PointOutT = ReferenceFrame>
float pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::tangent_radius_ [private]

Radius used to find tangent axis.

Definition at line 340 of file board.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:39:06