30 #ifndef MCL_3DL_POINT_CONVERSION_H 31 #define MCL_3DL_POINT_CONVERSION_H 37 #include <pcl/point_cloud.h> 38 #include <pcl/point_types.h> 41 #include <sensor_msgs/PointCloud2.h> 48 template <
typename Po
intTIn,
typename Po
intTOut>
50 const sensor_msgs::PointCloud2& msg, pcl::PointCloud<PointTOut>& pc)
52 typename pcl::PointCloud<PointTIn>::Ptr raw(
new typename pcl::PointCloud<PointTIn>);
54 if (raw->points.size() == 0)
59 pcl::copyPointCloud(*raw, pc);
64 template <
typename Po
intT>
66 const sensor_msgs::PointCloud2& msg, pcl::PointCloud<PointT>& pc)
68 const int x_idx = getPointCloud2FieldIndex(msg,
"x");
69 const int y_idx = getPointCloud2FieldIndex(msg,
"y");
70 const int z_idx = getPointCloud2FieldIndex(msg,
"z");
71 const int intensity_idx = getPointCloud2FieldIndex(msg,
"intensity");
72 const int label_idx = getPointCloud2FieldIndex(msg,
"label");
74 if (x_idx == -1 || y_idx == -1 || z_idx == -1)
76 ROS_ERROR(
"Given PointCloud2 doesn't have x, y, z fields");
79 if (intensity_idx != -1)
83 return fromROSMsgImpl<mcl_3dl::PointXYZIL, PointT>(msg, pc);
85 return fromROSMsgImpl<pcl::PointXYZI, PointT>(msg, pc);
89 return fromROSMsgImpl<pcl::PointXYZL, PointT>(msg, pc);
91 return fromROSMsgImpl<pcl::PointXYZ, PointT>(msg, pc);
94 #endif // MCL_3DL_POINT_CONVERSION_H
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
bool fromROSMsg(const sensor_msgs::PointCloud2 &msg, pcl::PointCloud< PointT > &pc)