TestBinHandler.cpp
Go to the documentation of this file.
1 #include <boost/archive/binary_iarchive.hpp>
2 #include <boost/archive/binary_oarchive.hpp>
3 #include <cstdio>
4 #include <fstream>
5 
6 #include "TestSetup.h"
7 #include "gtest/gtest.h"
8 #include "lanelet2_io/Io.h"
10 
11 using namespace lanelet;
12 
13 struct MyStuff {
14  int i{};
15 };
16 
17 template <typename T>
18 T writeAndLoad(const T& t) {
19  std::stringstream ss;
20  boost::archive::binary_oarchive oa(ss);
21  oa << t;
22  T tout;
23  boost::archive::binary_iarchive ia(ss);
24  ia >> tout;
25  return tout;
26 }
27 
28 TEST(Serialize, Attribute) { // NOLINT
29  lanelet::AttributeMap am{{"key", "value"}, {"key1", "value1"}};
30  EXPECT_EQ(am, writeAndLoad(am));
31 }
32 
33 class SerializeTest : public ::testing::Test {
34  public:
35  int id{0};
36  lanelet::AttributeMap attr{{"key", "value"}};
45 };
46 
47 TEST_F(SerializeTest, Point) { // NOLINT
48  auto pLoad = writeAndLoad(p1);
49  EXPECT_EQ(*p1.constData(), *pLoad.constData());
50 }
51 
52 TEST_F(SerializeTest, Regelem) { // NOLINT
53  auto rLoad = writeAndLoad(lanelet::RegulatoryElementPtr(regelem));
54  EXPECT_EQ(*regelem->constData(), *rLoad->constData());
55 }
56 
58  std::dynamic_pointer_cast<lanelet::GenericRegulatoryElement>(genericRegelem)->addParameter("lanelet", llt);
59  llt.addRegulatoryElement(genericRegelem);
60  auto lltLoad = writeAndLoad(llt);
61  EXPECT_EQ(llt.inverted(), lltLoad.inverted());
62  EXPECT_EQ(*llt.constData(), *lltLoad.constData());
63  EXPECT_EQ(lltLoad.regulatoryElementsAs<GenericRegulatoryElement>()
64  .front()
66  .front(),
67  lltLoad);
68 }
69 
70 TEST(OsmHandler, LaneletWithCenterline) { // NOLINT
71  auto num = 1;
74  llt.setCenterline(centerline);
75  auto lltLoad = writeAndLoad(llt);
76  EXPECT_TRUE(lltLoad.hasCustomCenterline());
77  EXPECT_TRUE(*lltLoad.centerline().constData() == *centerline.constData());
78  EXPECT_EQ(lltLoad.centerline().inverted(), centerline.inverted());
79 }
80 
81 TEST_F(SerializeTest, Area) { // NOLINT
82  std::dynamic_pointer_cast<lanelet::GenericRegulatoryElement>(genericRegelem)->addParameter("area", ar);
83  ar.addRegulatoryElement(genericRegelem);
84  auto arLoad = writeAndLoad(ar);
85  EXPECT_EQ(*ar.constData(), *arLoad.constData());
86  EXPECT_EQ(arLoad.regulatoryElementsAs<GenericRegulatoryElement>()
87  .front()
89  .front(),
90  arLoad);
91 }
92 
94  std::dynamic_pointer_cast<lanelet::GenericRegulatoryElement>(genericRegelem)->addParameter("lanelet", llt);
95  auto map = lanelet::utils::createMap({llt});
96  auto mapLoad = writeAndLoad(*map);
97  EXPECT_EQ(*map, mapLoad);
98 }
99 
100 TEST(BinHandler, extension) { // NOLINT
101  lanelet::test_setup::Tempfile t("file.bin");
102  auto map = std::make_shared<lanelet::LaneletMap>();
103  lanelet::write(t.get().string(), *map);
104 
105  auto mapLoad = lanelet::load(t.get().string());
106 }
107 
108 TEST(BinHandler, explicitIO) { // NOLINT
109  lanelet::test_setup::Tempfile t("file.bin");
110  auto map = std::make_shared<lanelet::LaneletMap>();
111  lanelet::write(t.get().string(), *map, "bin_handler");
112 
113  auto mapLoad = lanelet::load(t.get().string(), "bin_handler");
114 }
115 
116 TEST(BinHandler, fullMap) {
117  Origin origin({49, 8.4, 0});
118  std::string filenameIn = "../../lanelet2_maps/res/mapping_example.osm";
119  auto map = lanelet::load(filenameIn, origin);
120  auto llt = map->laneletLayer.find(44968);
121  writeAndLoad(*llt);
122 }
lanelet::Attribute
MyStuff
Definition: TestBinHandler.cpp:13
TestSetup.h
lanelet::GenericRegulatoryElement
lanelet::test_setup::Tempfile
Definition: TestSetup.h:124
lanelet
lanelet::utils::createMap
LaneletMapUPtr createMap(const Areas &fromAreas)
lanelet::RegulatoryElementPtr
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
lanelet::ConstArea
p2
BasicPoint p2
lanelet::Lanelet::setCenterline
void setCenterline(const LineString3d &centerline)
lanelet::test_setup::Tempfile::get
const fs::path & get() const
Definition: TestSetup.h:141
Io.h
ConstLineStringImpl< Point3d >::inverted
bool inverted() const noexcept
SerializeTest
Definition: TestBinHandler.cpp:33
writeAndLoad
T writeAndLoad(const T &t)
Definition: TestBinHandler.cpp:18
Serialize.h
lanelet::Area
lanelet::RegulatoryElement::getParameters
ConstRuleParameterMap getParameters() const
ConstPrimitive< LineStringData >::constData
const std::shared_ptr< const LineStringData > & 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::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
p1
BasicPoint p1
lanelet::Origin
Definition: Projection.h:11
lanelet::test_setup::setUpGenericRegulatoryElement
RegulatoryElementPtr setUpGenericRegulatoryElement(int &num)
Definition: TestSetup.h:86
TEST_F
TEST_F(SerializeTest, Point)
Definition: TestBinHandler.cpp:47
lanelet::test_setup::setUpArea
Area setUpArea(int &num, const std::string &type=AttributeValueString::Parking)
Definition: TestSetup.h:98
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::Point3d
lanelet::test_setup::setUpPoint
Point3d setUpPoint(int &num, int xOffset=0, const std::string &type=AttributeValueString::Start)
Definition: TestSetup.h:71
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map >
lanelet::ConstLanelet
TEST
TEST(Serialize, Attribute)
Definition: TestBinHandler.cpp:28
lanelet::test_setup::setUpRegulatoryElement
RegulatoryElementPtr setUpRegulatoryElement(int &num)
Definition: TestSetup.h:80
lanelet::LineString3d
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