Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::search::OrganizedNeighbor< PointT > Class Template Reference

OrganizedNeighbor is a class for optimized nearest neigbhor search in organized point clouds. More...

#include <organized.h>

Inheritance diagram for pcl::search::OrganizedNeighbor< PointT >:
Inheritance graph
[legend]

List of all members.

Classes

struct  Entry

Public Types

typedef boost::shared_ptr
< const
pcl::search::OrganizedNeighbor
< PointT > > 
ConstPtr
typedef boost::shared_ptr
< const std::vector< int > > 
IndicesConstPtr
typedef pcl::PointCloud< PointTPointCloud
typedef boost::shared_ptr
< const PointCloud
PointCloudConstPtr
typedef boost::shared_ptr
< PointCloud
PointCloudPtr
typedef boost::shared_ptr
< pcl::search::OrganizedNeighbor
< PointT > > 
Ptr

Public Member Functions

void computeCameraMatrix (Eigen::Matrix3f &camera_matrix) const
 Compute the camera matrix.
void estimateProjectionMatrix ()
 estimated the projection matrix from the input cloud.
bool isValid () const
 Test whether this search-object is valid (input is organized AND from projective device) User should use this method after setting the input cloud, since setInput just prints an error if input is not organized or a projection matrix could not be determined.
int nearestKSearch (const PointT &p_q, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) const
 Search for the k-nearest neighbors for a given query point.
 OrganizedNeighbor (bool sorted_results=false, float eps=1e-4f, unsigned pyramid_level=5)
 Constructor.
bool projectPoint (const PointT &p, pcl::PointXY &q) const
 projects a point into the image
int radiusSearch (const PointT &p_q, double radius, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const
 Search for all neighbors of query point that are within a given radius.
virtual void setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices=IndicesConstPtr())
 Provide a pointer to the input data set, if user has focal length he must set it before calling this.
virtual ~OrganizedNeighbor ()
 Empty deconstructor.

Protected Member Functions

void clipRange (int &begin, int &end, int min, int max) const
void getProjectedRadiusSearchBox (const PointT &point, float squared_radius, unsigned &minX, unsigned &minY, unsigned &maxX, unsigned &maxY) const
 Obtain a search box in 2D from a sphere with a radius in 3D.
template<typename MatrixType >
void makeSymmetric (MatrixType &matrix, bool use_upper_triangular=true) const
 copys upper or lower triangular part of the matrix to the other one
bool testPoint (const PointT &query, unsigned k, std::priority_queue< Entry > &queue, unsigned index) const
 test if point given by index is among the k NN in results to the query point.

Protected Attributes

const float eps_
 epsilon value for the MSE of the projection matrix estimation
Eigen::Matrix< float,
3, 3, Eigen::RowMajor > 
KR_
 inveser of the left 3x3 projection matrix which is K * R (with K being the camera matrix and R the rotation matrix)
Eigen::Matrix< float,
3, 3, Eigen::RowMajor > 
KR_KRT_
 inveser of the left 3x3 projection matrix which is K * R (with K being the camera matrix and R the rotation matrix)
std::vector< unsigned char > mask_
 mask, indicating whether the point was in the indices list or not.
Eigen::Matrix< float,
3, 4, Eigen::RowMajor > 
projection_matrix_
 the projection matrix. Either set by user or calculated by the first / each input cloud
const unsigned pyramid_level_
 using only a subsample of points to calculate the projection matrix. pyramid_level_ = use down sampled cloud given by pyramid_level_

Detailed Description

template<typename PointT>
class pcl::search::OrganizedNeighbor< PointT >

OrganizedNeighbor is a class for optimized nearest neigbhor search in organized point clouds.

Author:
Radu B. Rusu, Julius Kammerl, Suat Gedikli, Koen Buys

Definition at line 61 of file organized.h.


Member Typedef Documentation

template<typename PointT>
typedef boost::shared_ptr<const pcl::search::OrganizedNeighbor<PointT> > pcl::search::OrganizedNeighbor< PointT >::ConstPtr

Reimplemented from pcl::search::Search< PointT >.

Definition at line 73 of file organized.h.

template<typename PointT>
typedef boost::shared_ptr<const std::vector<int> > pcl::search::OrganizedNeighbor< PointT >::IndicesConstPtr

Reimplemented from pcl::search::Search< PointT >.

Definition at line 70 of file organized.h.

