Functions
pcl_conversions Namespace Reference

Functions

void copyImageMetaData (const sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
 
void copyPCLImageMetaData (const pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
 
void copyPCLPointCloud2MetaData (const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
 
void copyPointCloud2MetaData (const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
 
void fromPCL (const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
 
ros::Time fromPCL (const pcl::uint64_t &pcl_stamp)
 
void fromPCL (const pcl::PCLHeader &pcl_header, std_msgs::Header &header)
 
std_msgs::Header fromPCL (const pcl::PCLHeader &pcl_header)
 
void fromPCL (const pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
 
void fromPCL (const pcl::PCLPointField &pcl_pf, sensor_msgs::PointField &pf)
 
void fromPCL (const std::vector< pcl::PCLPointField > &pcl_pfs, std::vector< sensor_msgs::PointField > &pfs)
 
void fromPCL (const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
 
void fromPCL (const pcl::PointIndices &pcl_pi, pcl_msgs::PointIndices &pi)
 
void fromPCL (const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
 
void fromPCL (const pcl::Vertices &pcl_vert, pcl_msgs::Vertices &vert)
 
void fromPCL (const std::vector< pcl::Vertices > &pcl_verts, std::vector< pcl_msgs::Vertices > &verts)
 
void fromPCL (std::vector< pcl::Vertices > &pcl_verts, std::vector< pcl_msgs::Vertices > &verts)
 
void fromPCL (const pcl::PolygonMesh &pcl_mesh, pcl_msgs::PolygonMesh &mesh)
 
void moveFromPCL (pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
 
void moveFromPCL (pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
 
void moveFromPCL (pcl::PointIndices &pcl_pi, pcl_msgs::PointIndices &pi)
 
void moveFromPCL (pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
 
void moveFromPCL (pcl::Vertices &pcl_vert, pcl_msgs::Vertices &vert)
 
void moveFromPCL (pcl::PolygonMesh &pcl_mesh, pcl_msgs::PolygonMesh &mesh)
 
void moveToPCL (sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
 
void moveToPCL (sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
 
void moveToPCL (pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
 
void moveToPCL (pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
 
void moveToPCL (pcl_msgs::Vertices &vert, pcl::Vertices &pcl_vert)
 
void moveToPCL (std::vector< pcl_msgs::Vertices > &verts, std::vector< pcl::Vertices > &pcl_verts)
 
void moveToPCL (pcl_msgs::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh)
 
void toPCL (const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
 
pcl::uint64_t toPCL (const ros::Time &stamp)
 
void toPCL (const std_msgs::Header &header, pcl::PCLHeader &pcl_header)
 
pcl::PCLHeader toPCL (const std_msgs::Header &header)
 
void toPCL (const sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
 
void toPCL (const sensor_msgs::PointField &pf, pcl::PCLPointField &pcl_pf)
 
void toPCL (const std::vector< sensor_msgs::PointField > &pfs, std::vector< pcl::PCLPointField > &pcl_pfs)
 
void toPCL (const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
 
void toPCL (const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
 
void toPCL (const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
 
void toPCL (const pcl_msgs::Vertices &vert, pcl::Vertices &pcl_vert)
 
void toPCL (const std::vector< pcl_msgs::Vertices > &verts, std::vector< pcl::Vertices > &pcl_verts)
 
void toPCL (const pcl_msgs::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh)
 

Function Documentation

void pcl_conversions::copyImageMetaData ( const sensor_msgs::Image &  image,
pcl::PCLImage &  pcl_image 
)
inline

Definition at line 169 of file pcl_conversions.h.

void pcl_conversions::copyPCLImageMetaData ( const pcl::PCLImage &  pcl_image,
sensor_msgs::Image &  image 
)
inline

PCLImage <=> Image

Definition at line 144 of file pcl_conversions.h.

void pcl_conversions::copyPCLPointCloud2MetaData ( const pcl::PCLPointCloud2 &  pcl_pc2,
sensor_msgs::PointCloud2 &  pc2 
)
inline

PCLPointCloud2 <=> PointCloud2

Definition at line 238 of file pcl_conversions.h.

void pcl_conversions::copyPointCloud2MetaData ( const sensor_msgs::PointCloud2 &  pc2,
pcl::PCLPointCloud2 &  pcl_pc2 
)
inline

Definition at line 265 of file pcl_conversions.h.

void pcl_conversions::fromPCL ( const pcl::uint64_t &  pcl_stamp,
ros::Time stamp 
)
inline

PCLHeader <=> Header

Definition at line 80 of file pcl_conversions.h.

ros::Time pcl_conversions::fromPCL ( const pcl::uint64_t &  pcl_stamp)
inline

Definition at line 92 of file pcl_conversions.h.

void pcl_conversions::fromPCL ( const pcl::PCLHeader &  pcl_header,
std_msgs::Header header 
)
inline

PCLHeader <=> Header

Definition at line 110 of file pcl_conversions.h.

std_msgs::Header pcl_conversions::fromPCL ( const pcl::PCLHeader &  pcl_header)
inline

Definition at line 126 of file pcl_conversions.h.

void pcl_conversions::fromPCL ( const pcl::PCLImage &  pcl_image,
sensor_msgs::Image &  image 
)
inline

Definition at line 155 of file pcl_conversions.h.

void pcl_conversions::fromPCL ( const pcl::PCLPointField &  pcl_pf,
sensor_msgs::PointField &  pf 
)
inline

PCLPointField <=> PointField

Definition at line 196 of file pcl_conversions.h.

void pcl_conversions::fromPCL ( const std::vector< pcl::PCLPointField > &  pcl_pfs,
std::vector< sensor_msgs::PointField > &  pfs 
)
inline

Definition at line 205 of file pcl_conversions.h.

void pcl_conversions::fromPCL ( const pcl::PCLPointCloud2 &  pcl_pc2,
sensor_msgs::PointCloud2 &  pc2 
)
inline

Definition at line 251 of file pcl_conversions.h.

void pcl_conversions::fromPCL ( const pcl::PointIndices &  pcl_pi,
pcl_msgs::PointIndices &  pi 
)
inline

pcl::PointIndices <=> pcl_msgs::PointIndices

Definition at line 294 of file pcl_conversions.h.

void pcl_conversions::fromPCL ( const pcl::ModelCoefficients &  pcl_mc,
pcl_msgs::ModelCoefficients &  mc 
)
inline

pcl::ModelCoefficients <=> pcl_msgs::ModelCoefficients

Definition at line 324 of file pcl_conversions.h.

void pcl_conversions::fromPCL ( const pcl::Vertices &  pcl_vert,
pcl_msgs::Vertices &  vert 
)
inline

pcl::Vertices <=> pcl_msgs::Vertices

Definition at line 354 of file pcl_conversions.h.

void pcl_conversions::fromPCL ( const std::vector< pcl::Vertices > &  pcl_verts,
std::vector< pcl_msgs::Vertices > &  verts 
)
inline

Definition at line 360 of file pcl_conversions.h.

void pcl_conversions::fromPCL ( std::vector< pcl::Vertices > &  pcl_verts,
std::vector< pcl_msgs::Vertices > &  verts 
)
inline

Definition at line 377 of file pcl_conversions.h.

void pcl_conversions::fromPCL ( const pcl::PolygonMesh &  pcl_mesh,
pcl_msgs::PolygonMesh &  mesh 
)
inline

pcl::PolygonMesh <=> pcl_msgs::PolygonMesh

Definition at line 424 of file pcl_conversions.h.

void pcl_conversions::moveFromPCL ( pcl::PCLImage &  pcl_image,
sensor_msgs::Image &  image 
)
inline

Definition at line 162 of file pcl_conversions.h.

void pcl_conversions::moveFromPCL ( pcl::PCLPointCloud2 &  pcl_pc2,
sensor_msgs::PointCloud2 &  pc2 
)
inline

Definition at line 258 of file pcl_conversions.h.

void pcl_conversions::moveFromPCL ( pcl::PointIndices &  pcl_pi,
pcl_msgs::PointIndices &  pi 
)
inline

Definition at line 301 of file pcl_conversions.h.

void pcl_conversions::moveFromPCL ( pcl::ModelCoefficients &  pcl_mc,
pcl_msgs::ModelCoefficients &  mc 
)
inline

Definition at line 331 of file pcl_conversions.h.

void pcl_conversions::moveFromPCL ( pcl::Vertices &  pcl_vert,
pcl_msgs::Vertices &  vert 
)
inline

Definition at line 371 of file pcl_conversions.h.

void pcl_conversions::moveFromPCL ( pcl::PolygonMesh &  pcl_mesh,
pcl_msgs::PolygonMesh &  mesh 
)
inline

Definition at line 432 of file pcl_conversions.h.

void pcl_conversions::moveToPCL ( sensor_msgs::Image &  image,
pcl::PCLImage &  pcl_image 
)
inline

Definition at line 187 of file pcl_conversions.h.

void pcl_conversions::moveToPCL ( sensor_msgs::PointCloud2 &  pc2,
pcl::PCLPointCloud2 &  pcl_pc2 
)
inline

Definition at line 285 of file pcl_conversions.h.

void pcl_conversions::moveToPCL ( pcl_msgs::PointIndices &  pi,
pcl::PointIndices &  pcl_pi 
)
inline

Definition at line 315 of file pcl_conversions.h.

void pcl_conversions::moveToPCL ( pcl_msgs::ModelCoefficients &  mc,
pcl::ModelCoefficients &  pcl_mc 
)
inline

Definition at line 345 of file pcl_conversions.h.

void pcl_conversions::moveToPCL ( pcl_msgs::Vertices &  vert,
pcl::Vertices &  pcl_vert 
)
inline

Definition at line 405 of file pcl_conversions.h.

void pcl_conversions::moveToPCL ( std::vector< pcl_msgs::Vertices > &  verts,
std::vector< pcl::Vertices > &  pcl_verts 
)
inline

Definition at line 411 of file pcl_conversions.h.

void pcl_conversions::moveToPCL ( pcl_msgs::PolygonMesh &  mesh,
pcl::PolygonMesh &  pcl_mesh 
)
inline

Definition at line 447 of file pcl_conversions.h.

void pcl_conversions::toPCL ( const ros::Time stamp,
pcl::uint64_t &  pcl_stamp 
)
inline

Definition at line 86 of file pcl_conversions.h.

pcl::uint64_t pcl_conversions::toPCL ( const ros::Time stamp)
inline

Definition at line 100 of file pcl_conversions.h.

void pcl_conversions::toPCL ( const std_msgs::Header header,
pcl::PCLHeader &  pcl_header 
)
inline

Definition at line 118 of file pcl_conversions.h.

pcl::PCLHeader pcl_conversions::toPCL ( const std_msgs::Header header)
inline

Definition at line 134 of file pcl_conversions.h.

void pcl_conversions::toPCL ( const sensor_msgs::Image &  image,
pcl::PCLImage &  pcl_image 
)
inline

Definition at line 180 of file pcl_conversions.h.

void pcl_conversions::toPCL ( const sensor_msgs::PointField &  pf,
pcl::PCLPointField &  pcl_pf 
)
inline

Definition at line 216 of file pcl_conversions.h.

void pcl_conversions::toPCL ( const std::vector< sensor_msgs::PointField > &  pfs,
std::vector< pcl::PCLPointField > &  pcl_pfs 
)
inline

Definition at line 225 of file pcl_conversions.h.

void pcl_conversions::toPCL ( const sensor_msgs::PointCloud2 &  pc2,
pcl::PCLPointCloud2 &  pcl_pc2 
)
inline

Definition at line 278 of file pcl_conversions.h.

void pcl_conversions::toPCL ( const pcl_msgs::PointIndices &  pi,
pcl::PointIndices &  pcl_pi 
)
inline

Definition at line 308 of file pcl_conversions.h.

void pcl_conversions::toPCL ( const pcl_msgs::ModelCoefficients &  mc,
pcl::ModelCoefficients &  pcl_mc 
)
inline

Definition at line 338 of file pcl_conversions.h.

void pcl_conversions::toPCL ( const pcl_msgs::Vertices &  vert,
pcl::Vertices &  pcl_vert 
)
inline

Definition at line 388 of file pcl_conversions.h.

void pcl_conversions::toPCL ( const std::vector< pcl_msgs::Vertices > &  verts,
std::vector< pcl::Vertices > &  pcl_verts 
)
inline

Definition at line 394 of file pcl_conversions.h.

void pcl_conversions::toPCL ( const pcl_msgs::PolygonMesh &  mesh,
pcl::PolygonMesh &  pcl_mesh 
)
inline

Definition at line 439 of file pcl_conversions.h.



pcl_conversions
Author(s): William Woodall
autogenerated on Mon Jun 10 2019 14:15:12