00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_2D_HPP_
00038 #define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_2D_HPP_
00039
00041 template <typename PointSource, typename PointTarget, typename Scalar> inline void
00042 pcl::registration::TransformationEstimation2D<PointSource, PointTarget, Scalar>::estimateRigidTransformation (
00043 const pcl::PointCloud<PointSource> &cloud_src,
00044 const pcl::PointCloud<PointTarget> &cloud_tgt,
00045 Matrix4 &transformation_matrix) const
00046 {
00047 size_t nr_points = cloud_src.points.size ();
00048 if (cloud_tgt.points.size () != nr_points)
00049 {
00050 PCL_ERROR ("[pcl::TransformationEstimation2D::estimateRigidTransformation] Number or points in source (%zu) differs than target (%zu)!\n", nr_points, cloud_tgt.points.size ());
00051 return;
00052 }
00053
00054 ConstCloudIterator<PointSource> source_it (cloud_src);
00055 ConstCloudIterator<PointTarget> target_it (cloud_tgt);
00056 estimateRigidTransformation (source_it, target_it, transformation_matrix);
00057 }
00058
00060 template <typename PointSource, typename PointTarget, typename Scalar> void
00061 pcl::registration::TransformationEstimation2D<PointSource, PointTarget, Scalar>::estimateRigidTransformation (
00062 const pcl::PointCloud<PointSource> &cloud_src,
00063 const std::vector<int> &indices_src,
00064 const pcl::PointCloud<PointTarget> &cloud_tgt,
00065 Matrix4 &transformation_matrix) const
00066 {
00067 if (indices_src.size () != cloud_tgt.points.size ())
00068 {
00069 PCL_ERROR ("[pcl::Transformation2D::estimateRigidTransformation] Number or points in source (%zu) differs than target (%zu)!\n", indices_src.size (), cloud_tgt.points.size ());
00070 return;
00071 }
00072
00073 ConstCloudIterator<PointSource> source_it (cloud_src, indices_src);
00074 ConstCloudIterator<PointTarget> target_it (cloud_tgt);
00075 estimateRigidTransformation (source_it, target_it, transformation_matrix);
00076 }
00077
00078
00080 template <typename PointSource, typename PointTarget, typename Scalar> inline void
00081 pcl::registration::TransformationEstimation2D<PointSource, PointTarget, Scalar>::estimateRigidTransformation (
00082 const pcl::PointCloud<PointSource> &cloud_src,
00083 const std::vector<int> &indices_src,
00084 const pcl::PointCloud<PointTarget> &cloud_tgt,
00085 const std::vector<int> &indices_tgt,
00086 Matrix4 &transformation_matrix) const
00087 {
00088 if (indices_src.size () != indices_tgt.size ())
00089 {
00090 PCL_ERROR ("[pcl::TransformationEstimation2D::estimateRigidTransformation] Number or points in source (%zu) differs than target (%zu)!\n", indices_src.size (), indices_tgt.size ());
00091 return;
00092 }
00093
00094 ConstCloudIterator<PointSource> source_it (cloud_src, indices_src);
00095 ConstCloudIterator<PointTarget> target_it (cloud_tgt, indices_tgt);
00096 estimateRigidTransformation (source_it, target_it, transformation_matrix);
00097 }
00098
00100 template <typename PointSource, typename PointTarget, typename Scalar> void
00101 pcl::registration::TransformationEstimation2D<PointSource, PointTarget, Scalar>::estimateRigidTransformation (
00102 const pcl::PointCloud<PointSource> &cloud_src,
00103 const pcl::PointCloud<PointTarget> &cloud_tgt,
00104 const pcl::Correspondences &correspondences,
00105 Matrix4 &transformation_matrix) const
00106 {
00107 ConstCloudIterator<PointSource> source_it (cloud_src, correspondences, true);
00108 ConstCloudIterator<PointTarget> target_it (cloud_tgt, correspondences, false);
00109 estimateRigidTransformation (source_it, target_it, transformation_matrix);
00110 }
00111
00113 template <typename PointSource, typename PointTarget, typename Scalar> inline void
00114 pcl::registration::TransformationEstimation2D<PointSource, PointTarget, Scalar>::estimateRigidTransformation (
00115 ConstCloudIterator<PointSource>& source_it,
00116 ConstCloudIterator<PointTarget>& target_it,
00117 Matrix4 &transformation_matrix) const
00118 {
00119 source_it.reset (); target_it.reset ();
00120
00121 Eigen::Matrix<Scalar, 4, 1> centroid_src, centroid_tgt;
00122
00123 compute3DCentroid (source_it, centroid_src);
00124 compute3DCentroid (target_it, centroid_tgt);
00125 source_it.reset (); target_it.reset ();
00126
00127
00128 centroid_src[2] = 0.0f;
00129 centroid_tgt[2] = 0.0f;
00130
00131 Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> cloud_src_demean, cloud_tgt_demean;
00132 demeanPointCloud (source_it, centroid_src, cloud_src_demean);
00133 demeanPointCloud (target_it, centroid_tgt, cloud_tgt_demean);
00134
00135 getTransformationFromCorrelation (cloud_src_demean, centroid_src, cloud_tgt_demean, centroid_tgt, transformation_matrix);
00136 }
00137
00139 template <typename PointSource, typename PointTarget, typename Scalar> void
00140 pcl::registration::TransformationEstimation2D<PointSource, PointTarget, Scalar>::getTransformationFromCorrelation (
00141 const Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> &cloud_src_demean,
00142 const Eigen::Matrix<Scalar, 4, 1> ¢roid_src,
00143 const Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> &cloud_tgt_demean,
00144 const Eigen::Matrix<Scalar, 4, 1> ¢roid_tgt,
00145 Matrix4 &transformation_matrix) const
00146 {
00147 transformation_matrix.setIdentity ();
00148
00149
00150 Eigen::Matrix<Scalar, 3, 3> H = (cloud_src_demean * cloud_tgt_demean.transpose ()).topLeftCorner (3, 3);
00151
00152 float angle = atan2 ((H (0, 1) - H (1, 0)), (H(0, 0) + H (1, 1)));
00153
00154 Eigen::Matrix<Scalar, 3, 3> R (Eigen::Matrix<Scalar, 3, 3>::Identity ());
00155 R (0, 0) = R (1, 1) = cos (angle);
00156 R (0, 1) = -sin (angle);
00157 R (1, 0) = sin (angle);
00158
00159
00160 transformation_matrix.topLeftCorner (3, 3).matrix () = R;
00161 const Eigen::Matrix<Scalar, 3, 1> Rc (R * centroid_src.head (3).matrix ());
00162 transformation_matrix.block (0, 3, 3, 1).matrix () = centroid_tgt.head (3) - Rc;
00163 }
00164
00165 #endif // PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_2D_HPP_