template<typename PointT>
typedef pcl::PointCloud<PointT> pcl::search::OrganizedNeighbor< PointT >::PointCloud

Reimplemented from pcl::search::Search< PointT >.

Definition at line 66 of file organized.h.

template<typename PointT>
typedef boost::shared_ptr<const PointCloud> pcl::search::OrganizedNeighbor< PointT >::PointCloudConstPtr

Reimplemented from pcl::search::Search< PointT >.

Definition at line 69 of file organized.h.

template<typename PointT>
typedef boost::shared_ptr<PointCloud> pcl::search::OrganizedNeighbor< PointT >::PointCloudPtr

Reimplemented from pcl::search::Search< PointT >.

Definition at line 67 of file organized.h.

template<typename PointT>
typedef boost::shared_ptr<pcl::search::OrganizedNeighbor<PointT> > pcl::search::OrganizedNeighbor< PointT >::Ptr

Reimplemented from pcl::search::Search< PointT >.

Definition at line 72 of file organized.h.


Constructor & Destructor Documentation

template<typename PointT>
pcl::search::OrganizedNeighbor< PointT >::OrganizedNeighbor ( bool  sorted_results = false,
float  eps = 1e-4f,
unsigned  pyramid_level = 5 
) [inline]

Constructor.

Parameters:
[in]sorted_resultswhether the results should be return sorted in ascending order on the distances or not. This applies only for radius search, since knn always returns sorted resutls
[in]epsthe threshold for the mean-squared-error of the estimation of the projection matrix. if the MSE is above this value, the point cloud is considered as not from a projective device, thus organized neighbor search can not be applied on that cloud.
[in]pyramid_levelthe level of the down sampled point cloud to be used for projection matrix estimation

Definition at line 87 of file organized.h.

template<typename PointT>
virtual pcl::search::OrganizedNeighbor< PointT >::~OrganizedNeighbor ( ) [inline, virtual]

Empty deconstructor.

Definition at line 99 of file organized.h.


Member Function Documentation

template<typename PointT>
void pcl::search::OrganizedNeighbor< PointT >::clipRange ( int &  begin,
int &  end,
int  min,
int  max 
) const [inline, protected]

Definition at line 234 of file organized.h.

template<typename PointT >
void pcl::search::OrganizedNeighbor< PointT >::computeCameraMatrix ( Eigen::Matrix3f &  camera_matrix) const

Compute the camera matrix.

Parameters:
[out]camera_matrixthe resultant computed camera matrix

Definition at line 345 of file organized.hpp.

template<typename PointT >
void pcl::search::OrganizedNeighbor< PointT >::estimateProjectionMatrix ( )

estimated the projection matrix from the input cloud.

Definition at line 372 of file organized.hpp.

template<typename PointT >
void pcl::search::OrganizedNeighbor< PointT >::getProjectedRadiusSearchBox ( const PointT point,
float  squared_radius,
unsigned &  minX,
unsigned &  minY,
unsigned &  maxX,
unsigned &  maxY 
) const [protected]

Obtain a search box in 2D from a sphere with a radius in 3D.

Parameters:
[in]pointthe query point (sphere center)
[in]squared_radiusthe squared sphere radius
[out]minXthe min X box coordinate
[out]minYthe min Y box coordinate
[out]maxXthe max X box coordinate
[out]maxYthe max Y box coordinate

Definition at line 267 of file organized.hpp.

template<typename PointT>
bool pcl::search::OrganizedNeighbor< PointT >::isValid ( ) const [inline]

Test whether this search-object is valid (input is organized AND from projective device) User should use this method after setting the input cloud, since setInput just prints an error if input is not organized or a projection matrix could not be determined.

Returns:
true if the input data is organized and from a projective device, false otherwise

Definition at line 107 of file organized.h.

template<typename PointT >
template<typename MatrixType >
void pcl::search::OrganizedNeighbor< PointT >::makeSymmetric ( MatrixType &  matrix,
bool  use_upper_triangular = true 
) const [protected]

copys upper or lower triangular part of the matrix to the other one

Definition at line 321 of file organized.hpp.

template<typename PointT >
int pcl::search::OrganizedNeighbor< PointT >::nearestKSearch ( const PointT p_q,
int  k,
std::vector< int > &  k_indices,
std::vector< float > &  k_sqr_distances 
) const [virtual]

Search for the k-nearest neighbors for a given query point.

