TestOsmHandler.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
4 
5 #include <cstdio>
6 
7 #include "TestSetup.h"
8 #include "lanelet2_io/Io.h"
10 
11 using namespace lanelet;
12 
13 template <typename T, typename TT>
14 T writeAndLoad(const T& value, TT(LaneletMapLayers::*layer)) {
15  LaneletMap llmap;
16  llmap.add(value);
17 
18  ErrorMessages errsWrite;
19  ErrorMessages errsLoad;
20  auto projector = defaultProjection(Origin({0, 0, 0}));
21  io_handlers::OsmParser parser(projector);
22  io_handlers::OsmWriter writer(projector);
23  auto file = writer.toOsmFile(llmap, errsWrite);
24  auto loadedMap = parser.fromOsmFile(*file, errsLoad);
25  EXPECT_TRUE(errsWrite.empty());
26  EXPECT_TRUE(errsLoad.empty());
27  auto& valueLayer = llmap.*layer;
28  EXPECT_EQ(1ul, valueLayer.size());
29  return valueLayer.get(utils::getId(value));
30 }
31 
32 TEST(OsmHandler, writeAndLoadMapWithOneLanelet) { // NOLINT
33  auto num = 1;
36  std::dynamic_pointer_cast<lanelet::GenericRegulatoryElement>(genRegelem)->addParameter("lanelet", llt);
38  auto lltLoad = writeAndLoad(llt, &LaneletMap::laneletLayer);
39  EXPECT_EQ(llt.inverted(), lltLoad.inverted());
40  EXPECT_EQ(*llt.constData(), *lltLoad.constData());
41  EXPECT_EQ(lltLoad.regulatoryElementsAs<GenericRegulatoryElement>()
42  .front()
44  .front(),
45  lltLoad);
46 }
47 
48 TEST(OsmHandler, writeAndLoadMapWithCenterlineLanelet) { // NOLINT
49  auto num = 1;
52  llt.setCenterline(centerline);
53  auto lltLoad = writeAndLoad(llt, &LaneletMap::laneletLayer);
54  EXPECT_EQ(lltLoad.centerline().constData(), centerline.constData());
55  EXPECT_EQ(lltLoad.centerline().inverted(), centerline.inverted());
56 }
57 
58 TEST(OsmHandler, writeAndLoadMapWithPolygon) { // NOLINT
59  auto num = 1;
61  auto polyLoad = writeAndLoad(poly, &LaneletMap::polygonLayer);
62  EXPECT_EQ(poly.id(), polyLoad.id());
63 }
64 
65 TEST(OsmHandler, writeAndLoadMapWithOneArea) { // NOLINT
66  auto map = std::make_unique<lanelet::LaneletMap>();
67  auto num = 1;
68  auto ar = test_setup::setUpArea(num);
70  std::dynamic_pointer_cast<lanelet::GenericRegulatoryElement>(genRegelem)->addParameter("area", ar);
71  ar.addRegulatoryElement(genRegelem);
72  auto arLoad = writeAndLoad(ar, &LaneletMap::areaLayer);
73  EXPECT_EQ(*ar.constData(), *arLoad.constData());
74  EXPECT_EQ(arLoad.regulatoryElementsAs<GenericRegulatoryElement>()
75  .front()
77  .front(),
78  arLoad);
79 }
80 
81 TEST(OsmHandler, writeAndLoadMapWithRegElem) { // NOLINT
82  auto map = std::make_unique<lanelet::LaneletMap>();
83  auto num = 1;
84  auto regElem = test_setup::setUpRegulatoryElement(num);
86  EXPECT_EQ(*regElem->constData(), *rLoad->constData());
87 }
88 
89 TEST(OsmHandler, writeMapWithIncompleteRegelem) { // NOLINT
90  auto num = 1;
91  auto regElem = test_setup::setUpRegulatoryElement(num);
92  lanelet::LaneletMap map({}, {}, {{regElem->id(), regElem}}, {}, {}, {});
93  ErrorMessages errsWrite;
94  auto projector = defaultProjection(Origin({0, 0, 0}));
95  auto file = io_handlers::OsmWriter(projector).toOsmFile(map, errsWrite);
96  EXPECT_GT(errsWrite.size(), 0ul);
97 }
98 
99 TEST(OsmHandler, writeMapWithIncompleteLanelet) { // NOLINT
100  auto num = 1;
101  auto llt = test_setup::setUpLanelet(num);
102  lanelet::LaneletMap map({{llt.id(), llt}}, {}, {}, {}, {}, {});
103  ErrorMessages errsWrite;
104  auto projector = defaultProjection(Origin({0, 0, 0}));
105  auto file = io_handlers::OsmWriter(projector).toOsmFile(map, errsWrite);
106  EXPECT_GT(errsWrite.size(), 0ul);
107 }
108 
109 TEST(OsmHandler, writeMapWithLaneletAndAreaToFile) { // NOLINT
110  auto map = std::make_unique<lanelet::LaneletMap>();
111  auto num = 1;
112  auto ar = test_setup::setUpArea(num);
113  auto ll = test_setup::setUpLanelet(num);
114  map->add(ar);
115  map->add(ll);
117  Origin origin({49, 8.4, 0});
118  write(file.get().string(), *map, origin);
119  EXPECT_NO_THROW(load(file.get().string(), origin)); // NOLINT
120 }
lanelet::LaneletMapLayers::laneletLayer
LaneletLayer laneletLayer
lanelet::ErrorMessages
std::vector< std::string > ErrorMessages
Definition: Io.h:11
TestSetup.h
lanelet::GenericRegulatoryElement
lanelet::test_setup::Tempfile
Definition: TestSetup.h:124
LaneletMap.h
lanelet::LaneletMapLayers::areaLayer
AreaLayer areaLayer
lanelet
lanelet::RegulatoryElementPtr
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
lanelet::io_handlers::OsmWriter::toOsmFile
std::unique_ptr< osm::File > toOsmFile(const LaneletMap &laneletMap, ErrorMessages &errors, const io::Configuration &params=io::Configuration()) const
Definition: OsmHandlerWrite.cpp:309
lanelet::ConstArea
file
osm::File & file
Definition: OsmHandlerWrite.cpp:245
lanelet::LaneletMap::add
void add(Area area)
lanelet::Lanelet::setCenterline
void setCenterline(const LineString3d &centerline)
lanelet::ConstLanelet::inverted
bool inverted() const
lanelet::utils::getId
Id getId()
lanelet::io_handlers::OsmWriter
Writer class for osm files.
Definition: OsmHandler.h:11
lanelet::LaneletMapLayers::polygonLayer
PolygonLayer polygonLayer
lanelet::io_handlers::OsmParser
Parser class for osm files.
Definition: OsmHandler.h:34
Io.h
ConstLineStringImpl< Point3d >::inverted
bool inverted() const noexcept
lanelet::LaneletMapLayers::regulatoryElementLayer
RegulatoryElementLayer regulatoryElementLayer
OsmHandler.h
BasicRegulatoryElements.h
lanelet::RegulatoryElement::getParameters
ConstRuleParameterMap getParameters() const
ConstPrimitive< LaneletData >::constData
const std::shared_ptr< const LaneletData > & constData() const
lanelet::test_setup::setUpLanelet
Lanelet setUpLanelet(int &num, const std::string &type=AttributeValueString::Road)
Definition: TestSetup.h:90
lanelet::LaneletMap
lanelet::Lanelet
lanelet::io_handlers::OsmParser::fromOsmFile
std::unique_ptr< LaneletMap > fromOsmFile(const osm::File &file, ErrorMessages &errors) const
Definition: OsmHandlerLoad.cpp:441
lanelet::LineString3d::invert
LineString3d invert() const noexcept
lanelet::load
std::unique_ptr< LaneletMap > load(const std::string &filename, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
Loads a lanelet map from a file.
Definition: Io.cpp:24
TEST
TEST(OsmHandler, writeAndLoadMapWithOneLanelet)
Definition: TestOsmHandler.cpp:32
lanelet::Origin
Definition: Projection.h:11
lanelet::test_setup::setUpGenericRegulatoryElement
RegulatoryElementPtr setUpGenericRegulatoryElement(int &num)
Definition: TestSetup.h:86
lanelet::test_setup::setUpArea
Area setUpArea(int &num, const std::string &type=AttributeValueString::Parking)
Definition: TestSetup.h:98
lanelet::Lanelet::addRegulatoryElement
void addRegulatoryElement(RegulatoryElementPtr regElem)
lanelet::LaneletMapLayers
lanelet::write
void write(const std::string &filename, const lanelet::LaneletMap &map, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
writes a map to a file
Definition: Io.cpp:61
lanelet::defaultProjection
DefaultProjector defaultProjection(Origin origin=Origin::defaultOrigin())
Definition: Projection.h:78
lanelet::genRegelem
static RegisterRegulatoryElement< GenericRegulatoryElement > genRegelem
lanelet::Polygon3d
lanelet::ConstLanelet
lanelet::test_setup::setUpRegulatoryElement
RegulatoryElementPtr setUpRegulatoryElement(int &num)
Definition: TestSetup.h:80
writeAndLoad
T writeAndLoad(const T &value, TT(LaneletMapLayers::*layer))
Definition: TestOsmHandler.cpp:14
lanelet::LineString3d
writer
ToFileWriter & writer
Definition: OsmHandlerWrite.cpp:246
lanelet::test_setup::setUpLineString
LineString3d setUpLineString(int &num, const std::string &type=AttributeValueString::Curbstone)
Definition: TestSetup.h:75


lanelet2_io
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:03