test_point_types.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, 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 #include <gtest/gtest.h>
31 
32 #include <pcl_ros/point_cloud.h>
33 #include <pcl/filters/voxel_grid.h>
34 
36 
37 #include <mcl_3dl/point_types.h>
38 
39 TEST(PointTypes, VoxelGrid)
40 {
41  pcl::PointCloud<mcl_3dl::PointXYZIL>::Ptr pc(new pcl::PointCloud<mcl_3dl::PointXYZIL>);
42  pc->resize(3);
43  pc->points[0].x = 1.0;
44  pc->points[0].y = 2.0;
45  pc->points[0].z = 3.0;
46  pc->points[0].intensity = 4.0;
47  pc->points[0].label = 1;
48  pc->points[1].x = 1.02;
49  pc->points[1].y = 2.02;
50  pc->points[1].z = 3.02;
51  pc->points[1].intensity = 5.0;
52  pc->points[1].label = 3;
53  pc->points[2].x = -1.0;
54  pc->points[2].y = -2.0;
55  pc->points[2].z = -3.0;
56  pc->points[2].intensity = 6.0;
57  pc->points[2].label = 4;
58 
59  pcl::PointCloud<mcl_3dl::PointXYZIL>::Ptr pc2(new pcl::PointCloud<mcl_3dl::PointXYZIL>);
61  ds.setInputCloud(pc);
62  ds.setLeafSize(0.1, 0.1, 0.1);
63  ds.filter(*pc2);
64 
65  ASSERT_EQ(pc2->size(), 2u);
66  int num_1(0), num_4(0);
67  for (auto &p : *pc2)
68  {
69  switch (p.label)
70  {
71  case 1u:
72  case 3u:
73  ASSERT_FLOAT_EQ(p.x, 1.01);
74  ASSERT_FLOAT_EQ(p.y, 2.01);
75  ASSERT_FLOAT_EQ(p.z, 3.01);
76  ASSERT_FLOAT_EQ(p.intensity, 4.5);
77  num_1++;
78  break;
79  case 4u:
80  ASSERT_EQ(p.x, -1.0);
81  ASSERT_EQ(p.y, -2.0);
82  ASSERT_EQ(p.z, -3.0);
83  ASSERT_EQ(p.intensity, 6.0);
84  num_4++;
85  break;
86  default:
87  ASSERT_TRUE(false)
88  << "Unexpected point label (" << p.label << "); "
89  << "original labels are [1, 3, 4]";
90  break;
91  }
92  }
93  ASSERT_TRUE(num_1 == 1 && num_4 == 1);
94 }
95 
96 int main(int argc, char **argv)
97 {
98  testing::InitGoogleTest(&argc, argv);
99 
100  return RUN_ALL_TESTS();
101 }
virtual void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
TEST(PointTypes, VoxelGrid)
int main(int argc, char **argv)


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36