compressed_point_cloud_test.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/sensor/compressed_point_cloud.h"
00018 
00019 #include "gmock/gmock.h"
00020 
00021 namespace Eigen {
00022 
00023 // Prints Vector3f in a readable format in matcher ApproximatelyEquals when
00024 // failing a test. Without this function, the output is formated as hexadecimal
00025 // 8 bit numbers.
00026 void PrintTo(const Vector3f& x, std::ostream* os) {
00027   *os << "(" << x[0] << ", " << x[1] << ", " << x[2] << ")";
00028 }
00029 
00030 }  // namespace Eigen
00031 
00032 namespace cartographer {
00033 namespace sensor {
00034 namespace {
00035 
00036 using ::testing::Contains;
00037 using ::testing::FloatNear;
00038 using ::testing::PrintToString;
00039 
00040 constexpr float kPrecision = 0.001f;
00041 
00042 // Matcher for 3-d vectors w.r.t. to the target precision.
00043 MATCHER_P(ApproximatelyEquals, expected,
00044           std::string("is equal to ") + PrintToString(expected)) {
00045   return (arg.position - expected).isZero(kPrecision);
00046 }
00047 
00048 // Helper function to test the mapping of a single point. Includes test for
00049 // recompressing the same point again.
00050 void TestPoint(const Eigen::Vector3f& p) {
00051   CompressedPointCloud compressed({{p}});
00052   EXPECT_EQ(1, compressed.size());
00053   EXPECT_THAT(*compressed.begin(), ApproximatelyEquals(p));
00054   CompressedPointCloud recompressed({*compressed.begin()});
00055   EXPECT_THAT(*recompressed.begin(), ApproximatelyEquals(p));
00056 }
00057 
00058 TEST(CompressPointCloudTest, CompressesPointsCorrectly) {
00059   TestPoint(Eigen::Vector3f(8000.f, 7500.f, 5000.f));
00060   TestPoint(Eigen::Vector3f(1000.f, 2000.f, 3000.f));
00061   TestPoint(Eigen::Vector3f(100.f, 200.f, 300.f));
00062   TestPoint(Eigen::Vector3f(10.f, 20.f, 30.f));
00063   TestPoint(Eigen::Vector3f(-0.00049f, -0.0005f, -0.0015f));
00064   TestPoint(Eigen::Vector3f(0.05119f, 0.0512f, 0.05121));
00065   TestPoint(Eigen::Vector3f(-0.05119f, -0.0512f, -0.05121));
00066   TestPoint(Eigen::Vector3f(0.8405f, 0.84f, 0.8396f));
00067   TestPoint(Eigen::Vector3f(0.8395f, 0.8394f, 0.8393f));
00068   TestPoint(Eigen::Vector3f(0.839f, 0.8391f, 0.8392f));
00069   TestPoint(Eigen::Vector3f(0.8389f, 0.8388f, 0.83985f));
00070 }
00071 
00072 TEST(CompressPointCloudTest, Compresses) {
00073   const CompressedPointCloud compressed({{Eigen::Vector3f(0.838f, 0, 0)},
00074                                          {Eigen::Vector3f(0.839f, 0, 0)},
00075                                          {Eigen::Vector3f(0.840f, 0, 0)}});
00076   EXPECT_FALSE(compressed.empty());
00077   EXPECT_EQ(3, compressed.size());
00078   const PointCloud decompressed = compressed.Decompress();
00079   EXPECT_EQ(3, decompressed.size());
00080   EXPECT_THAT(decompressed,
00081               Contains(ApproximatelyEquals(Eigen::Vector3f(0.838f, 0, 0))));
00082   EXPECT_THAT(decompressed,
00083               Contains(ApproximatelyEquals(Eigen::Vector3f(0.839f, 0, 0))));
00084   EXPECT_THAT(decompressed,
00085               Contains(ApproximatelyEquals(Eigen::Vector3f(0.840f, 0, 0))));
00086 }
00087 
00088 TEST(CompressPointCloudTest, CompressesEmptyPointCloud) {
00089   CompressedPointCloud compressed;
00090   EXPECT_TRUE(compressed.empty());
00091   EXPECT_EQ(0, compressed.size());
00092 }
00093 
00094 // Test for gaps.
00095 // Produces a series of points densly packed along the x axis, compresses these
00096 // points (twice), and tests, whether there are gaps between two consecutive
00097 // points.
00098 TEST(CompressPointCloudTest, CompressesNoGaps) {
00099   PointCloud point_cloud;
00100   for (int i = 0; i < 3000; ++i) {
00101     point_cloud.push_back({Eigen::Vector3f(kPrecision * i - 1.5f, 0, 0)});
00102   }
00103   const CompressedPointCloud compressed(point_cloud);
00104   const PointCloud decompressed = compressed.Decompress();
00105   const CompressedPointCloud recompressed(decompressed);
00106   EXPECT_EQ(decompressed.size(), recompressed.size());
00107 
00108   std::vector<float> x_coord;
00109   for (const RangefinderPoint& p : compressed) {
00110     x_coord.push_back(p.position[0]);
00111   }
00112   std::sort(x_coord.begin(), x_coord.end());
00113   for (size_t i = 1; i < x_coord.size(); ++i) {
00114     EXPECT_THAT(std::abs(x_coord[i] - x_coord[i - 1]),
00115                 FloatNear(kPrecision, 1e-7f));
00116   }
00117 }
00118 
00119 }  // namespace
00120 }  // namespace sensor
00121 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35