1 #include <gtest/gtest.h> 13 template <
typename T,
typename TT>
25 EXPECT_TRUE(errsWrite.empty());
26 EXPECT_TRUE(errsLoad.empty());
27 auto& valueLayer = llmap.*layer;
28 EXPECT_EQ(1ul, valueLayer.size());
32 TEST(OsmHandler, writeAndLoadMapWithOneLanelet) {
39 EXPECT_EQ(llt.
inverted(), lltLoad.inverted());
40 EXPECT_EQ(*llt.
constData(), *lltLoad.constData());
48 TEST(OsmHandler, writeAndLoadMapWithCenterlineLanelet) {
54 EXPECT_EQ(lltLoad.centerline().constData(), centerline.
constData());
55 EXPECT_EQ(lltLoad.centerline().inverted(), centerline.
inverted());
58 TEST(OsmHandler, writeAndLoadMapWithPolygon) {
62 EXPECT_EQ(poly.id(), polyLoad.id());
65 TEST(OsmHandler, writeAndLoadMapWithOneArea) {
66 auto map = std::make_unique<lanelet::LaneletMap>();
73 EXPECT_EQ(*ar.constData(), *arLoad.constData());
81 TEST(OsmHandler, writeAndLoadMapWithRegElem) {
82 auto map = std::make_unique<lanelet::LaneletMap>();
86 EXPECT_EQ(*regElem->constData(), *rLoad->constData());
89 TEST(OsmHandler, writeMapWithIncompleteRegelem) {
96 EXPECT_GT(errsWrite.size(), 0ul);
99 TEST(OsmHandler, writeMapWithIncompleteLanelet) {
106 EXPECT_GT(errsWrite.size(), 0ul);
109 TEST(OsmHandler, writeMapWithLaneletAndAreaToFile) {
110 auto map = std::make_unique<lanelet::LaneletMap>();
117 Origin origin({49, 8.4, 0});
118 write(file.
get().string(), *map, origin);
119 EXPECT_NO_THROW(
load(file.
get().string(), origin));
Writer class for osm files.
T writeAndLoad(const T &value, TT(LaneletMapLayers::*layer))
std::vector< std::string > ErrorMessages
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
void addRegulatoryElement(RegulatoryElementPtr regElem)
Lanelet setUpLanelet(int &num, const std::string &type=AttributeValueString::Road)
Parser class for osm files.
std::unique_ptr< LaneletMap > fromOsmFile(const osm::File &file, ErrorMessages &errors) const
LineString3d setUpLineString(int &num, const std::string &type=AttributeValueString::Curbstone)
void setCenterline(const LineString3d ¢erline)
RegulatoryElementPtr setUpRegulatoryElement(int &num)
void add(Lanelet lanelet)
const std::shared_ptr< const LaneletData > & constData() const
LaneletLayer laneletLayer
RegulatoryElementLayer regulatoryElementLayer
std::unique_ptr< LaneletMap > load(const std::string &filename, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration ¶ms=io::Configuration())
Loads a lanelet map from a file.
void write(const std::string &filename, const lanelet::LaneletMap &map, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration ¶ms=io::Configuration())
writes a map to a file
RegulatoryElementPtr setUpGenericRegulatoryElement(int &num)
const fs::path & get() const
Area setUpArea(int &num, const std::string &type=AttributeValueString::Parking)
DefaultProjector defaultProjection(Origin origin=Origin::defaultOrigin())
bool inverted() const noexcept
LineString3d invert() const noexcept
static RegisterRegulatoryElement< GenericRegulatoryElement > genRegelem
PolygonLayer polygonLayer
ConstRuleParameterMap getParameters() const
TEST(OsmHandler, writeAndLoadMapWithOneLanelet)
std::unique_ptr< osm::File > toOsmFile(const LaneletMap &laneletMap, ErrorMessages &errors, const io::Configuration ¶ms=io::Configuration()) const