line_tests.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2018, Locus Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 #include <gtest/gtest.h>
00035 #include <nav_grid_iterators/line/bresenham.h>
00036 #include <nav_grid_iterators/line/ray_trace.h>
00037 
00038 template<class iterator_type>
00039 int countIterations(iterator_type it, int max_iterations = 1000)
00040 {
00041   int count = 0;
00042   iterator_type end = it.end();
00043   for ( ; it != end; ++it)
00044   {
00045     ++count;
00046     if (count >= max_iterations) break;
00047   }
00048   return count;
00049 }
00050 
00051 TEST(Lines, line)
00052 {
00053   for (int i = 0; i <= 1; i++)
00054   {
00055     bool include_last_point = i == 0;
00056     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, 0, 0, include_last_point)), 1 - i);
00057     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, 3, 0, include_last_point)), 4 - i);
00058     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, -3, 0, include_last_point)), 4 - i);
00059     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(3, 0, 0, 0, include_last_point)), 4 - i);
00060     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(-3, 0, 0, 0, include_last_point)), 4 - i);
00061     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, 0, 3, include_last_point)), 4 - i);
00062     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, 0, -3, include_last_point)), 4 - i);
00063     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 3, 0, 0, include_last_point)), 4 - i);
00064     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, -3, 0, 0, include_last_point)), 4 - i);
00065     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, 1, 9, include_last_point)), 10 - i);
00066     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, -1, -9, include_last_point)), 10 - i);
00067     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(1, 9, 0, 0, include_last_point)), 10 - i);
00068     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(-1, -9, 0, 0, include_last_point)), 10 - i);
00069     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(9, 1, 0, 0, include_last_point)), 10 - i);
00070     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, 9, 1, include_last_point)), 10 - i);
00071     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(-5, -5, 5, 5, include_last_point)), 11 - i);
00072     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(-5, 5, 15, 5, include_last_point)), 21 - i);
00073     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(15, 5, -5, 5, include_last_point)), 21 - i);
00074     EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(15, 5, 15, 7, include_last_point)), 3 - i);
00075 
00076     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, 0, 0, include_last_point)), 1 - i);
00077     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, 3, 0, include_last_point)), 4 - i);
00078     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, -3, 0, include_last_point)), 4 - i);
00079     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(3, 0, 0, 0, include_last_point)), 4 - i);
00080     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(-3, 0, 0, 0, include_last_point)), 4 - i);
00081     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, 0, 3, include_last_point)), 4 - i);
00082     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, 0, -3, include_last_point)), 4 - i);
00083     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 3, 0, 0, include_last_point)), 4 - i);
00084     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, -3, 0, 0, include_last_point)), 4 - i);
00085     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, 1, 9, include_last_point)), 11 - i);
00086     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, -1, -9, include_last_point)), 11 - i);
00087     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(1, 9, 0, 0, include_last_point)), 11 - i);
00088     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(-1, -9, 0, 0, include_last_point)), 11 - i);
00089     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(9, 1, 0, 0, include_last_point)), 11 - i);
00090     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, 9, 1, include_last_point)), 11 - i);
00091     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(-5, -5, 5, 5, include_last_point)), 21 - i);
00092     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(-5, 5, 15, 5, include_last_point)), 21 - i);
00093     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(15, 5, -5, 5, include_last_point)), 21 - i);
00094     EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(15, 5, 15, 7, include_last_point)), 3 - i);
00095   }
00096 }
00097 
00098 TEST(Lines, border_conditions)
00099 {
00100   int N = 100;
00101   int N2 = N / 2;
00102   for (int include_last_point = 0; include_last_point <= 1; ++include_last_point)
00103   {
00104     for (int i=0; i < N; ++i)
00105     {
00106       EXPECT_LT(countIterations(nav_grid_iterators::Bresenham(0, 0,  N2, i - N2, include_last_point)), N*3);
00107       EXPECT_LT(countIterations(nav_grid_iterators::Bresenham(0, 0, -N2, i - N2, include_last_point)), N*3);
00108       EXPECT_LT(countIterations(nav_grid_iterators::Bresenham(0, 0, i - N2,  N2, include_last_point)), N*3);
00109       EXPECT_LT(countIterations(nav_grid_iterators::Bresenham(0, 0, i - N2, -N2, include_last_point)), N*3);
00110       EXPECT_LT(countIterations(nav_grid_iterators::RayTrace(0, 0,  N2, i - N2, include_last_point)), N*3);
00111       EXPECT_LT(countIterations(nav_grid_iterators::RayTrace(0, 0, -N2, i - N2, include_last_point)), N*3);
00112       EXPECT_LT(countIterations(nav_grid_iterators::RayTrace(0, 0, i - N2,  N2, include_last_point)), N*3);
00113       EXPECT_LT(countIterations(nav_grid_iterators::RayTrace(0, 0, i - N2, -N2, include_last_point)), N*3);
00114     }
00115   }
00116 }
00117 
00118 TEST(Lines, equality)
00119 {
00120   nav_grid_iterators::Bresenham it1(0, 0, 5, 5);
00121   nav_grid_iterators::Bresenham it2(0, 0, 1, 1);
00122   ASSERT_FALSE(it1 == it2);
00123 }
00124 
00125 TEST(Lines, test_copy)
00126 {
00127   // This test will fail to compile if you cannot use the copy operator
00128   nav_grid_iterators::Bresenham bres(0, 0, 0, 0);
00129   bres = bres.begin();
00130   nav_grid_iterators::RayTrace rt(0, 0, 0, 0);
00131   rt = rt.begin();
00132 }
00133 
00134 int main(int argc, char **argv)
00135 {
00136   testing::InitGoogleTest(&argc, argv);
00137   return RUN_ALL_TESTS();
00138 }


nav_grid_iterators
Author(s):
autogenerated on Wed Jun 26 2019 20:09:45