test_routing_visualization.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 
3 #include <boost/filesystem.hpp>
4 
7 #include "test_routing_map.h"
8 
9 using namespace lanelet;
10 using namespace lanelet::routing;
11 using namespace lanelet::routing::tests;
12 namespace fs = boost::filesystem;
13 
14 class Tempfile {
15  public:
17  char path[] = {"/tmp/lanelet2_unittest.XXXXXX"};
18  auto* res = mkdtemp(path);
19  if (res == nullptr) {
20  throw lanelet::LaneletError("Failed to crate temporary directory");
21  }
22  path_ = path;
23  }
24  Tempfile(const Tempfile&) = delete;
25  Tempfile(Tempfile&&) = delete;
26  Tempfile& operator=(const Tempfile&) = delete;
27  Tempfile& operator=(Tempfile&&) = delete;
28  ~Tempfile() { fs::remove_all(fs::path(path_)); }
29 
30  auto operator()(const std::string& str) const noexcept -> std::string { return (fs::path(path_) / str).string(); }
31 
32  private:
33  std::string path_;
34 };
35 
37 
38 TEST_F(GermanVehicleGraph, GraphVizExport) { // NOLINT
39  EXPECT_NO_THROW(graph->exportGraphViz(tempfile("graphexport.dot"))); // NOLINT
41  EXPECT_NO_THROW(graph->exportGraphViz(tempfile("graphexportWithExcluded1.dot"), excluded)); // NOLINT
42  excluded |= RelationType::AdjacentLeft;
43  excluded |= RelationType::AdjacentRight;
44  EXPECT_NO_THROW(graph->exportGraphViz(tempfile("graphexportWithExcluded2.dot"), excluded)); // NOLINT
45 }
46 
47 TEST_F(GermanVehicleGraph, GraphVizExportError) { // NOLINT
48  EXPECT_THROW(graph->exportGraphViz("", RelationType::None), lanelet::InvalidInputError); // NOLINT
49  EXPECT_THROW(graph->exportGraphViz("/place/that/doesnt/exist"), lanelet::ExportError); // NOLINT
50 }
51 
52 TEST_F(GermanVehicleGraph, GraphMLExport) { // NOLINT
53  EXPECT_NO_THROW(graph->exportGraphML(tempfile("graphexport.graphml"))); // NOLINT
55  EXPECT_NO_THROW(graph->exportGraphML(tempfile("graphexportWithExcluded1.graphml"), excluded)); // NOLINT
56  excluded |= RelationType::AdjacentLeft;
57  excluded |= RelationType::AdjacentLeft;
58  excluded |= RelationType::AdjacentRight;
59  EXPECT_NO_THROW(graph->exportGraphML(tempfile("graphexportWithExcluded2.graphml"), excluded)); // NOLINT
60 }
61 
62 TEST_F(GermanVehicleGraph, GraphMLExportError) { // NOLINT
63  EXPECT_THROW(graph->exportGraphML("", RelationType::None), lanelet::InvalidInputError); // NOLINT
64  EXPECT_THROW(graph->exportGraphML("/place/that/doesnt/exist", RelationType::None), lanelet::ExportError); // NOLINT
65 }
66 
67 TEST_F(GermanVehicleGraph, DebugLaneletMap) { // NOLINT
68  LaneletMapPtr map{graph->getDebugLaneletMap()};
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));
74 }
75 
76 TEST_F(GermanPedestrianGraph, DebugLaneletMap) { // NOLINT
77  LaneletMapPtr map{graph->getDebugLaneletMap()};
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));
82 }
83 
84 TEST_F(GermanBicycleGraph, DebugLaneletMap) { // NOLINT
85  LaneletMapPtr map{graph->getDebugLaneletMap()};
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));
91 }
92 
93 TYPED_TEST(AllGraphsTest, CheckDebugLaneletMap) {
94  ASSERT_NO_THROW(this->graph->getDebugLaneletMap()); // NOLINT
95  const LaneletMapPtr map{this->graph->getDebugLaneletMap()};
96  for (const auto& it : map->pointLayer) {
97  EXPECT_NO_THROW(it.attribute("id")); // NOLINT
98  }
99  for (const auto& it : map->lineStringLayer) {
100  EXPECT_NO_THROW(it.attribute("relation")); // NOLINT
101  }
102 }
RoutingGraph.h
LaneletMapPtr
std::shared_ptr< LaneletMap > LaneletMapPtr
lanelet
lanelet::routing::tests::GermanPedestrianGraph
Definition: test_routing_map.h:502
lanelet::routing::RelationType
RelationType
Definition: Forward.h:56
lanelet::routing::tests
Definition: test_routing_map.h:17
lanelet::routing
Definition: Forward.h:11
tempfile
static Tempfile tempfile
Definition: test_routing_visualization.cpp:36
lanelet::routing::tests::AllGraphsTest
Definition: test_routing_map.h:521
lanelet::routing::tests::GermanVehicleGraph
Definition: test_routing_map.h:493
lanelet::ExportError
Thrown when an export to the provided file(name) cannot be done.
Definition: Exceptions.h:11
Tempfile::~Tempfile
~Tempfile()
Definition: test_routing_visualization.cpp:28
Tempfile::operator()
auto operator()(const std::string &str) const noexcept -> std::string
Definition: test_routing_visualization.cpp:30
TEST_F
TEST_F(GermanVehicleGraph, GraphVizExport)
Definition: test_routing_visualization.cpp:38
Tempfile::Tempfile
Tempfile()
Definition: test_routing_visualization.cpp:16
lanelet::routing::RelationType::Conflicting
@ Conflicting
Unreachable but with overlapping shape.
lanelet::routing::tests::GermanBicycleGraph
Definition: test_routing_map.h:511
Tempfile
Definition: test_routing_visualization.cpp:14
lanelet::routing::RelationType::None
@ None
No relation.
lanelet::routing::RelationType::AdjacentLeft
@ AdjacentLeft
directly adjacent, unreachable left neighbor
TYPED_TEST
TYPED_TEST(AllGraphsTest, CheckDebugLaneletMap)
Definition: test_routing_visualization.cpp:93
lanelet::routing::RelationType::AdjacentRight
@ AdjacentRight
directly adjacent, unreachable right neighbor
lanelet::LaneletError
Tempfile::path_
std::string path_
Definition: test_routing_visualization.cpp:33
test_routing_map.h
Exceptions.h
lanelet::InvalidInputError


lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49