1 #include <boost/archive/binary_iarchive.hpp> 2 #include <boost/archive/binary_oarchive.hpp> 7 #include "gtest/gtest.h" 20 boost::archive::binary_oarchive oa(ss);
23 boost::archive::binary_iarchive ia(ss);
49 EXPECT_EQ(*
p1.constData(), *pLoad.constData());
54 EXPECT_EQ(*regelem->constData(), *rLoad->constData());
59 llt.addRegulatoryElement(genericRegelem);
61 EXPECT_EQ(llt.inverted(), lltLoad.inverted());
62 EXPECT_EQ(*llt.constData(), *lltLoad.constData());
70 TEST(OsmHandler, LaneletWithCenterline) {
76 EXPECT_TRUE(lltLoad.hasCustomCenterline());
77 EXPECT_TRUE(*lltLoad.centerline().constData() == *centerline.
constData());
78 EXPECT_EQ(lltLoad.centerline().inverted(), centerline.
inverted());
83 ar.addRegulatoryElement(genericRegelem);
85 EXPECT_EQ(*ar.constData(), *arLoad.constData());
97 EXPECT_EQ(*map, mapLoad);
102 auto map = std::make_shared<lanelet::LaneletMap>();
110 auto map = std::make_shared<lanelet::LaneletMap>();
117 Origin origin({49, 8.4, 0});
118 std::string filenameIn =
"../../lanelet2_maps/res/mapping_example.osm";
120 auto llt = map->laneletLayer.find(44968);
TEST_F(SerializeTest, Point)
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
Point3d setUpPoint(int &num, int xOffset=0, const std::string &type=AttributeValueString::Start)
Lanelet setUpLanelet(int &num, const std::string &type=AttributeValueString::Road)
T writeAndLoad(const T &t)
LineString3d setUpLineString(int &num, const std::string &type=AttributeValueString::Curbstone)
void setCenterline(const LineString3d ¢erline)
RegulatoryElementPtr setUpRegulatoryElement(int &num)
const std::shared_ptr< const LineStringData > & constData() const
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)
bool inverted() const noexcept
TEST(Serialize, Attribute)
LineString3d invert() const noexcept
LaneletMapUPtr createMap(const Points3d &fromPoints)
ConstRuleParameterMap getParameters() const