1 #include <gtest/gtest.h>
3 #include <boost/filesystem.hpp>
12 namespace fs = boost::filesystem;
17 char path[] = {
"/tmp/lanelet2_unittest.XXXXXX"};
18 auto* res = mkdtemp(path);
30 auto operator()(
const std::string& str)
const noexcept -> std::string {
return (fs::path(path_) / str).string(); }
39 EXPECT_NO_THROW(graph->exportGraphViz(
tempfile(
"graphexport.dot")));
41 EXPECT_NO_THROW(graph->exportGraphViz(
tempfile(
"graphexportWithExcluded1.dot"), excluded));
44 EXPECT_NO_THROW(graph->exportGraphViz(
tempfile(
"graphexportWithExcluded2.dot"), excluded));
53 EXPECT_NO_THROW(graph->exportGraphML(
tempfile(
"graphexport.graphml")));
55 EXPECT_NO_THROW(graph->exportGraphML(
tempfile(
"graphexportWithExcluded1.graphml"), excluded));
59 EXPECT_NO_THROW(graph->exportGraphML(
tempfile(
"graphexportWithExcluded2.graphml"), excluded));
69 EXPECT_TRUE(map->pointLayer.exists(2007));
70 EXPECT_TRUE(map->pointLayer.exists(2020));
71 EXPECT_TRUE(map->pointLayer.exists(2032));
72 EXPECT_GT(map->lineStringLayer.size(), map->pointLayer.size());
73 EXPECT_FALSE(map->pointLayer.exists(2031));
78 EXPECT_FALSE(map->pointLayer.exists(2007));
79 EXPECT_FALSE(map->pointLayer.exists(2020));
80 EXPECT_FALSE(map->pointLayer.exists(2032));
81 EXPECT_TRUE(map->pointLayer.exists(2031));
86 EXPECT_TRUE(map->pointLayer.exists(2007));
87 EXPECT_TRUE(map->pointLayer.exists(2020));
88 EXPECT_TRUE(map->pointLayer.exists(2032));
89 EXPECT_FALSE(map->pointLayer.exists(2022));
90 EXPECT_FALSE(map->pointLayer.exists(2031));
94 ASSERT_NO_THROW(this->graph->getDebugLaneletMap());
96 for (
const auto& it : map->pointLayer) {
97 EXPECT_NO_THROW(it.attribute(
"id"));
99 for (
const auto& it : map->lineStringLayer) {
100 EXPECT_NO_THROW(it.attribute(
"relation"));