#include <boost/function.hpp>
#include <boost/bind.hpp>
#include <pcl/pcl_base.h>
#include "pcl/kdtree/kdtree.h"
#include "pcl/kdtree/kdtree_flann.h"
#include "pcl/registration/transforms.h"
#include <Eigen/SVD>
#include "pcl/win32_macros.h"
#include "pcl/registration/registration.hpp"
Go to the source code of this file.
Classes | |
class | pcl::Registration< PointSource, PointTarget >::FeatureContainer< FeatureType > |
An inner class containing pointers to the source and target feature clouds along with the KdTree and the parameters needed to perform the correspondence search. This class extends FeatureContainerInterface, which contains abstract methods for any methods that do not depend on the FeatureType --- these methods can thus be called from a pointer to FeatureContainerInterface without casting to the derived class. More... | |
class | pcl::Registration< PointSource, PointTarget >::FeatureContainerInterface |
class | pcl::Registration< PointSource, PointTarget > |
Registration represents the base registration class. All 3D registration methods should inherit from this class. More... | |
Namespaces | |
namespace | pcl |
Functions | |
template<typename PointSource , typename PointTarget > | |
void | pcl::estimateRigidTransformationSVD (const pcl::PointCloud< PointSource > &cloud_src, const std::vector< int > &indices_src, const pcl::PointCloud< PointTarget > &cloud_tgt, const std::vector< int > &indices_tgt, Eigen::Matrix4f &transformation_matrix) |
Estimate a rigid rotation transformation between a source and a target point cloud using SVD. | |
template<typename PointSource , typename PointTarget > | |
void | pcl::estimateRigidTransformationSVD (const pcl::PointCloud< PointSource > &cloud_src, const std::vector< int > &indices_src, const pcl::PointCloud< PointTarget > &cloud_tgt, Eigen::Matrix4f &transformation_matrix) |
Estimate a rigid rotation transformation between a source and a target point cloud using SVD. | |
template<typename PointSource , typename PointTarget > | |
void | pcl::estimateRigidTransformationSVD (const pcl::PointCloud< PointSource > &cloud_src, const pcl::PointCloud< PointTarget > &cloud_tgt, Eigen::Matrix4f &transformation_matrix) |
Estimate a rigid rotation transformation between a source and a target point cloud using SVD. |