Point Cloud Library (PCL)  1.14.1-dev
List of all members | 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. More...

#include <pcl/registration/correspondence_estimation_organized_projection.h>

+ Inheritance diagram for pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >:
+ Collaboration diagram for pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >:

Public Types

using PointCloudSource = pcl::PointCloud< PointSource >
 
using PointCloudSourcePtr = typename PointCloudSource::Ptr
 
using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr
 
using PointCloudTarget = pcl::PointCloud< PointTarget >
 
using PointCloudTargetPtr = typename PointCloudTarget::Ptr
 
using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr
 
using Ptr = shared_ptr< CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar > >
 
using ConstPtr = shared_ptr< const CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar > >
 
- Public Types inherited from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, float >
using Ptr = shared_ptr< CorrespondenceEstimationBase< PointSource, PointTarget, float > >
 
using ConstPtr = shared_ptr< const CorrespondenceEstimationBase< PointSource, PointTarget, float > >
 
using KdTree = pcl::search::KdTree< PointTarget >
 
using KdTreePtr = typename KdTree::Ptr
 
using KdTreeConstPtr = typename KdTree::ConstPtr
 
using KdTreeReciprocal = pcl::search::KdTree< PointSource >
 
using KdTreeReciprocalPtr = typename KdTreeReciprocal::Ptr
 
using KdTreeReciprocalConstPtr = typename KdTreeReciprocal::ConstPtr
 
using PointCloudSource = pcl::PointCloud< PointSource >
 
using PointCloudSourcePtr = typename PointCloudSource::Ptr
 
using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr
 
using PointCloudTarget = pcl::PointCloud< PointTarget >
 
using PointCloudTargetPtr = typename PointCloudTarget::Ptr
 
using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr
 
using PointRepresentationConstPtr = typename KdTree::PointRepresentationConstPtr
 
using PointRepresentationReciprocalConstPtr = typename KdTreeReciprocal::PointRepresentationConstPtr
 
- Public Types inherited from pcl::PCLBase< PointSource >
using PointCloud = pcl::PointCloud< PointSource >
 
using PointCloudPtr = typename PointCloud::Ptr
 
using PointCloudConstPtr = typename PointCloud::ConstPtr
 
using PointIndicesPtr = PointIndices::Ptr
 
using PointIndicesConstPtr = PointIndices::ConstPtr
 

Public Member Functions

 CorrespondenceEstimationOrganizedProjection ()
 Empty constructor that sets all the intrinsic calibration to the default Kinect values. More...
 
void setFocalLengths (const float fx, const float fy)
 Sets the focal length parameters of the target camera. More...
 
void getFocalLengths (float &fx, float &fy) const
 Reads back the focal length parameters of the target camera. More...
 
void setCameraCenters (const float cx, const float cy)
 Sets the camera center parameters of the target camera. More...
 
void getCameraCenters (float &cx, float &cy) const
 Reads back the camera center parameters of the target camera. More...
 
void setSourceTransformation (const Eigen::Matrix4f &src_to_tgt_transformation)
 Sets the transformation from the source point cloud to the target point cloud. More...
 
Eigen::Matrix4f getSourceTransformation () const
 Reads back the transformation from the source point cloud to the target point cloud. More...
 
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. More...
 
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. More...
 
void determineCorrespondences (Correspondences &correspondences, double max_distance)
 Computes the correspondences, applying a maximum Euclidean distance threshold. More...
 
void determineReciprocalCorrespondences (Correspondences &correspondences, double max_distance)
 Computes the correspondences, applying a maximum Euclidean distance threshold. More...
 
virtual CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::Ptr clone () const
 Clone and cast to CorrespondenceEstimationBase. More...
 
- Public Member Functions inherited from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, float >
 CorrespondenceEstimationBase ()
 Empty constructor. More...
 
 ~CorrespondenceEstimationBase () override=default
 Empty destructor. More...
 
void setInputSource (const PointCloudSourceConstPtr &cloud)
 Provide a pointer to the input source (e.g., the point cloud that we want to align to the target) More...
 
PointCloudSourceConstPtr const getInputSource ()
 Get a pointer to the input point cloud dataset target. More...
 
void setInputTarget (const PointCloudTargetConstPtr &cloud)
 Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to) More...
 
PointCloudTargetConstPtr const getInputTarget ()
 Get a pointer to the input point cloud dataset target. More...
 
void setNumberOfThreads (unsigned int nr_threads)
 Set the number of threads to use. More...
 
virtual bool requiresSourceNormals () const
 See if this rejector requires source normals. More...
 
