#include <pcl/common/eigen.h>#include <cstddef>#include <std_msgs/Header.h>#include <pcl/pcl_macros.h>#include <pcl/exceptions.h>#include <pcl/cloud_properties.h>#include <pcl/channel_properties.h>#include <pcl/point_traits.h>#include <pcl/for_each_type.h>#include <boost/shared_ptr.hpp>#include <map>#include <boost/mpl/size.hpp>
Go to the source code of this file.
Classes | |
| struct | pcl::PointCloud< Eigen::MatrixXf >::CopyFieldsChannelProperties< T > |
| Helper functor structure for copying channel information. More... | |
| struct | pcl::detail::FieldMapping |
| struct | pcl::PointCloud< Eigen::MatrixXf >::NdCopyEigenPointFunctor< PointOutT, PointInT > |
| Helper functor structure for copying data between an Eigen type and a PointT. More... | |
| struct | pcl::NdCopyEigenPointFunctor< PointOutT > |
| Helper functor structure for copying data between an Eigen type and a PointT. More... | |
| struct | pcl::PointCloud< Eigen::MatrixXf >::NdCopyPointEigenFunctor< PointInT, PointOutT > |
| Helper functor structure for copying data between an Eigen type and a PointT. More... | |
| struct | pcl::NdCopyPointEigenFunctor< PointInT > |
| Helper functor structure for copying data between an Eigen type and a PointT. More... | |
| class | pcl::PointCloud< PointT > |
| PointCloud represents the base class in PCL for storing collections of 3D points. More... | |
| class | pcl::PointCloud< Eigen::MatrixXf > |
| PointCloud specialization for Eigen matrices. For advanced users only! More... | |
Namespaces | |
| namespace | pcl |
| namespace | pcl::detail |
Typedefs | |
| typedef std::vector < detail::FieldMapping > | pcl::MsgFieldMap |
Functions | |
| template<typename PointT > | |
| boost::shared_ptr < pcl::MsgFieldMap > & | pcl::detail::getMapping (pcl::PointCloud< PointT > &p) |
| template<typename PointT > | |
| std::ostream & | pcl::operator<< (std::ostream &s, const pcl::PointCloud< PointT > &p) |