point_conversion.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, the mcl_3dl authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef MCL_3DL_POINT_CONVERSION_H
31 #define MCL_3DL_POINT_CONVERSION_H
32 
33 #include <ros/ros.h>
34 
35 #include <mcl_3dl/point_types.h>
36 
37 #include <pcl/point_cloud.h>
38 #include <pcl/point_types.h>
39 #include <pcl_ros/point_cloud.h>
40 
41 #include <sensor_msgs/PointCloud2.h>
43 
44 namespace mcl_3dl
45 {
46 namespace
47 {
48 template <typename PointTIn, typename PointTOut>
49 bool fromROSMsgImpl(
50  const sensor_msgs::PointCloud2& msg, pcl::PointCloud<PointTOut>& pc)
51 {
52  typename pcl::PointCloud<PointTIn>::Ptr raw(new typename pcl::PointCloud<PointTIn>);
53  pcl::fromROSMsg(msg, *raw);
54  if (raw->points.size() == 0)
55  {
56  ROS_ERROR("Given PointCloud2 is empty");
57  return false;
58  }
59  pcl::copyPointCloud(*raw, pc);
60  return true;
61 }
62 } // namespace
63 
64 template <typename PointT>
66  const sensor_msgs::PointCloud2& msg, pcl::PointCloud<PointT>& pc)
67 {
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");
73 
74  if (x_idx == -1 || y_idx == -1 || z_idx == -1)
75  {
76  ROS_ERROR("Given PointCloud2 doesn't have x, y, z fields");
77  return false;
78  }
79  if (intensity_idx != -1)
80  {
81  if (label_idx != -1)
82  {
83  return fromROSMsgImpl<mcl_3dl::PointXYZIL, PointT>(msg, pc);
84  }
85  return fromROSMsgImpl<pcl::PointXYZI, PointT>(msg, pc);
86  }
87  if (label_idx != -1)
88  {
89  return fromROSMsgImpl<pcl::PointXYZL, PointT>(msg, pc);
90  }
91  return fromROSMsgImpl<pcl::PointXYZ, PointT>(msg, pc);
92 }
93 } // namespace mcl_3dl
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)
#define ROS_ERROR(...)


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:16:29