Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar > Class Template Reference

CorrespondenceEstimationOrganizedProjection computes correspondences by projecting the source point cloud onto the target point cloud using the camera intrinsic and extrinsic parameters. The correspondences can be trimmed by a depth threshold and by a distance threshold. It is not as precise as a nearest neighbor search, but it is much faster, as it avoids the usage of any additional structures (i.e., kd-trees). More...

#include <correspondence_estimation_organized_projection.h>

Inheritance diagram for pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const
CorrespondenceEstimationOrganizedProjection
< PointSource, PointTarget,
Scalar > > 
ConstPtr
typedef pcl::PointCloud
< PointSource > 
PointCloudSource
typedef PointCloudSource::ConstPtr PointCloudSourceConstPtr
typedef PointCloudSource::Ptr PointCloudSourcePtr
typedef pcl::PointCloud
< PointTarget > 
PointCloudTarget
typedef PointCloudTarget::ConstPtr PointCloudTargetConstPtr
typedef PointCloudTarget::Ptr PointCloudTargetPtr
typedef boost::shared_ptr
< CorrespondenceEstimationOrganizedProjection
< PointSource, PointTarget,
Scalar > > 
Ptr

Public Member Functions

 CorrespondenceEstimationOrganizedProjection ()
 Empty constructor that sets all the intrinsic calibration to the default Kinect values.
void determineCorrespondences (Correspondences &correspondences, double max_distance)
 Computes the correspondences, applying a maximum Euclidean distance threshold.
void determineReciprocalCorrespondences (Correspondences &correspondences, double max_distance)
 Computes the correspondences, applying a maximum Euclidean distance threshold.
void getCameraCenters (float &cx, float &cy) const
 Reads back the camera center parameters of the target camera.
float getDepthThreshold () const
 Reads back the depth threshold; after projecting the source points in the image space of the target camera, this threshold is applied on the depths of corresponding dexels to eliminate the ones that are too far from each other.
void getFocalLengths (float &fx, float &fy) const
 Reads back the focal length parameters of the target camera.
Eigen::Matrix4f getSourceTransformation () const
 Reads back the transformation from the source point cloud to the target point cloud.
void setCameraCenters (const float cx, const float cy)
 Sets the camera center parameters of the target camera.
void setDepthThreshold (const float depth_threshold)
 Sets the depth threshold; after projecting the source points in the image space of the target camera, this threshold is applied on the depths of corresponding dexels to eliminate the ones that are too far from each other.
void setFocalLengths (const float fx, const float fy)
 Sets the focal length parameters of the target camera.
void setSourceTransformation (const Eigen::Matrix4f &src_to_tgt_transformation)
 Sets the transformation from the source point cloud to the target point cloud.

Protected Member Functions

bool initCompute ()
 Internal computation initalization.

Protected Attributes

float cx_
float cy_
float depth_threshold_
float fx_
float fy_
Eigen::Matrix3f projection_matrix_
Eigen::Matrix4f src_to_tgt_transformation_

Detailed Description

template<typename PointSource, typename PointTarget, typename Scalar = float>
class pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >

CorrespondenceEstimationOrganizedProjection computes correspondences by projecting the source point cloud onto the target point cloud using the camera intrinsic and extrinsic parameters. The correspondences can be trimmed by a depth threshold and by a distance threshold. It is not as precise as a nearest neighbor search, but it is much faster, as it avoids the usage of any additional structures (i.e., kd-trees).

Note:
The target point cloud must be organized (no restrictions on the source) and the target point cloud must be given in the camera coordinate frame. Any other transformation is specified by the src_to_tgt_transformation_ variable.
Author:
Alex Ichim

Definition at line 61 of file correspondence_estimation_organized_projection.h.


Member Typedef Documentation

template<typename PointSource , typename PointTarget , typename Scalar = float>
typedef boost::shared_ptr< const CorrespondenceEstimationOrganizedProjection<PointSource, PointTarget, Scalar> > pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::ConstPtr
template<typename PointSource , typename PointTarget , typename Scalar = float>
typedef pcl::PointCloud<PointSource> pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudSource
template<typename PointSource , typename PointTarget , typename Scalar = float>
typedef PointCloudSource::ConstPtr pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudSourceConstPtr
template<typename PointSource , typename PointTarget , typename Scalar = float>
typedef PointCloudSource::Ptr pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudSourcePtr
template<typename PointSource , typename PointTarget , typename Scalar = float>
typedef pcl::PointCloud<PointTarget> pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudTarget
template<typename PointSource , typename PointTarget , typename Scalar = float>
typedef PointCloudTarget::ConstPtr pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudTargetConstPtr
template<typename PointSource , typename PointTarget , typename Scalar = float>
typedef PointCloudTarget::Ptr pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudTargetPtr
template<typename PointSource , typename PointTarget , typename Scalar = float>
typedef boost::shared_ptr< CorrespondenceEstimationOrganizedProjection<PointSource, PointTarget, Scalar> > pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::Ptr

