Namespaces | Functions
pcl Namespace Reference

Namespaces

 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)
 
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)
 
void toROSMsg (const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
 

Function Documentation

◆ concatenatePointCloud()

bool pcl::concatenatePointCloud ( const sensor_msgs::PointCloud2 &  cloud1,
const sensor_msgs::PointCloud2 &  cloud2,
sensor_msgs::PointCloud2 &  cloud_out 
)
inline

Overload asdf

Definition at line 643 of file pcl_conversions.h.

◆ createMapping()

template<typename PointT >
void pcl::createMapping ( const std::vector< sensor_msgs::PointField > &  msg_fields,
MsgFieldMap &  field_map 
)

Overload pcl::createMapping

Definition at line 595 of file pcl_conversions.h.

◆ fromROSMsg()

template<typename T >
void pcl::fromROSMsg ( const sensor_msgs::PointCloud2 &  cloud,
pcl::PointCloud< T > &  pcl_cloud 
)

Definition at line 570 of file pcl_conversions.h.

◆ getFieldIndex()

int pcl::getFieldIndex ( const sensor_msgs::PointCloud2 &  cloud,
const std::string &  field_name 
)
inline

Overload pcl::getFieldIndex

Definition at line 479 of file pcl_conversions.h.

◆ getFieldsList()

std::string pcl::getFieldsList ( const sensor_msgs::PointCloud2 &  cloud)
inline

Overload pcl::getFieldsList

Definition at line 492 of file pcl_conversions.h.

◆ moveFromROSMsg()

template<typename T >
void pcl::moveFromROSMsg ( sensor_msgs::PointCloud2 &  cloud,
pcl::PointCloud< T > &  pcl_cloud 
)

Definition at line 585 of file pcl_conversions.h.

◆ moveToROSMsg()

void pcl::moveToROSMsg ( sensor_msgs::PointCloud2 &  cloud,
sensor_msgs::Image &  image 
)
inline

Definition at line 515 of file pcl_conversions.h.

◆ toROSMsg() [1/3]

template<typename T >
void pcl::toROSMsg ( const pcl::PointCloud< T > &  cloud,
sensor_msgs::Image &  msg 
)

Definition at line 525 of file pcl_conversions.h.

◆ toROSMsg() [2/3]

template<typename T >
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 557 of file pcl_conversions.h.

◆ toROSMsg() [3/3]

void pcl::toROSMsg ( const sensor_msgs::PointCloud2 &  cloud,
sensor_msgs::Image &  image 
)
inline

Provide pcl::toROSMsg

Definition at line 505 of file pcl_conversions.h.



pcl_conversions
Author(s): William Woodall
autogenerated on Fri Jul 12 2024 02:54:37