#include <pcl/point_cloud.h>#include <pcl/point_types.h>#include <Eigen/Core>#include <Eigen/Geometry>#include "pcl/registration/transforms.hpp"

Go to the source code of this file.
Namespaces | |
| namespace | pcl |
Functions | |
| template<typename PointT > | |
| void | pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< int > &indices, const Eigen::Vector4f ¢roid, Eigen::MatrixXf &cloud_out) |
| Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix. | |
| template<typename PointT > | |
| void | pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Eigen::Vector4f ¢roid, Eigen::MatrixXf &cloud_out) |
| Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix. | |
| template<typename PointT > | |
| void | pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< int > &indices, const Eigen::Vector4f ¢roid, pcl::PointCloud< PointT > &cloud_out) |
| Subtract a centroid from a point cloud and return the de-meaned representation. | |
| template<typename PointT > | |
| void | pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Eigen::Vector4f ¢roid, pcl::PointCloud< PointT > &cloud_out) |
| Subtract a centroid from a point cloud and return the de-meaned representation. | |
| template<typename PointT > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Vector3f &offset, const Eigen::Quaternionf &rotation) |
| Apply a rigid transform defined by a 3D offset and a quaternion. | |
| template<typename PointT > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform) |
| Apply an affine transform defined by an Eigen Transform. | |
| template<typename PointT > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< int > &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Affine3f &transform) |
| Apply an affine transform defined by an Eigen Transform. | |
| template<typename PointT > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Affine3f &transform) |
| Apply an affine transform defined by an Eigen Transform. | |
| template<typename PointT > | |
| void | pcl::transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Vector3f &offset, const Eigen::Quaternionf &rotation) |
| Transform a point cloud and rotate its normals using an Eigen transform. | |
| template<typename PointT > | |
| void | pcl::transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform) |
| Transform a point cloud and rotate its normals using an Eigen transform. | |
| template<typename PointT > | |
| void | pcl::transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Affine3f &transform) |
| Transform a point cloud and rotate its normals using an Eigen transform. | |