197 lines
4.6 KiB
C++
197 lines
4.6 KiB
C++
/*
|
|
* PolygonIteratorTest.cpp
|
|
*
|
|
* Created on: Sep 19, 2014
|
|
* Author: Péter Fankhauser
|
|
* Institute: ETH Zurich, ANYbotics
|
|
*/
|
|
|
|
#include "grid_map_core/iterators/PolygonIterator.hpp"
|
|
#include "grid_map_core/GridMap.hpp"
|
|
#include "grid_map_core/Polygon.hpp"
|
|
|
|
// gtest
|
|
#include <gtest/gtest.h>
|
|
|
|
// Vector
|
|
#include <vector>
|
|
|
|
using grid_map::GridMap;
|
|
using grid_map::Length;
|
|
using grid_map::Polygon;
|
|
using grid_map::PolygonIterator;
|
|
using grid_map::Position;
|
|
|
|
TEST(PolygonIterator, FullCover) {
|
|
std::vector<std::string> types;
|
|
types.emplace_back("type");
|
|
GridMap map(types);
|
|
map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)
|
|
|
|
Polygon polygon;
|
|
polygon.addVertex(Position(-100.0, 100.0));
|
|
polygon.addVertex(Position(100.0, 100.0));
|
|
polygon.addVertex(Position(100.0, -100.0));
|
|
polygon.addVertex(Position(-100.0, -100.0));
|
|
|
|
PolygonIterator iterator(map, polygon);
|
|
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(0, (*iterator)(0));
|
|
EXPECT_EQ(0, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(0, (*iterator)(0));
|
|
EXPECT_EQ(1, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(0, (*iterator)(0));
|
|
EXPECT_EQ(2, (*iterator)(1));
|
|
|
|
for (int i = 0; i < 37; ++i) {
|
|
++iterator;
|
|
}
|
|
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(7, (*iterator)(0));
|
|
EXPECT_EQ(4, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_TRUE(iterator.isPastEnd());
|
|
}
|
|
|
|
TEST(PolygonIterator, Outside)
|
|
{
|
|
GridMap map({"types"});
|
|
map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)
|
|
|
|
Polygon polygon;
|
|
polygon.addVertex(Position(99.0, 101.0));
|
|
polygon.addVertex(Position(101.0, 101.0));
|
|
polygon.addVertex(Position(101.0, 99.0));
|
|
polygon.addVertex(Position(99.0, 99.0));
|
|
|
|
PolygonIterator iterator(map, polygon);
|
|
|
|
EXPECT_TRUE(iterator.isPastEnd());
|
|
}
|
|
|
|
TEST(PolygonIterator, Square)
|
|
{
|
|
GridMap map({"types"});
|
|
map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)
|
|
|
|
Polygon polygon;
|
|
polygon.addVertex(Position(-1.0, 1.5));
|
|
polygon.addVertex(Position(1.0, 1.5));
|
|
polygon.addVertex(Position(1.0, -1.5));
|
|
polygon.addVertex(Position(-1.0, -1.5));
|
|
|
|
PolygonIterator iterator(map, polygon);
|
|
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(3, (*iterator)(0));
|
|
EXPECT_EQ(1, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(3, (*iterator)(0));
|
|
EXPECT_EQ(2, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(3, (*iterator)(0));
|
|
EXPECT_EQ(3, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(4, (*iterator)(0));
|
|
EXPECT_EQ(1, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(4, (*iterator)(0));
|
|
EXPECT_EQ(2, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(4, (*iterator)(0));
|
|
EXPECT_EQ(3, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_TRUE(iterator.isPastEnd());
|
|
}
|
|
|
|
TEST(PolygonIterator, TopLeftTriangle)
|
|
{
|
|
GridMap map({"types"});
|
|
map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)
|
|
|
|
Polygon polygon;
|
|
polygon.addVertex(Position(-40.1, 20.6));
|
|
polygon.addVertex(Position(40.1, 20.4));
|
|
polygon.addVertex(Position(-40.1, -20.6));
|
|
|
|
PolygonIterator iterator(map, polygon);
|
|
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(0, (*iterator)(0));
|
|
EXPECT_EQ(0, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(1, (*iterator)(0));
|
|
EXPECT_EQ(0, (*iterator)(1));
|
|
|
|
// TODO Extend.
|
|
}
|
|
|
|
TEST(PolygonIterator, MoveMap)
|
|
{
|
|
GridMap map({"layer"});
|
|
map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)
|
|
map.move(Position(2.0, 0.0));
|
|
|
|
Polygon polygon;
|
|
polygon.addVertex(Position(6.1, 1.6));
|
|
polygon.addVertex(Position(0.9, 1.6));
|
|
polygon.addVertex(Position(0.9, -1.6));
|
|
polygon.addVertex(Position(6.1, -1.6));
|
|
PolygonIterator iterator(map, polygon);
|
|
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(6, (*iterator)(0));
|
|
EXPECT_EQ(1, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(6, (*iterator)(0));
|
|
EXPECT_EQ(2, (*iterator)(1));
|
|
|
|
for (int i = 0; i < 4; ++i) {
|
|
++iterator;
|
|
}
|
|
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(7, (*iterator)(0));
|
|
EXPECT_EQ(3, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(0, (*iterator)(0));
|
|
EXPECT_EQ(1, (*iterator)(1));
|
|
|
|
for (int i = 0; i < 8; ++i) {
|
|
++iterator;
|
|
}
|
|
|
|
EXPECT_FALSE(iterator.isPastEnd());
|
|
EXPECT_EQ(2, (*iterator)(0));
|
|
EXPECT_EQ(3, (*iterator)(1));
|
|
|
|
++iterator;
|
|
EXPECT_TRUE(iterator.isPastEnd());
|
|
}
|