40 #ifndef PCL_ROS_CONVERSIONS_H_
41 #define PCL_ROS_CONVERSIONS_H_
44 #warning The <pcl/ros/conversions.h> header is deprecated. please use \
45 <pcl/conversions.h> instead.
48 #include <pcl/conversions.h>
68 "pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.");
70 template <
typename Po
intT>
void
83 "pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.");
84 template<
typename Po
intT>
void
96 "pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.");
97 template<
typename Po
intT>
void
111 "pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.");
112 template<
typename CloudT>
void
125 "pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.");
133 #endif //#ifndef PCL_ROS_CONVERSIONS_H_
void toPCLPointCloud2(const pcl::PointCloud< PointT > &cloud, pcl::PCLPointCloud2 &msg)
Convert a pcl::PointCloud object to a PCLPointCloud2 binary data blob.
std::vector< detail::FieldMapping > MsgFieldMap
void fromROSMsg(const pcl::PCLPointCloud2 &msg, pcl::PointCloud< PointT > &cloud, const MsgFieldMap &field_map)
void fromPCLPointCloud2(const pcl::PCLPointCloud2 &msg, pcl::PointCloud< PointT > &cloud, const MsgFieldMap &field_map)
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud object using a field_map...
PointCloud represents the base class in PCL for storing collections of 3D points. ...
PCL_DEPRECATED(template< typename PointT > void fromROSMsg(const pcl::PCLPointCloud2 &msg, pcl::PointCloud< PointT > &cloud, const MsgFieldMap &field_map),"pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.")
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud object using a field_map...
void toROSMsg(const pcl::PointCloud< PointT > &cloud, pcl::PCLPointCloud2 &msg)