Note:
limiting the maximum search radius (with setMaxDistance) can lead to a significant improvement in search speed
Parameters:
[in]p_qthe given query point (setInputCloud must be given a-priori!)
[in]kthe number of neighbors to search for (used only if horizontal and vertical window not given already!)
[out]k_indicesthe resultant point indices (must be resized to k beforehand!)
[out]k_sqr_distances
Note:
this function does not return distances
Returns:
number of neighbors found
Todo:
still need to implements this functionality

Implements pcl::search::Search< PointT >.

Definition at line 113 of file organized.hpp.

template<typename PointT >
bool pcl::search::OrganizedNeighbor< PointT >::projectPoint ( const PointT p,
pcl::PointXY q 
) const

projects a point into the image

Parameters:
[in]ppoint in 3D World Coordinate Frame to be projected onto the image plane
[out]qthe 2D projected point in pixel coordinates (u,v)
Returns:
true if projection is valid, false otherwise

Definition at line 517 of file organized.hpp.

template<typename PointT >
int pcl::search::OrganizedNeighbor< PointT >::radiusSearch ( const PointT p_q,
double  radius,
std::vector< int > &  k_indices,
std::vector< float > &  k_sqr_distances,
unsigned int  max_nn = 0 
) const [virtual]

Search for all neighbors of query point that are within a given radius.

Parameters:
[in]p_qthe given query point
[in]radiusthe radius of the sphere bounding all of p_q's neighbors
[out]k_indicesthe resultant indices of the neighboring points
[out]k_sqr_distancesthe resultant squared distances to the neighboring points
[in]max_nnif given, bounds the maximum returned neighbors to this value. If max_nn is set to 0 or to a number higher than the number of points in the input cloud, all neighbors in radius will be returned.
Returns:
number of neighbors found in radius

Implements pcl::search::Search< PointT >.

Definition at line 50 of file organized.hpp.

template<typename PointT>
virtual void pcl::search::OrganizedNeighbor< PointT >::setInputCloud ( const PointCloudConstPtr cloud,
const IndicesConstPtr indices = IndicesConstPtr () 
) [inline, virtual]

Provide a pointer to the input data set, if user has focal length he must set it before calling this.

Parameters:
[in]cloudthe const boost shared pointer to a PointCloud message
[in]indicesthe const boost shared pointer to PointIndices

Definition at line 128 of file organized.h.

template<typename PointT>
bool pcl::search::OrganizedNeighbor< PointT >::testPoint ( const PointT query,
unsigned  k,
std::priority_queue< Entry > &  queue,
unsigned  index 
) const [inline, protected]

test if point given by index is among the k NN in results to the query point.

Parameters:
[in]queryquery point
[in]knumber of maximum nn interested in
[in]queuepriority queue with k NN
[in]indexindex on point to be tested
Returns:
wheter the top element changed or not.

Definition at line 215 of file organized.h.


Member Data Documentation

template<typename PointT>
const float pcl::search::OrganizedNeighbor< PointT >::eps_ [protected]

epsilon value for the MSE of the projection matrix estimation

Definition at line 267 of file organized.h.

template<typename PointT>
Eigen::Matrix<float, 3, 3, Eigen::RowMajor> pcl::search::OrganizedNeighbor< PointT >::KR_ [protected]

inveser of the left 3x3 projection matrix which is K * R (with K being the camera matrix and R the rotation matrix)

Definition at line 261 of file organized.h.

template<typename PointT>
Eigen::Matrix<float, 3, 3, Eigen::RowMajor> pcl::search::OrganizedNeighbor< PointT >::KR_KRT_ [protected]

inveser of the left 3x3 projection matrix which is K * R (with K being the camera matrix and R the rotation matrix)

Definition at line 264 of file organized.h.

template<typename PointT>
std::vector<unsigned char> pcl::search::OrganizedNeighbor< PointT >::mask_ [protected]

mask, indicating whether the point was in the indices list or not.

Definition at line 273 of file organized.h.

template<typename PointT>
Eigen::Matrix<float, 3, 4, Eigen::RowMajor> pcl::search::OrganizedNeighbor< PointT >::projection_matrix_ [protected]

the projection matrix. Either set by user or calculated by the first / each input cloud

Definition at line 258 of file organized.h.

template<typename PointT>
const unsigned pcl::search::OrganizedNeighbor< PointT >::pyramid_level_ [protected]

using only a subsample of points to calculate the projection matrix. pyramid_level_ = use down sampled cloud given by pyramid_level_

Definition at line 270 of file organized.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:24