34 #include <gtest/gtest.h> 41 template<
class iterator_type>
45 iterator_type end = it.end();
46 for ( ; it != end; ++it)
49 if (count >= max_iterations)
break;
54 TEST(WholeGrid, whole_grid)
63 ASSERT_EQ(i.x, count % info.
width);
64 ASSERT_EQ(i.y, count / info.
width);
70 TEST(WholeGrid, whole_grid_range)
78 ASSERT_EQ(i.x, count % info.
width);
79 ASSERT_EQ(i.y, count / info.
width);
92 std::vector<Index> vec;
93 std::copy(wg.
begin(), wg.
end(), std::back_inserter(vec));
94 for (
int count = 0; count < 16; ++count)
96 Index& i = vec[count];
97 ASSERT_EQ(i.x, count % info.
width);
98 ASSERT_EQ(i.y, count / info.
width);
110 ASSERT_EQ(i.x, static_cast<unsigned int>(1 + count % 2));
111 ASSERT_EQ(i.y, static_cast<unsigned int>(2 + count / 2));
147 ASSERT_FALSE(it1 == it2);
172 ASSERT_FALSE(it1 == it2);
175 TEST(CircleOutline, circle_outline)
182 unsigned int size = 0;
200 ASSERT_FALSE(it1 == it2);
225 ASSERT_FALSE(it1 == it2);
256 TEST(Line, signed_line_diff_res)
303 ASSERT_FALSE(it1 == it2);
308 nav_2d_msgs::Point2D pt;
321 nav_2d_msgs::Polygon2D simple_square;
322 simple_square.points.push_back(
make_point(1.4, 1.4));
323 simple_square.points.push_back(
make_point(1.4, 3.6));
324 simple_square.points.push_back(
make_point(3.6, 3.6));
325 simple_square.points.push_back(
make_point(3.6, 1.4));
347 nav_2d_msgs::Polygon2D empty_polygon;
359 nav_2d_msgs::Polygon2D simple_square;
360 simple_square.points.push_back(
make_point(1.4, 1.4));
361 simple_square.points.push_back(
make_point(1.4, 3.6));
362 simple_square.points.push_back(
make_point(3.6, 3.6));
363 simple_square.points.push_back(
make_point(3.6, 1.4));
365 nav_2d_msgs::Polygon2D triangle;
366 triangle.points.push_back(
make_point(1.4, 1.4));
367 triangle.points.push_back(
make_point(1.4, 3.6));
368 triangle.points.push_back(
make_point(3.6, 3.6));
373 ASSERT_FALSE(it1 == it2);
377 ASSERT_FALSE(it3 == it4);
388 nav_2d_msgs::Polygon2D simple_square;
389 simple_square.points.push_back(
make_point(1.4, 1.4));
390 simple_square.points.push_back(
make_point(1.4, 3.6));
391 simple_square.points.push_back(
make_point(3.6, 3.6));
392 simple_square.points.push_back(
make_point(3.6, 1.4));
395 whole_grid = whole_grid.
begin();
397 sub_grid = sub_grid.
begin();
403 spiral = spiral.
begin();
412 TEST(Iterators, test_assignment)
420 EXPECT_EQ((*iter1).x, 2U);
421 EXPECT_EQ((*iter1).y, 2U);
426 EXPECT_EQ((*iter1).x, 2U);
427 EXPECT_EQ((*iter1).y, 2U);
428 EXPECT_EQ((*iter2).x, 2U);
429 EXPECT_EQ((*iter2).y, 2U);
433 EXPECT_EQ((*iter1).x, 2U);
434 EXPECT_EQ((*iter1).y, 2U);
435 EXPECT_EQ((*iter2).x, 3U);
436 EXPECT_EQ((*iter2).y, 2U);
440 EXPECT_EQ((*iter1).x, 3U);
441 EXPECT_EQ((*iter1).y, 2U);
442 EXPECT_EQ((*iter2).x, 3U);
443 EXPECT_EQ((*iter2).y, 2U);
447 EXPECT_EQ((*iter1).x, 3U);
448 EXPECT_EQ((*iter1).y, 2U);
449 EXPECT_EQ((*iter2).x, 2U);
450 EXPECT_EQ((*iter2).y, 3U);
454 EXPECT_EQ((*iter1).x, 3U);
455 EXPECT_EQ((*iter1).y, 2U);
456 EXPECT_EQ((*iter2).x, 2U);
457 EXPECT_EQ((*iter2).y, 3U);
458 EXPECT_EQ((*iter3).x, 3U);
459 EXPECT_EQ((*iter3).y, 2U);
462 int main(
int argc,
char **argv)
464 testing::InitGoogleTest(&argc, argv);
465 return RUN_ALL_TESTS();
Line begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
int countIterations(iterator_type it, int max_iterations=1000)
WholeGrid begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
Iterates over all of the valid indexes on the outline of a polygon.
Iterates over all of the valid indexes that lie within a circle from the center out.
Iterates over all of the valid indexes that lie within a circle in row major order.
SubGrid begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
GenericIndex< unsigned int > Index
void touch(unsigned intx, unsigned inty)
int main(int argc, char **argv)
nav_2d_msgs::Point2D make_point(double x, double y)
Iterates over the valid indexes that lie on the outline of a circle.
WholeGrid end() const override
Helper function for range-style iteration.
CircleOutline begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
Iterates over all of the valid indexes of a line.
Iterates over all of the valid indexes that lie within an arbitrary polygon in row major order...
TEST(WholeGrid, whole_grid)
PolygonFill begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
Iterator for looping through every index within an aligned rectangular portion of the grid...
CircleFill begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
Spiral begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
PolygonOutline begin() const override
Helper function for range-style iteration Equivalent to the above constructor.