virtual void setSourceNormals (pcl::PCLPointCloud2::ConstPtr)
 Abstract method for setting the source normals. More...
 
virtual bool requiresTargetNormals () const
 See if this rejector requires target normals. More...
 
virtual void setTargetNormals (pcl::PCLPointCloud2::ConstPtr)
 Abstract method for setting the target normals. More...
 
void setIndicesSource (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represent the input source point cloud. More...
 
IndicesPtr const getIndicesSource ()
 Get a pointer to the vector of indices used for the source dataset. More...
 
void setIndicesTarget (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represent the input target point cloud. More...
 
IndicesPtr const getIndicesTarget ()
 Get a pointer to the vector of indices used for the target dataset. More...
 
void setSearchMethodTarget (const KdTreePtr &tree, bool force_no_recompute=false)
 Provide a pointer to the search object used to find correspondences in the target cloud. More...
 
KdTreePtr getSearchMethodTarget () const
 Get a pointer to the search method used to find correspondences in the target cloud. More...
 
void setSearchMethodSource (const KdTreeReciprocalPtr &tree, bool force_no_recompute=false)
 Provide a pointer to the search object used to find correspondences in the source cloud (usually used by reciprocal correspondence finding). More...
 
KdTreeReciprocalPtr getSearchMethodSource () const
 Get a pointer to the search method used to find correspondences in the source cloud. More...
 
void setPointRepresentation (const PointRepresentationConstPtr &point_representation)
 Provide a boost shared pointer to the PointRepresentation for target cloud to be used when searching for nearest neighbors. More...
 
void setPointRepresentationReciprocal (const PointRepresentationReciprocalConstPtr &point_representation_reciprocal)
 Provide a boost shared pointer to the PointRepresentation for source cloud to be used when searching for nearest neighbors. More...
 
- Public Member Functions inherited from pcl::PCLBase< PointSource >
 PCLBase ()
 Empty constructor. More...
 
 PCLBase (const PCLBase &base)
 Copy constructor. More...
 
virtual ~PCLBase ()=default
 Destructor. More...
 
virtual void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset. More...
 
PointCloudConstPtr const getInputCloud () const
 Get a pointer to the input point cloud dataset. More...
 
virtual void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const IndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (std::size_t row_start, std::size_t col_start, std::size_t nb_rows, std::size_t nb_cols)
 Set the indices for the points laying within an interest region of the point cloud. More...
 
IndicesPtr getIndices ()
 Get a pointer to the vector of indices used. More...
 
IndicesConstPtr const getIndices () const
 Get a pointer to the vector of indices used. More...
 
const PointSource & operator[] (std::size_t pos) const
 Override PointCloud operator[] to shorten code. More...
 

Protected Member Functions

bool initCompute ()
 
- Protected Member Functions inherited from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, float >
const std::string & getClassName () const
 Abstract class get name method. More...
 
bool initCompute ()
 Internal computation initialization. More...
 
bool initComputeReciprocal ()
 Internal computation initialization for reciprocal correspondences. More...
 
- Protected Member Functions inherited from pcl::PCLBase< PointSource >
bool initCompute ()
 This method should get called before starting the actual computation. More...
 
bool deinitCompute ()
 This method should get called after finishing the actual computation. More...
 

Protected Attributes

float fx_ {525.f}
 
float fy_ {525.f}
 
float cx_ {319.5f}
 
float cy_ {239.5f}
 
Eigen::Matrix4f src_to_tgt_transformation_
 
float depth_threshold_
 
Eigen::Matrix3f projection_matrix_
 
- Protected Attributes inherited from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, float >
std::string corr_name_
 The correspondence estimation method name. More...
 
KdTreePtr tree_
 A pointer to the spatial search object used for the target dataset. More...
 
KdTreeReciprocalPtr tree_reciprocal_
 A pointer to the spatial search object used for the source dataset. More...
 
PointCloudTargetConstPtr target_
 The input point cloud dataset target. More...
 
IndicesPtr target_indices_
 The target point cloud dataset indices. More...
 
PointRepresentationConstPtr point_representation_
 The target point representation used (internal). More...
 
PointRepresentationReciprocalConstPtr point_representation_reciprocal_
 The source point representation used (internal). More...
 
PointCloudTargetPtr input_transformed_
 The transformed input source point cloud dataset. More...
 
std::vector< pcl::PCLPointFieldinput_fields_
 The types of input point fields available. More...
 
bool target_cloud_updated_
 Variable that stores whether we have a new target cloud, meaning we need to pre-process it again. More...
 
bool source_cloud_updated_
 Variable that stores whether we have a new source cloud, meaning we need to pre-process it again. More...
 
bool force_no_recompute_
 A flag which, if set, means the tree operating on the target cloud will never be recomputed. More...
 
bool force_no_recompute_reciprocal_
 A flag which, if set, means the tree operating on the source cloud will never be recomputed. More...
 
unsigned int num_threads_
 
- Protected Attributes inherited from pcl::PCLBase< PointSource >
PointCloudConstPtr input_
 The input point cloud dataset. More...
 
IndicesPtr indices_
 A pointer to the vector of point indices to use. More...
 
bool use_indices_
 Set to true if point indices are used. More...
 
bool fake_indices_
 If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More...
 

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 60 of file correspondence_estimation_organized_projection.h.

Member Typedef Documentation

◆ ConstPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::ConstPtr = shared_ptr<const CorrespondenceEstimationOrganizedProjection<PointSource, PointTarget, Scalar> >

◆ PointCloudSource

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudSource = pcl::PointCloud<PointSource>

◆ PointCloudSourceConstPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr

◆ PointCloudSourcePtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudSourcePtr = typename PointCloudSource::Ptr

◆ PointCloudTarget

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudTarget = pcl::PointCloud<PointTarget>

◆ PointCloudTargetConstPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr

◆ PointCloudTargetPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudTargetPtr = typename PointCloudTarget::Ptr

◆ Ptr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::Ptr = shared_ptr< CorrespondenceEstimationOrganizedProjection<PointSource, PointTarget, Scalar> >

Constructor & Destructor Documentation

◆ CorrespondenceEstimationOrganizedProjection()

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 92 of file correspondence_estimation_organized_projection.h.

Member Function Documentation

◆ clone()

template<typename PointSource , typename PointTarget , typename Scalar = float>
virtual CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::Ptr pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::clone ( ) const
inlinevirtual

◆ determineCorrespondences()

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
[out]correspondencesthe found correspondences (index of query point, index of target point, distance)
[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, float >.

Definition at line 77 of file correspondence_estimation_organized_projection.hpp.

References pcl::isFinite().

◆ determineReciprocalCorrespondences()

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
[out]correspondencesthe found correspondences (index of query and target point, distance)
[in]max_distanceEuclidean distance threshold above which correspondences will be rejected

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

Definition at line 122 of file correspondence_estimation_organized_projection.hpp.

◆ getCameraCenters()

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 136 of file correspondence_estimation_organized_projection.h.

References pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::cx_, and pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::cy_.

◆ getDepthThreshold()

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.

Returns
the depth threshold

Definition at line 180 of file correspondence_estimation_organized_projection.h.

References pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::depth_threshold_.

◆ getFocalLengths()

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 114 of file correspondence_estimation_organized_projection.h.

References pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::fx_, and pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::fy_.

◆ getSourceTransformation()

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.
Returns
the transformation

Definition at line 158 of file correspondence_estimation_organized_projection.h.

References pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::src_to_tgt_transformation_.

◆ initCompute()

template<typename PointSource , typename PointTarget , typename Scalar >
bool pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::initCompute
protected

Check if the target cloud is organized

Put the projection matrix together

Definition at line 50 of file correspondence_estimation_organized_projection.hpp.

◆ setCameraCenters()

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 125 of file correspondence_estimation_organized_projection.h.

References pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::cx_, and pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::cy_.

◆ setDepthThreshold()

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 169 of file correspondence_estimation_organized_projection.h.

References pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::depth_threshold_.

◆ setFocalLengths()

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.

References pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::fx_, and pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::fy_.

◆ setSourceTransformation()

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 148 of file correspondence_estimation_organized_projection.h.

References pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::src_to_tgt_transformation_.

Member Data Documentation

◆ cx_

template<typename PointSource , typename PointTarget , typename Scalar = float>
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::cx_ {319.5f}
protected

◆ cy_

template<typename PointSource , typename PointTarget , typename Scalar = float>
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::cy_ {239.5f}
protected

◆ depth_threshold_

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

◆ fx_

template<typename PointSource , typename PointTarget , typename Scalar = float>
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::fx_ {525.f}
protected

◆ fy_

template<typename PointSource , typename PointTarget , typename Scalar = float>
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::fy_ {525.f}
protected

◆ projection_matrix_

template<typename PointSource , typename PointTarget , typename Scalar = float>
Eigen::Matrix3f pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::projection_matrix_
protected

◆ src_to_tgt_transformation_

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: