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>
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_ |
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).
Definition at line 61 of file correspondence_estimation_organized_projection.h.
typedef boost::shared_ptr< const CorrespondenceEstimationOrganizedProjection<PointSource, PointTarget, Scalar> > pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::ConstPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 82 of file correspondence_estimation_organized_projection.h.
typedef pcl::PointCloud<PointSource> pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudSource |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 73 of file correspondence_estimation_organized_projection.h.
typedef PointCloudSource::ConstPtr pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudSourceConstPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 75 of file correspondence_estimation_organized_projection.h.
typedef PointCloudSource::Ptr pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudSourcePtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 74 of file correspondence_estimation_organized_projection.h.
typedef pcl::PointCloud<PointTarget> pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudTarget |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 77 of file correspondence_estimation_organized_projection.h.
typedef PointCloudTarget::ConstPtr pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudTargetConstPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 79 of file correspondence_estimation_organized_projection.h.
typedef PointCloudTarget::Ptr pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::PointCloudTargetPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 78 of file correspondence_estimation_organized_projection.h.
typedef boost::shared_ptr< CorrespondenceEstimationOrganizedProjection<PointSource, PointTarget, Scalar> > pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::Ptr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 81 of file correspondence_estimation_organized_projection.h.
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.
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::determineCorrespondences | ( | pcl::Correspondences & | correspondences, |
double | max_distance | ||
) | [virtual] |
Computes the correspondences, applying a maximum Euclidean distance threshold.
[in] | max_distance | Euclidean 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.
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::determineReciprocalCorrespondences | ( | pcl::Correspondences & | correspondences, |
double | max_distance | ||
) | [virtual] |
Computes the correspondences, applying a maximum Euclidean distance threshold.
[in] | max_distance | Euclidean 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.
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::getCameraCenters | ( | float & | cx, |
float & | cy | ||
) | const [inline] |
Reads back the camera center parameters of the target camera.
[out] | cx | the x-coordinate of the camera center |
[out] | cy | the y-coordinate of the camera center |
Definition at line 128 of file correspondence_estimation_organized_projection.h.
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.
[out] | depth_threshold | the depth threshold |
Definition at line 164 of file correspondence_estimation_organized_projection.h.
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::getFocalLengths | ( | float & | fx, |
float & | fy | ||
) | const [inline] |
Reads back the focal length parameters of the target camera.
[out] | fx | the focal length in pixels along the x-axis of the image |
[out] | fy | the focal length in pixels along the y-axis of the image |
Definition at line 111 of file correspondence_estimation_organized_projection.h.
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.
[out] | src_to_tgt_transformation | the transformation |
Definition at line 146 of file correspondence_estimation_organized_projection.h.
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.
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::setCameraCenters | ( | const float | cx, |
const float | cy | ||
) | [inline] |
Sets the camera center parameters of the target camera.
[in] | cx | the x-coordinate of the camera center |
[in] | cy | the y-coordinate of the camera center |
Definition at line 120 of file correspondence_estimation_organized_projection.h.
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.
[in] | depth_threshold | the depth threshold |
Definition at line 155 of file correspondence_estimation_organized_projection.h.
void pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::setFocalLengths | ( | const float | fx, |
const float | fy | ||
) | [inline] |
Sets the focal length parameters of the target camera.
[in] | fx | the focal length in pixels along the x-axis of the image |
[in] | fy | the focal length in pixels along the y-axis of the image |
Definition at line 103 of file correspondence_estimation_organized_projection.h.
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.
[in] | src_to_tgt_transformation | the transformation |
Definition at line 137 of file correspondence_estimation_organized_projection.h.
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::cx_ [protected] |
Definition at line 186 of file correspondence_estimation_organized_projection.h.
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::cy_ [protected] |
Definition at line 186 of file correspondence_estimation_organized_projection.h.
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::depth_threshold_ [protected] |
Definition at line 188 of file correspondence_estimation_organized_projection.h.
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::fx_ [protected] |
Definition at line 185 of file correspondence_estimation_organized_projection.h.
float pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::fy_ [protected] |
Definition at line 185 of file correspondence_estimation_organized_projection.h.
Eigen::Matrix3f pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::projection_matrix_ [protected] |
Definition at line 190 of file correspondence_estimation_organized_projection.h.
Eigen::Matrix4f pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::src_to_tgt_transformation_ [protected] |
Definition at line 187 of file correspondence_estimation_organized_projection.h.