#include <pcl/point_cloud.h>#include <pcl/point_types.h>#include <pcl/common/centroid.h>#include <pcl/common/eigen.h>#include <pcl/PointIndices.h>#include <pcl/common/impl/transforms.hpp>

Go to the source code of this file.
Namespaces | |
| namespace | pcl |
Functions | |
| template<typename PointT , typename Scalar > | |
| double | pcl::getPrincipalTransformation (const pcl::PointCloud< PointT > &cloud, Eigen::Transform< Scalar, 3, Eigen::Affine > &transform) |
| Calculates the principal (PCA-based) alignment of the point cloud. | |
| template<typename PointT > | |
| double | pcl::getPrincipalTransformation (const pcl::PointCloud< PointT > &cloud, Eigen::Affine3f &transform) |
| template<typename PointT , typename Scalar > | |
| PointT | pcl::transformPoint (const PointT &point, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transform) |
| Transform a point with members x,y,z. | |
| template<typename PointT > | |
| PointT | pcl::transformPoint (const PointT &point, const Eigen::Affine3f &transform) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &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) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< int > &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &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) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transform) |
| Apply an affine transform defined by an Eigen Transform. | |
| template<typename PointT > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Affine3f &transform) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform) |
| Apply a rigid transform defined by a 4x4 matrix. | |
| template<typename PointT > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< int > &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform) |
| Apply a rigid transform defined by a 4x4 matrix. | |
| template<typename PointT > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< int > &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform) |
| Apply a rigid transform defined by a 4x4 matrix. | |
| template<typename PointT > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 3, 1 > &offset, const Eigen::Quaternion< Scalar > &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::Vector3f &offset, const Eigen::Quaternionf &rotation) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &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) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, const std::vector< int > &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &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, const std::vector< int > &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Affine3f &transform) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &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, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Affine3f &transform) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &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::Matrix4f &transform) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, const std::vector< int > &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &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, const std::vector< int > &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &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, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform) |
| template<typename PointT , typename Scalar > | |
| void | pcl::transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 3, 1 > &offset, const Eigen::Quaternion< Scalar > &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::Vector3f &offset, const Eigen::Quaternionf &rotation) |