#include <sensor_msgs/PointField.h>#include <sensor_msgs/PointCloud2.h>#include <sensor_msgs/Image.h>#include <pcl/point_cloud.h>#include <pcl/point_traits.h>#include <pcl/for_each_type.h>#include <pcl/exceptions.h>#include <pcl/console/print.h>#include <boost/foreach.hpp>

Go to the source code of this file.
Classes | |
| struct | pcl::detail::FieldAdder< PointT > |
| struct | pcl::detail::FieldMapper< PointT > |
Namespaces | |
| namespace | pcl |
| namespace | pcl::detail |
Functions | |
| template<typename PointT > | |
| void | pcl::createMapping (const std::vector< sensor_msgs::PointField > &msg_fields, MsgFieldMap &field_map) |
| bool | pcl::detail::fieldOrdering (const FieldMapping &a, const FieldMapping &b) |
| template<typename PointT > | |
| void | pcl::fromROSMsg (const sensor_msgs::PointCloud2 &msg, pcl::PointCloud< PointT > &cloud, const MsgFieldMap &field_map) |
| Convert a PointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map. | |
| template<typename PointT > | |
| void | pcl::fromROSMsg (const sensor_msgs::PointCloud2 &msg, pcl::PointCloud< PointT > &cloud) |
| Convert a PointCloud2 binary data blob into a pcl::PointCloud<T> object. | |
| template<typename PointT > | |
| void | pcl::toROSMsg (const pcl::PointCloud< PointT > &cloud, sensor_msgs::PointCloud2 &msg) |
| Convert a pcl::PointCloud<T> object to a PointCloud2 binary data blob. | |
| template<typename CloudT > | |
| void | pcl::toROSMsg (const CloudT &cloud, sensor_msgs::Image &msg) |
| Copy the RGB fields of a PointCloud into sensor_msgs::Image format. | |
| void | pcl::toROSMsg (const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &msg) |
| Copy the RGB fields of a PointCloud2 msg into sensor_msgs::Image format. | |