OsmFile.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include <deque>
6 #include <map>
7 #include <pugixml.hpp>
8 #include <string>
9 #include <utility>
10 
12 
13 namespace lanelet {
14 namespace osm {
15 
16 struct Primitive;
17 using Attributes = std::map<std::string, std::string>;
18 using Role = std::pair<std::string, Primitive*>;
19 using Roles = std::deque<Role>; // need iterator validity on push_back
20 using Errors = std::vector<std::string>;
21 
23 struct Primitive {
24  Primitive() = default;
25  Primitive(Primitive&& rhs) noexcept = default; // NOLINT
26  Primitive& operator=(Primitive&& rhs) noexcept = default;
27  Primitive(const Primitive& rhs) = delete;
28  Primitive& operator=(const Primitive& rhs) = delete;
29  virtual ~Primitive() = default;
31  virtual std::string type() = 0;
32 
33  Id id{0};
35 };
36 
38 struct Node : public Primitive {
39  Node() = default;
41  std::string type() override { return "node"; }
43 };
44 
46 struct Way : public Primitive {
47  Way() = default;
48  Way(Id id, Attributes attributes, std::vector<Node*> nodes)
49  : Primitive{id, std::move(attributes)}, nodes{std::move(nodes)} {}
50  std::string type() override { return "way"; }
51  std::vector<Node*> nodes;
52 };
53 
55 struct Relation : public Primitive {
56  Relation() = default;
58  : Primitive{id, std::move(attributes)}, members{std::move(roles)} {}
59  std::string type() override { return "relation"; }
61 };
62 
63 using Nodes = std::map<Id, Node>;
64 using Ways = std::map<Id, Way>;
65 using Relations = std::map<Id, Relation>;
66 
72 struct File {
73  File() noexcept = default;
74  File(File&& rhs) noexcept = default; // NOLINT
75  File& operator=(File&& rhs) noexcept = default;
76  File(const File& rhs) = delete;
77  File& operator=(const File& rhs) = delete;
78  ~File() noexcept = default;
79 
83 };
84 
85 inline auto findRole(const Roles& roles, const std::string& roleName) {
86  return std::find_if(roles.begin(), roles.end(), [&](auto& role) { return roleName == role.first; });
87 }
88 
89 template <typename Func>
90 inline auto forEachMember(const Roles& roles, const std::string& roleName, Func&& f) {
91  std::for_each(roles.begin(), roles.end(), [&](auto& role) {
92  if (roleName == role.first) {
93  f(role);
94  };
95  });
96 }
97 
100 File read(pugi::xml_document& node, lanelet::osm::Errors* errors = nullptr);
101 
104 std::unique_ptr<pugi::xml_document> write(const File& file, const io::Configuration& params = io::Configuration());
105 
106 inline bool operator==(const Node& lhs, const Node& rhs) { return lhs.id == rhs.id; }
107 bool operator==(const Way& lhs, const Way& rhs);
108 bool operator==(const Relation& lhs, const Relation& rhs);
109 bool operator==(const File& lhs, const File& rhs);
110 } // namespace osm
111 } // namespace lanelet
lanelet::osm::Way::nodes
std::vector< Node * > nodes
Definition: OsmFile.h:51
lanelet::osm::Node::type
std::string type() override
Definition: OsmFile.h:41
lanelet
GPSPoint.h
lanelet::io::Configuration
std::map< std::string, Attribute > Configuration
Definition: Configuration.h:8
lanelet::osm::Way::Way
Way()=default
file
osm::File & file
Definition: OsmHandlerWrite.cpp:245
lanelet::osm::Relations
std::map< Id, Relation > Relations
Definition: OsmFile.h:65
lanelet::osm::Way::Way
Way(Id id, Attributes attributes, std::vector< Node * > nodes)
Definition: OsmFile.h:48
lanelet::osm::File::nodes
Nodes nodes
Definition: OsmFile.h:80
lanelet::operator==
bool operator==(const Attribute &lhs, const Attribute &rhs)
lanelet::osm::File::~File
~File() noexcept=default
lanelet::Id
int64_t Id
lanelet::osm::Primitive::type
virtual std::string type()=0
lanelet::osm::Relation::members
Roles members
Definition: OsmFile.h:60
Forward.h
lanelet::osm::Way::type
std::string type() override
Definition: OsmFile.h:50
lanelet::osm::Node::Node
Node(Id id, Attributes attributes, GPSPoint point)
Definition: OsmFile.h:40
lanelet::osm::Nodes
std::map< Id, Node > Nodes
Definition: OsmFile.h:63
lanelet::osm::Relation::Relation
Relation(Id id, Attributes attributes, Roles roles=Roles())
Definition: OsmFile.h:57
lanelet::osm::Relation
Osm relation object.
Definition: OsmFile.h:55
lanelet::osm::Primitive
Common abstract base class for all osm primitives. Provides id and attributes.
Definition: OsmFile.h:23
lanelet::osm::File::ways
Ways ways
Definition: OsmFile.h:81
lanelet::osm::read
File read(pugi::xml_document &node, lanelet::osm::Errors *errors=nullptr)
Definition: OsmFile.cpp:343
lanelet::osm::Ways
std::map< Id, Way > Ways
Definition: OsmFile.h:64
lanelet::osm::File
Intermediate representation of an osm file.
Definition: OsmFile.h:72
lanelet::osm::File::operator=
File & operator=(File &&rhs) noexcept=default
lanelet::osm::Role
std::pair< std::string, Primitive * > Role
Definition: OsmFile.h:18
lanelet::osm::Node
Osm node object.
Definition: OsmFile.h:38
lanelet::osm::Errors
std::vector< std::string > Errors
Definition: OsmFile.h:20
lanelet::osm::Node::point
GPSPoint point
Definition: OsmFile.h:42
lanelet::osm::Attributes
std::map< std::string, std::string > Attributes
Definition: OsmFile.h:17
lanelet::osm::Node::Node
Node()=default
lanelet::osm::Roles
std::deque< Role > Roles
Definition: OsmFile.h:19
lanelet::osm::forEachMember
auto forEachMember(const Roles &roles, const std::string &roleName, Func &&f)
Definition: OsmFile.h:90
lanelet::osm::Primitive::id
Id id
Definition: OsmFile.h:33
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::osm::File::relations
Relations relations
Definition: OsmFile.h:82
lanelet::osm::Primitive::operator=
Primitive & operator=(Primitive &&rhs) noexcept=default
lanelet::osm::Primitive::attributes
Attributes attributes
Definition: OsmFile.h:34
lanelet::osm::Way
Osm way object.
Definition: OsmFile.h:46
lanelet::osm::File::File
File() noexcept=default
lanelet::osm::Relation::Relation
Relation()=default
lanelet::osm::Primitive::Primitive
Primitive()=default
lanelet::osm::Primitive::Primitive
Primitive(Id id, Attributes attributes)
Definition: OsmFile.h:30
lanelet::osm::Relation::type
std::string type() override
Definition: OsmFile.h:59
lanelet::osm::Primitive::~Primitive
virtual ~Primitive()=default
Configuration.h
lanelet::osm::findRole
auto findRole(const Roles &roles, const std::string &roleName)
Definition: OsmFile.h:85
lanelet::GPSPoint


lanelet2_io
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:03