#include <string>
#include <boost/fusion/sequence/intrinsic/at_key.hpp>
#include "pcl/pcl_base.h"
#include "pcl/PointIndices.h"
#include "pcl/ros/conversions.h"
#include <locale>
#include "pcl/io/io.hpp"
Go to the source code of this file.
Namespaces | |
namespace | pcl |
Functions | |
template<typename PointIn1T , typename PointIn2T , typename PointOutT > | |
void | pcl::concatenateFields (const pcl::PointCloud< PointIn1T > &cloud1_in, const pcl::PointCloud< PointIn2T > &cloud2_in, pcl::PointCloud< PointOutT > &cloud_out) |
Concatenate two datasets representing different fields. | |
bool | pcl::concatenatePointCloud (const sensor_msgs::PointCloud2 &cloud1, const sensor_msgs::PointCloud2 &cloud2, sensor_msgs::PointCloud2 &cloud_out) |
Concatenate two sensor_msgs::PointCloud2. Returns true if successful, false if failed (e.g., name/number of fields differs). | |
template<typename PointT > | |
void | pcl::copyPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< pcl::PointIndices > &indices, pcl::PointCloud< PointT > &cloud_out) |
Extract the indices of a given point cloud as a new point cloud. | |
template<typename PointT > | |
void | pcl::copyPointCloud (const pcl::PointCloud< PointT > &cloud_in, const PointIndices &indices, pcl::PointCloud< PointT > &cloud_out) |
Extract the indices of a given point cloud as a new point cloud. | |
template<typename PointT > | |
void | pcl::copyPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< int > &indices, pcl::PointCloud< PointT > &cloud_out) |
Extract the indices of a given point cloud as a new point cloud. | |
void | pcl::copyPointCloud (const sensor_msgs::PointCloud2 &cloud_in, const std::vector< int > &indices, sensor_msgs::PointCloud2 &cloud_out) |
Extract the indices of a given point cloud as a new point cloud. | |
template<typename PointInT , typename PointOutT > | |
void | pcl::copyPointCloud (const pcl::PointCloud< PointInT > &cloud_in, pcl::PointCloud< PointOutT > &cloud_out) |
Copy all the fields from a given point cloud into a new point cloud. | |
bool | pcl::getEigenAsPointCloud (Eigen::MatrixXf &in, sensor_msgs::PointCloud2 &out) |
Copy the XYZ dimensions from an Eigen MatrixXf into a sensor_msgs::PointCloud2 message. | |
template<typename PointT > | |
int | pcl::getFieldIndex (const pcl::PointCloud< PointT > &cloud, const std::string &field_name, std::vector< sensor_msgs::PointField > &fields) |
Get the index of a specified field (i.e., dimension/channel). | |
int | pcl::getFieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name) |
Get the index of a specified field (i.e., dimension/channel). | |
template<typename PointT > | |
void | pcl::getFields (const pcl::PointCloud< PointT > &cloud, std::vector< sensor_msgs::PointField > &fields) |
Get the list of available fields (i.e., dimension/channel). | |
int | pcl::getFieldSize (int datatype) |
Obtains the size of a specific field data type in bytes. | |
std::string | pcl::getFieldsList (const sensor_msgs::PointCloud2 &cloud) |
Get the available point cloud fields as a space separated string. | |
template<typename PointT > | |
std::string | pcl::getFieldsList (const pcl::PointCloud< PointT > &cloud) |
Get the list of all fields available in a given cloud. | |
char | pcl::getFieldType (int type) |
Obtains the type of the PointField from a specific PointField as a char. | |
int | pcl::getFieldType (int size, char type) |
Obtains the type of the PointField from a specific size and type. | |
bool | pcl::getPointCloudAsEigen (const sensor_msgs::PointCloud2 &in, Eigen::MatrixXf &out) |
Copy the XYZ dimensions of a sensor_msgs::PointCloud2 into Eigen format. |