test_point_cloud_random_sampler.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 <pcl/point_types.h>
31 #include <pcl_ros/point_cloud.h>
32 
34 
35 #include <gtest/gtest.h>
36 
37 TEST(PointCloudRandomSampler, Sampling)
38 {
39  pcl::PointCloud<pcl::PointXYZ>::Ptr pc_input(new pcl::PointCloud<pcl::PointXYZ>);
40  pc_input->width = 1;
41  pc_input->height = 0;
42  pc_input->header.frame_id = "frame0";
43  pc_input->header.stamp = 12345;
44 
45  const float points_ref[][3] =
46  {
47  { 10, 11, 12 },
48  { 20, 21, 22 },
49  { 30, 31, 32 }
50  };
51  for (const auto& p_ref : points_ref)
52  {
53  pc_input->push_back(pcl::PointXYZ(p_ref[0], p_ref[1], p_ref[2]));
54  }
55 
57 
58  for (size_t num = 1; num < 4; num++)
59  {
60  pcl::PointCloud<pcl::PointXYZ>::Ptr pc_output = sampler.sample<pcl::PointXYZ>(pc_input, num);
61 
62  // Check header and number of the points
63  ASSERT_EQ(pc_output->header.frame_id, pc_input->header.frame_id);
64  ASSERT_EQ(pc_output->header.stamp, pc_input->header.stamp);
65  ASSERT_EQ(pc_output->height, 1u);
66  ASSERT_EQ(pc_output->width, num);
67 
68  // Check that the all sampled points are in the original point array
69  for (const pcl::PointXYZ& p : *pc_output)
70  {
71  bool found = false;
72  for (const auto& p_ref : points_ref)
73  {
74  if (p_ref[0] == p.x && p_ref[1] == p.y && p_ref[2] == p.z)
75  {
76  found = true;
77  break;
78  }
79  }
80  ASSERT_TRUE(found) << "A sampled point is not in the original points array";
81  }
82  }
83 
84  // Make sure that the sampler returns 0 point output for 0 point input
85  pcl::PointCloud<pcl::PointXYZ>::Ptr pc_output0 = sampler.sample<pcl::PointXYZ>(pc_input, 0);
86  ASSERT_EQ(pc_output0->points.size(), 0u);
87 }
88 
89 int main(int argc, char** argv)
90 {
91  testing::InitGoogleTest(&argc, argv);
92 
93  return RUN_ALL_TESTS();
94 }
TEST(PointCloudRandomSampler, Sampling)
int main(int argc, char **argv)
pcl::PointCloud< POINT_TYPE >::Ptr sample(const typename pcl::PointCloud< POINT_TYPE >::ConstPtr &pc, const size_t num) const


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