|
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Go to the documentation of this file.
39 #ifndef POINT_CLOUD_COMMON_TRANSFORMATION_ESTIMATION_SYMMETRIC_POINT_TO_PLANE_LLS_H_
40 #define POINT_CLOUD_COMMON_TRANSFORMATION_ESTIMATION_SYMMETRIC_POINT_TO_PLANE_LLS_H_
42 #include <pcl/registration/transformation_estimation.h>
43 #include <pcl/registration/warp_point_rigid.h>
44 #include <pcl/cloud_iterator.h>
49 namespace registration {
62 template <
typename Po
intSource,
typename Po
intTarget,
typename Scalar =
float>
64 :
public TransformationEstimation<PointSource, PointTarget, Scalar> {
66 using Ptr = boost::shared_ptr<TransformationEstimationSymmetricPointToPlaneLLS2<PointSource, PointTarget, Scalar> >;
68 boost::shared_ptr<const TransformationEstimationSymmetricPointToPlaneLLS2<PointSource, PointTarget, Scalar> >;
70 using Matrix4 =
typename TransformationEstimation<PointSource, PointTarget, Scalar>::Matrix4;
71 using Vector6 = Eigen::Matrix<Scalar, 6, 1>;
82 const pcl::PointCloud<PointTarget>& cloud_tgt,
83 Matrix4& transformation_matrix)
const override;
92 const std::vector<int>& indices_src,
93 const pcl::PointCloud<PointTarget>& cloud_tgt,
94 Matrix4& transformation_matrix)
const override;
104 const std::vector<int>& indices_src,
105 const pcl::PointCloud<PointTarget>& cloud_tgt,
106 const std::vector<int>& indices_tgt,
107 Matrix4& transformation_matrix)
const override;
116 const pcl::PointCloud<PointTarget>& cloud_tgt,
117 const pcl::Correspondences& correspondences,
118 Matrix4& transformation_matrix)
const override;
137 ConstCloudIterator<PointTarget>& target_it,
Matrix4& transformation_matrix)
const;
154 #endif // POINT_CLOUD_COMMON_TRANSFORMATION_ESTIMATION_SYMMETRIC_POINT_TO_PLANE_LLS_H_
Definition: correspondence_rejection_surface_normal2.h:45