Constructor & Destructor Documentation

template<typename PointSource , typename PointTarget , typename Scalar = float>
pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::CorrespondenceEstimationOrganizedProjection ( ) [inline]

Empty constructor that sets all the intrinsic calibration to the default Kinect values.

Definition at line 87 of file correspondence_estimation_organized_projection.h.


Member Function Documentation

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::determineCorrespondences ( pcl::Correspondences correspondences,
double  max_distance 
) [virtual]

Computes the correspondences, applying a maximum Euclidean distance threshold.

Parameters:
[in]max_distanceEuclidean distance threshold above which correspondences will be rejected

Check if the point was behind the camera

Check if the depth difference is larger than the threshold

Implements pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.

Definition at line 71 of file correspondence_estimation_organized_projection.hpp.

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::determineReciprocalCorrespondences ( pcl::Correspondences correspondences,
double  max_distance 
) [virtual]

Computes the correspondences, applying a maximum Euclidean distance threshold.

Parameters:
[in]max_distanceEuclidean distance threshold above which correspondences will be rejected

Implements pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.

Definition at line 118 of file correspondence_estimation_organized_projection.hpp.

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::getCameraCenters ( float &  cx,
float &  cy 
) const [inline]

Reads back the camera center parameters of the target camera.

Parameters:
[out]cxthe x-coordinate of the camera center
[out]cythe y-coordinate of the camera center

Definition at line 128 of file correspondence_estimation_organized_projection.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::getDepthThreshold ( ) const [inline]

Reads back the depth threshold; after projecting the source points in the image space of the target camera, this threshold is applied on the depths of corresponding dexels to eliminate the ones that are too far from each other.

Parameters:
[out]depth_thresholdthe depth threshold

Definition at line 164 of file correspondence_estimation_organized_projection.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::getFocalLengths ( float &  fx,
float &  fy 
) const [inline]

Reads back the focal length parameters of the target camera.

Parameters:
[out]fxthe focal length in pixels along the x-axis of the image
[out]fythe focal length in pixels along the y-axis of the image

Definition at line 111 of file correspondence_estimation_organized_projection.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
Eigen::Matrix4f pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::getSourceTransformation ( ) const [inline]

Reads back the transformation from the source point cloud to the target point cloud.

Note:
The target point cloud must be in its local camera coordinates, so use this transformation to correct for that.
Parameters:
[out]src_to_tgt_transformationthe transformation

Definition at line 146 of file correspondence_estimation_organized_projection.h.

template<typename PointSource , typename PointTarget , typename Scalar >
bool pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::initCompute ( ) [protected]

Internal computation initalization.

Check if the target cloud is organized

Put the projection matrix together

Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.

Definition at line 46 of file correspondence_estimation_organized_projection.hpp.

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::setCameraCenters ( const float  cx,
const float  cy 
) [inline]

Sets the camera center parameters of the target camera.

Parameters:
[in]cxthe x-coordinate of the camera center
[in]cythe y-coordinate of the camera center

Definition at line 120 of file correspondence_estimation_organized_projection.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::setDepthThreshold ( const float  depth_threshold) [inline]

Sets the depth threshold; after projecting the source points in the image space of the target camera, this threshold is applied on the depths of corresponding dexels to eliminate the ones that are too far from each other.

Parameters:
[in]depth_thresholdthe depth threshold

Definition at line 155 of file correspondence_estimation_organized_projection.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::setFocalLengths ( const float  fx,
const float  fy 
) [inline]

Sets the focal length parameters of the target camera.

Parameters:
[in]fxthe focal length in pixels along the x-axis of the image
[in]fythe focal length in pixels along the y-axis of the image

Definition at line 103 of file correspondence_estimation_organized_projection.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::setSourceTransformation ( const Eigen::Matrix4f &  src_to_tgt_transformation) [inline]

Sets the transformation from the source point cloud to the target point cloud.

Note:
The target point cloud must be in its local camera coordinates, so use this transformation to correct for that.
Parameters:
[in]src_to_tgt_transformationthe transformation

Definition at line 137 of file correspondence_estimation_organized_projection.h.


Member Data Documentation

template<typename PointSource , typename PointTarget , typename Scalar = float>
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::cx_ [protected]
template<typename PointSource , typename PointTarget , typename Scalar = float>
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::cy_ [protected]
template<typename PointSource , typename PointTarget , typename Scalar = float>
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::depth_threshold_ [protected]
template<typename PointSource , typename PointTarget , typename Scalar = float>
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::fx_ [protected]
template<typename PointSource , typename PointTarget , typename Scalar = float>
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::fy_ [protected]
template<typename PointSource , typename PointTarget , typename Scalar = float>
Eigen::Matrix3f pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::projection_matrix_ [protected]
template<typename PointSource , typename PointTarget , typename Scalar = float>
Eigen::Matrix4f pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::src_to_tgt_transformation_ [protected]

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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:45:03