Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <pcl/point_types.h>
00031 #include <pcl_ros/point_cloud.h>
00032
00033 #include <mcl_3dl/point_cloud_random_sampler.h>
00034
00035 #include <gtest/gtest.h>
00036
00037 TEST(PointCloudRandomSampler, Sampling)
00038 {
00039 pcl::PointCloud<pcl::PointXYZ>::Ptr pc_input(new pcl::PointCloud<pcl::PointXYZ>);
00040 pc_input->width = 1;
00041 pc_input->height = 0;
00042 pc_input->header.frame_id = "frame0";
00043 pc_input->header.stamp = 12345;
00044
00045 const float points_ref[][3] =
00046 {
00047 { 10, 11, 12 },
00048 { 20, 21, 22 },
00049 { 30, 31, 32 }
00050 };
00051 for (const auto& p_ref : points_ref)
00052 {
00053 pc_input->push_back(pcl::PointXYZ(p_ref[0], p_ref[1], p_ref[2]));
00054 }
00055
00056 mcl_3dl::PointCloudRandomSampler sampler;
00057
00058 for (size_t num = 1; num < 4; num++)
00059 {
00060 pcl::PointCloud<pcl::PointXYZ>::Ptr pc_output = sampler.sample<pcl::PointXYZ>(pc_input, num);
00061
00062
00063 ASSERT_EQ(pc_output->header.frame_id, pc_input->header.frame_id);
00064 ASSERT_EQ(pc_output->header.stamp, pc_input->header.stamp);
00065 ASSERT_EQ(pc_output->height, 1u);
00066 ASSERT_EQ(pc_output->width, num);
00067
00068
00069 for (const pcl::PointXYZ& p : *pc_output)
00070 {
00071 bool found = false;
00072 for (const auto& p_ref : points_ref)
00073 {
00074 if (p_ref[0] == p.x && p_ref[1] == p.y && p_ref[2] == p.z)
00075 {
00076 found = true;
00077 break;
00078 }
00079 }
00080 ASSERT_TRUE(found) << "A sampled point is not in the original points array";
00081 }
00082 }
00083
00084
00085 pcl::PointCloud<pcl::PointXYZ>::Ptr pc_output0 = sampler.sample<pcl::PointXYZ>(pc_input, 0);
00086 ASSERT_EQ(pc_output0->points.size(), 0u);
00087 }
00088
00089 int main(int argc, char** argv)
00090 {
00091 testing::InitGoogleTest(&argc, argv);
00092
00093 return RUN_ALL_TESTS();
00094 }