Namespaces | |
namespace | io |
Functions | |
bool | concatenatePointCloud (const sensor_msgs::PointCloud2 &cloud1, const sensor_msgs::PointCloud2 &cloud2, sensor_msgs::PointCloud2 &cloud_out) |
template<typename PointT > | |
void | createMapping (const std::vector< sensor_msgs::PointField > &msg_fields, MsgFieldMap &field_map) |
template<typename T > | |
void | fromROSMsg (const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud) |
int | getFieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name) |
std::string | getFieldsList (const sensor_msgs::PointCloud2 &cloud) |
template<typename T > | |
void | moveFromROSMsg (sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud) |
void | moveToROSMsg (sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image) |
void | toROSMsg (const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image) |
template<typename T > | |
void | toROSMsg (const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg) |
template<typename T > | |
void | toROSMsg (const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud) |
bool pcl::concatenatePointCloud | ( | const sensor_msgs::PointCloud2 & | cloud1, |
const sensor_msgs::PointCloud2 & | cloud2, | ||
sensor_msgs::PointCloud2 & | cloud_out | ||
) | [inline] |
Overload asdf
Definition at line 612 of file pcl_conversions.h.
void pcl::createMapping | ( | const std::vector< sensor_msgs::PointField > & | msg_fields, |
MsgFieldMap & | field_map | ||
) |
Overload pcl::createMapping
Definition at line 564 of file pcl_conversions.h.
void pcl::fromROSMsg | ( | const sensor_msgs::PointCloud2 & | cloud, |
pcl::PointCloud< T > & | pcl_cloud | ||
) |
Definition at line 546 of file pcl_conversions.h.
int pcl::getFieldIndex | ( | const sensor_msgs::PointCloud2 & | cloud, |
const std::string & | field_name | ||
) | [inline] |
Overload pcl::getFieldIndex
Definition at line 460 of file pcl_conversions.h.
std::string pcl::getFieldsList | ( | const sensor_msgs::PointCloud2 & | cloud | ) | [inline] |
Overload pcl::getFieldsList
Definition at line 473 of file pcl_conversions.h.
void pcl::moveFromROSMsg | ( | sensor_msgs::PointCloud2 & | cloud, |
pcl::PointCloud< T > & | pcl_cloud | ||
) |
Definition at line 554 of file pcl_conversions.h.
void pcl::moveToROSMsg | ( | sensor_msgs::PointCloud2 & | cloud, |
sensor_msgs::Image & | image | ||
) | [inline] |
Definition at line 496 of file pcl_conversions.h.
void pcl::toROSMsg | ( | const sensor_msgs::PointCloud2 & | cloud, |
sensor_msgs::Image & | image | ||
) | [inline] |
Provide pcl::toROSMsg
Definition at line 486 of file pcl_conversions.h.
void pcl::toROSMsg | ( | const pcl::PointCloud< T > & | cloud, |
sensor_msgs::Image & | msg | ||
) |
Definition at line 506 of file pcl_conversions.h.
void pcl::toROSMsg | ( | const pcl::PointCloud< T > & | pcl_cloud, |
sensor_msgs::PointCloud2 & | cloud | ||
) |
Provide to/fromROSMsg for sensor_msgs::PointCloud2 <=> pcl::PointCloud<T>
Definition at line 538 of file pcl_conversions.h.