Classes | Namespaces | Functions
pcl_conversions.h File Reference
#include <vector>
#include <ros/ros.h>
#include <pcl/conversions.h>
#include <pcl/PCLHeader.h>
#include <std_msgs/Header.h>
#include <pcl/PCLImage.h>
#include <sensor_msgs/Image.h>
#include <pcl/PCLPointField.h>
#include <sensor_msgs/PointField.h>
#include <pcl/PCLPointCloud2.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl/PointIndices.h>
#include <pcl_msgs/PointIndices.h>
#include <pcl/ModelCoefficients.h>
#include <pcl_msgs/ModelCoefficients.h>
#include <pcl/Vertices.h>
#include <pcl_msgs/Vertices.h>
#include <pcl/PolygonMesh.h>
#include <pcl_msgs/PolygonMesh.h>
#include <pcl/io/pcd_io.h>
#include <Eigen/StdVector>
#include <Eigen/Geometry>
Include dependency graph for pcl_conversions.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  ros::message_traits::DataType< pcl::PCLPointCloud2 >
struct  ros::DefaultMessageCreator< pcl::PCLPointCloud2 >
struct  ros::message_traits::Definition< pcl::PCLPointCloud2 >
struct  ros::message_traits::HasHeader< pcl::PCLPointCloud2 >
struct  ros::message_traits::MD5Sum< pcl::PCLPointCloud2 >
struct  ros::serialization::Serializer< pcl::PCLHeader >
struct  ros::serialization::Serializer< pcl::PCLPointCloud2 >
struct  ros::serialization::Serializer< pcl::PCLPointField >

Namespaces

namespace  pcl
namespace  pcl::io
namespace  pcl_conversions
namespace  ros
namespace  ros::message_traits
namespace  ros::serialization

Functions

bool pcl::concatenatePointCloud (const sensor_msgs::PointCloud2 &cloud1, const sensor_msgs::PointCloud2 &cloud2, sensor_msgs::PointCloud2 &cloud_out)
void pcl_conversions::copyImageMetaData (const sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
void pcl_conversions::copyPCLImageMetaData (const pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
void pcl_conversions::copyPCLPointCloud2MetaData (const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
void pcl_conversions::copyPointCloud2MetaData (const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
template<typename PointT >
void pcl::createMapping (const std::vector< sensor_msgs::PointField > &msg_fields, MsgFieldMap &field_map)
int pcl::io::destructiveSavePCDFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), const bool binary_mode=false)
void pcl_conversions::fromPCL (const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
ros::Time pcl_conversions::fromPCL (const pcl::uint64_t &pcl_stamp)
void pcl_conversions::fromPCL (const pcl::PCLHeader &pcl_header, std_msgs::Header &header)
std_msgs::Header pcl_conversions::fromPCL (const pcl::PCLHeader &pcl_header)
void pcl_conversions::fromPCL (const pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
void pcl_conversions::fromPCL (const pcl::PCLPointField &pcl_pf, sensor_msgs::PointField &pf)
void pcl_conversions::fromPCL (const std::vector< pcl::PCLPointField > &pcl_pfs, std::vector< sensor_msgs::PointField > &pfs)
void pcl_conversions::fromPCL (const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
void pcl_conversions::fromPCL (const pcl::PointIndices &pcl_pi, pcl_msgs::PointIndices &pi)
void pcl_conversions::fromPCL (const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
void pcl_conversions::fromPCL (const pcl::Vertices &pcl_vert, pcl_msgs::Vertices &vert)
void pcl_conversions::fromPCL (const std::vector< pcl::Vertices > &pcl_verts, std::vector< pcl_msgs::Vertices > &verts)
void pcl_conversions::fromPCL (std::vector< pcl::Vertices > &pcl_verts, std::vector< pcl_msgs::Vertices > &verts)
void pcl_conversions::fromPCL (const pcl::PolygonMesh &pcl_mesh, pcl_msgs::PolygonMesh &mesh)
template<typename T >
void pcl::fromROSMsg (const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
int pcl::getFieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
std::string pcl::getFieldsList (const sensor_msgs::PointCloud2 &cloud)
int pcl::io::loadPCDFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
void pcl_conversions::moveFromPCL (pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
void pcl_conversions::moveFromPCL (pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
void pcl_conversions::moveFromPCL (pcl::PointIndices &pcl_pi, pcl_msgs::PointIndices &pi)
void pcl_conversions::moveFromPCL (pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
void pcl_conversions::moveFromPCL (pcl::Vertices &pcl_vert, pcl_msgs::Vertices &vert)
void pcl_conversions::moveFromPCL (pcl::PolygonMesh &pcl_mesh, pcl_msgs::PolygonMesh &mesh)
template<typename T >
void pcl::moveFromROSMsg (sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
void pcl_conversions::moveToPCL (sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
void pcl_conversions::moveToPCL (sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
void pcl_conversions::moveToPCL (pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
void pcl_conversions::moveToPCL (pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
void pcl_conversions::moveToPCL (pcl_msgs::Vertices &vert, pcl::Vertices &pcl_vert)
void pcl_conversions::moveToPCL (std::vector< pcl_msgs::Vertices > &verts, std::vector< pcl::Vertices > &pcl_verts)
void pcl_conversions::moveToPCL (pcl_msgs::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh)
void pcl::moveToROSMsg (sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
int pcl::io::savePCDFile (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), const bool binary_mode=false)
void pcl_conversions::toPCL (const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
pcl::uint64_t pcl_conversions::toPCL (const ros::Time &stamp)
void pcl_conversions::toPCL (const std_msgs::Header &header, pcl::PCLHeader &pcl_header)
pcl::PCLHeader pcl_conversions::toPCL (const std_msgs::Header &header)
void pcl_conversions::toPCL (const sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
void pcl_conversions::toPCL (const sensor_msgs::PointField &pf, pcl::PCLPointField &pcl_pf)
void pcl_conversions::toPCL (const std::vector< sensor_msgs::PointField > &pfs, std::vector< pcl::PCLPointField > &pcl_pfs)
void pcl_conversions::toPCL (const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
void pcl_conversions::toPCL (const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
void pcl_conversions::toPCL (const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
void pcl_conversions::toPCL (const pcl_msgs::Vertices &vert, pcl::Vertices &pcl_vert)
void pcl_conversions::toPCL (const std::vector< pcl_msgs::Vertices > &verts, std::vector< pcl::Vertices > &pcl_verts)
void pcl_conversions::toPCL (const pcl_msgs::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh)
void pcl::toROSMsg (const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
template<typename T >
void pcl::toROSMsg (const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
template<typename T >
void pcl::toROSMsg (const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)


pcl_conversions
Author(s): William Woodall
autogenerated on Thu Nov 3 2016 03:30:00