test_blockmem_gridmap_performance.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2017, the neonavigation authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <cstddef>
00031 
00032 #include <gtest/gtest.h>
00033 
00034 #include <planner_cspace/blockmem_gridmap.h>
00035 
00036 TEST(BlockmemGridmap, SpacialAccessPerformance)
00037 {
00038   constexpr int size[3] =
00039       {
00040         0x420, 0x420, 0x28
00041       };
00042   constexpr int pad[3] =
00043       {
00044         0x200, 0x200, 0x10
00045       };
00046   constexpr int range = 0x10;
00047 
00048   BlockMemGridmap<float, 3, 2, 0x20> gm;
00049   BlockMemGridmap<float, 3, 2, 0x20> gm_ret;
00050 
00051   using Vec = CyclicVecInt<3, 2>;
00052   using ThreeDimArrayFloat = std::array<std::array<std::array<float, size[0]>, size[1]>, size[2]>;
00053 
00054   std::shared_ptr<ThreeDimArrayFloat> array(new ThreeDimArrayFloat);
00055   std::shared_ptr<ThreeDimArrayFloat> array_ret(new ThreeDimArrayFloat);
00056 
00057   gm.reset(Vec(size));
00058   gm_ret.reset(Vec(size));
00059 
00060   Vec i;
00061   // Generate dataset.
00062   for (i[0] = 0; i[0] < size[0]; ++i[0])
00063   {
00064     for (i[1] = 0; i[1] < size[1]; ++i[1])
00065     {
00066       for (i[2] = 0; i[2] < size[2]; ++i[2])
00067       {
00068         gm[i] = i[2] * 0x100 + i[1] * 0x10 + i[0];
00069         (*array)[i[2]][i[1]][i[0]] = gm[i];
00070       }
00071     }
00072   }
00073   // Check dataset.
00074   for (i[0] = pad[0]; i[0] < size[0] - pad[0]; ++i[0])
00075   {
00076     for (i[1] = pad[1]; i[1] < size[1] - pad[1]; ++i[1])
00077     {
00078       for (i[2] = pad[2]; i[2] < size[2] - pad[2]; ++i[2])
00079       {
00080         ASSERT_EQ(gm[i], (*array)[i[2]][i[1]][i[0]]);
00081       }
00082     }
00083   }
00084 
00085   // Performance test for BlockMemGridmap.
00086   const auto ts0 = boost::chrono::high_resolution_clock::now();
00087   for (i[0] = pad[0]; i[0] < size[0] - pad[0]; ++i[0])
00088   {
00089     for (i[1] = pad[1]; i[1] < size[1] - pad[1]; ++i[1])
00090     {
00091       for (i[2] = pad[2]; i[2] < size[2] - pad[2]; ++i[2])
00092       {
00093         Vec j;
00094         gm_ret[i] = 0;
00095 
00096         for (j[0] = -range; j[0] <= range; ++j[0])
00097         {
00098           for (j[1] = -range; j[1] <= range; ++j[1])
00099           {
00100             for (j[2] = -range; j[2] <= range; ++j[2])
00101             {
00102               const Vec ij = i + j;
00103               gm_ret[i] += gm[ij];
00104             }
00105           }
00106         }
00107       }
00108     }
00109     std::cerr << ".";
00110   }
00111   std::cerr << std::endl;
00112   const auto te0 = boost::chrono::high_resolution_clock::now();
00113   std::cout << "BlockMemGridmap<3, 2>: " << boost::chrono::duration<float>(te0 - ts0).count() << std::endl;
00114 
00115   // Performance test for 3D Array.
00116   const auto ts1 = boost::chrono::high_resolution_clock::now();
00117   for (i[0] = pad[0]; i[0] < size[0] - pad[0]; ++i[0])
00118   {
00119     for (i[1] = pad[1]; i[1] < size[1] - pad[1]; ++i[1])
00120     {
00121       for (i[2] = pad[2]; i[2] < size[2] - pad[2]; ++i[2])
00122       {
00123         Vec j;
00124         (*array_ret)[i[2]][i[1]][i[0]] = 0;
00125 
00126         for (j[0] = -range; j[0] <= range; ++j[0])
00127         {
00128           for (j[1] = -range; j[1] <= range; ++j[1])
00129           {
00130             for (j[2] = -range; j[2] <= range; ++j[2])
00131             {
00132               const Vec ij = i + j;
00133               (*array_ret)[i[2]][i[1]][i[0]] += (*array)[ij[2]][ij[1]][ij[0]];
00134             }
00135           }
00136         }
00137       }
00138     }
00139     std::cerr << ".";
00140   }
00141   std::cerr << std::endl;
00142   const auto te1 = boost::chrono::high_resolution_clock::now();
00143   std::cout << "Array[][][]: " << boost::chrono::duration<float>(te1 - ts1).count() << std::endl;
00144 
00145   // Check result.
00146   for (i[0] = 0x200; i[0] < size[0] - 0x200; ++i[0])
00147   {
00148     for (i[1] = 0x200; i[1] < size[1] - 0x200; ++i[1])
00149     {
00150       for (i[2] = 0x10; i[2] < size[2] - 0x10; ++i[2])
00151       {
00152         ASSERT_EQ(gm_ret[i], (*array_ret)[i[2]][i[1]][i[0]]);
00153       }
00154     }
00155   }
00156 
00157   // Compare performance.
00158   ASSERT_LT(te0 - ts0, te1 - ts1);
00159 }
00160 
00161 int main(int argc, char** argv)
00162 {
00163   testing::InitGoogleTest(&argc, argv);
00164 
00165   return RUN_ALL_TESTS();
00166 }


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:27