OsmFile.cpp
Go to the documentation of this file.
2 
4 
5 #include <boost/format.hpp>
6 #include <iostream>
7 
8 namespace lanelet {
9 namespace osm {
10 namespace {
11 using LongLong = long long; // NOLINT
12 
13 namespace keyword {
14 constexpr const char* Osm = "osm";
15 constexpr const char* Tag = "tag";
16 constexpr const char* Key = "k";
17 constexpr const char* Value = "v";
18 constexpr const char* Node = "node";
19 constexpr const char* Way = "way";
20 constexpr const char* Relation = "relation";
21 constexpr const char* Member = "member";
22 constexpr const char* Role = "role";
23 constexpr const char* Type = "type";
24 constexpr const char* Nd = "nd";
25 constexpr const char* Ref = "ref";
26 constexpr const char* Id = "id";
27 constexpr const char* Lat = "lat";
28 constexpr const char* Lon = "lon";
29 constexpr const char* Version = "version";
30 constexpr const char* Visible = "visible";
31 constexpr const char* Elevation = "ele";
32 constexpr const char* Action = "action";
33 constexpr const char* Delete = "delete";
34 } // namespace keyword
35 
36 struct UnresolvedRole {
39  Primitive** location{};
40 };
41 
42 Attributes tags(const pugi::xml_node& node) {
43  Attributes attributes;
44  for (auto tag = node.child(keyword::Tag); tag; // NOLINT
45  tag = tag.next_sibling(keyword::Tag)) {
46  if (std::string(tag.attribute(keyword::Key).value()) == keyword::Elevation) {
47  continue;
48  }
49  attributes[tag.attribute(keyword::Key).value()] = tag.attribute(keyword::Value).value();
50  }
51  return attributes;
52 }
53 
54 bool isDeleted(const pugi::xml_node& node) {
55  auto action = node.attribute(keyword::Action);
56  return action && std::string(action.value()) == keyword::Delete; // NOLINT
57 }
58 
59 std::string toJosmStyle(const double d, const bool josm_format_elevation = false) {
60  std::string str = boost::str(boost::format{josm_format_elevation ? "%.2f" : "%.11f"} % d);
61  str.erase(str.find_last_not_of('0') + 1, std::string::npos);
62  str.erase(str.find_last_not_of('.') + 1, std::string::npos);
63  return str;
64 }
65 
66 void removeAndFixPlaceholders(Primitive** toRemove, Roles& fromRoles, std::vector<UnresolvedRole>& placeholders) {
67  // find other placeholders that we have to fix
68  auto remIt =
69  std::find_if(fromRoles.begin(), fromRoles.end(), [&](const Role& role) { return &role.second == toRemove; });
70  assert(remIt != fromRoles.end());
71  std::vector<std::pair<size_t, Primitive**>> placeholderLocations;
72  for (auto it = fromRoles.begin(); it != fromRoles.end(); ++it) {
73  if (it->second == nullptr && remIt != it) {
74  auto idx = std::distance(fromRoles.begin(), it);
75  placeholderLocations.emplace_back(it > remIt ? idx - 1 : idx, &it->second);
76  }
77  }
78  fromRoles.erase(remIt);
79  if (placeholderLocations.empty()) {
80  return; // nothing to update
81  }
82  // get the new locations
83  std::map<Primitive**, Primitive**> newLocations;
84  for (auto& loc : placeholderLocations) {
85  newLocations.emplace(loc.second, &std::next(fromRoles.begin(), long(loc.first))->second);
86  }
87  // adapt existing locations
88  for (auto& placeholder : placeholders) {
89  auto it = newLocations.find(placeholder.location);
90  if (it != newLocations.end()) {
91  placeholder.location = it->second;
92  }
93  }
94 }
95 
96 class OsmFileWriter {
97  public:
98  static std::unique_ptr<pugi::xml_document> write(const File& osmFile, const io::Configuration& params) {
99  auto xml = std::make_unique<pugi::xml_document>();
100  auto osmNode = xml->append_child(keyword::Osm);
101  osmNode.append_attribute("version") = "0.6";
102  // whether to upload the model in JOSM, false by default
103  {
104  const auto iter = params.find("josm_upload");
105  if (iter != params.end() && iter->second.asBool().value_or(false)) {
106  osmNode.append_attribute("upload") = "true";
107  } else {
108  osmNode.append_attribute("upload") = "false";
109  }
110  }
111  osmNode.append_attribute("generator") = "lanelet2";
112 
113  // whether to format elevation for JOSM (2 decimal places), false by default
114  const auto iter = params.find("josm_format_elevation");
115  const bool josm_format_elevation = iter != params.end() && iter->second.asBool().value_or(false);
116  lanelet::osm::OsmFileWriter::writeNodes(osmNode, osmFile.nodes, josm_format_elevation);
117  lanelet::osm::OsmFileWriter::writeWays(osmNode, osmFile.ways);
118  lanelet::osm::OsmFileWriter::writeRelations(osmNode, osmFile.relations);
119  return xml;
120  }
121 
122  private:
123  static void writeAttributes(pugi::xml_node& elemNode, const Attributes& attributes) {
124  for (const auto& attribute : attributes) {
125  auto tagNode = elemNode.append_child(keyword::Tag);
126  tagNode.append_attribute(keyword::Key) = attribute.first.c_str();
127  tagNode.append_attribute(keyword::Value) = attribute.second.c_str();
128  }
129  }
130 
131  static void writeNodes(pugi::xml_node& osmNode, const Nodes& nodes, const bool josm_format_elevation = false) {
132  for (const auto& node : nodes) {
133  auto xmlNode = osmNode.append_child(keyword::Node);
134  xmlNode.append_attribute(keyword::Id) = LongLong(node.second.id);
135  if (node.second.id > 0) {
136  xmlNode.append_attribute(keyword::Visible) = "true";
137  xmlNode.append_attribute(keyword::Version) = 1;
138  }
139  xmlNode.append_attribute(keyword::Lat) = toJosmStyle(node.second.point.lat).c_str();
140  xmlNode.append_attribute(keyword::Lon) = toJosmStyle(node.second.point.lon).c_str();
141 
142  if (node.second.point.ele != 0.) {
143  auto tagNode = xmlNode.append_child(keyword::Tag);
144  tagNode.append_attribute(keyword::Key) = keyword::Elevation;
145  tagNode.append_attribute(keyword::Value) = toJosmStyle(node.second.point.ele, josm_format_elevation).c_str();
146  }
147  writeAttributes(xmlNode, node.second.attributes);
148  }
149  }
150 
151  static void writeWays(pugi::xml_node& osmNode, const Ways& ways) {
152  for (const auto& wayElem : ways) {
153  const auto& way = wayElem.second;
154  auto xmlNode = osmNode.append_child(keyword::Way);
155  xmlNode.append_attribute(keyword::Id) = LongLong(way.id);
156  if (way.id > 0) {
157  xmlNode.append_attribute(keyword::Visible) = "true";
158  xmlNode.append_attribute(keyword::Version) = 1;
159  }
160  for (const auto& node : way.nodes) {
161  auto nd = xmlNode.append_child(keyword::Nd);
162  nd.append_attribute(keyword::Ref) = LongLong(node->id);
163  }
164  writeAttributes(xmlNode, way.attributes);
165  }
166  }
167 
168  static void writeRelations(pugi::xml_node& osmNode, const Relations& relations) {
169  for (const auto& relationElem : relations) {
170  const auto& relation = relationElem.second;
171  auto xmlNode = osmNode.append_child(keyword::Relation);
172  xmlNode.append_attribute(keyword::Id) = LongLong(relation.id);
173  if (relation.id > 0) {
174  xmlNode.append_attribute(keyword::Visible) = "true";
175  xmlNode.append_attribute(keyword::Version) = 1;
176  }
177  for (const auto& role : relation.members) {
178  auto xmlMember = xmlNode.append_child(keyword::Member);
179  auto type = role.second->type();
180  xmlMember.append_attribute(keyword::Type) = type.c_str();
181  xmlMember.append_attribute(keyword::Ref) = LongLong(role.second->id);
182  xmlMember.append_attribute(keyword::Role) = role.first.c_str();
183  }
184  writeAttributes(xmlNode, relation.attributes);
185  }
186  }
187 };
188 
189 class OsmFileParser {
190  public:
191  static File read(const pugi::xml_node& fileNode, Errors* errors = nullptr) {
192  OsmFileParser osmParser;
193  File file;
194  auto osmNode = fileNode.child(keyword::Osm);
195  file.nodes = lanelet::osm::OsmFileParser::readNodes(osmNode);
196  file.ways = osmParser.readWays(osmNode, file.nodes);
197  file.relations = osmParser.readRelations(osmNode, file.nodes, file.ways);
198  if (errors != nullptr) {
199  *errors = osmParser.errors_;
200  }
201  return file;
202  }
203 
204  private:
205  static Nodes readNodes(const pugi::xml_node& osmNode) {
206  Nodes nodes;
207  for (auto node = osmNode.child(keyword::Node); node; // NOLINT
208  node = node.next_sibling(keyword::Node)) {
209  if (isDeleted(node)) {
210  continue;
211  }
212  const auto id = node.attribute(keyword::Id).as_llong(InvalId);
213  const auto attributes = tags(node);
214  const auto lat = node.attribute(keyword::Lat).as_double(0.);
215  const auto lon = node.attribute(keyword::Lon).as_double(0.);
216  const auto ele = node.find_child_by_attribute(keyword::Tag, keyword::Key, keyword::Elevation)
217  .attribute(keyword::Value)
218  .as_double(0.);
219  nodes[id] = Node{id, attributes, {lat, lon, ele}};
220  }
221  return nodes;
222  }
223 
224  Ways readWays(const pugi::xml_node& osmNode, Nodes& nodes) {
225  Ways ways;
226  for (auto node = osmNode.child(keyword::Way); node; // NOLINT
227  node = node.next_sibling(keyword::Way)) {
228  if (isDeleted(node)) {
229  continue;
230  }
231  const auto id = node.attribute(keyword::Id).as_llong(InvalId);
232  const auto attributes = tags(node);
233  const auto nodeIds = [&node] {
234  Ids ids;
235  for (auto refNode = node.child(keyword::Nd); refNode; // NOLINT
236  refNode = refNode.next_sibling(keyword::Nd)) {
237  ids.push_back(refNode.attribute(keyword::Ref).as_llong());
238  }
239  return ids;
240  }();
241  std::vector<Node*> wayNodes;
242  try {
243  wayNodes = utils::transform(nodeIds, [&nodes](const auto& elem) { return &nodes.at(elem); });
244  } catch (std::out_of_range&) {
245  reportParseError(id, "Way references nonexisting points");
246  }
247  ways[id] = Way{id, attributes, wayNodes};
248  }
249  return ways;
250  }
251 
252  Relations readRelations(const pugi::xml_node& osmNode, Nodes& nodes, Ways& ways) {
253  Relations relations;
254  // Two-pass approach: We can resolve all roles except where relations reference relations. We insert a dummy nullptr
255  // and resolve that later on.
256  std::vector<UnresolvedRole> unresolvedRoles;
257  for (auto node = osmNode.child(keyword::Relation); node; // NOLINT
258  node = node.next_sibling(keyword::Relation)) {
259  if (isDeleted(node)) {
260  continue;
261  }
262  const auto id = node.attribute(keyword::Id).as_llong(InvalId);
263  const auto attributes = tags(node);
264  auto& relation = relations.emplace(id, Relation{id, attributes, {}}).first->second;
265 
266  // resolve members
267  auto& roles = relation.members;
268  for (auto member = node.child(keyword::Member); member; // NOLINT
269  member = member.next_sibling(keyword::Member)) {
270  Id memberId = member.attribute(keyword::Ref).as_llong();
271  const std::string role = member.attribute(keyword::Role).value();
272  const std::string type = member.attribute(keyword::Type).value();
273  try {
274  if (type == keyword::Node) {
275  roles.emplace_back(role, &nodes.at(memberId));
276  } else if (type == keyword::Way) {
277  roles.emplace_back(role, &ways.at(memberId));
278  } else if (type == keyword::Relation) {
279  // insert a placeholder and store a pointer to it for the second pass
280  roles.emplace_back(role, nullptr);
281  unresolvedRoles.push_back(UnresolvedRole{id, memberId, &roles.back().second});
282  }
283  } catch (std::out_of_range&) {
284  reportParseError(id, "Relation has nonexistent member " + std::to_string(memberId));
285  }
286  }
287  }
288 
289  // now resolve all unresolved roles that point to other relations
290  for (const auto& unresolvedRole : unresolvedRoles) {
291  try {
292  assert(*unresolvedRole.location == nullptr);
293  *unresolvedRole.location = &relations.at(unresolvedRole.referencedRelation);
294  } catch (std::out_of_range&) {
295  reportParseError(unresolvedRole.relation, "Relation references nonexistent relation " +
296  std::to_string(unresolvedRole.referencedRelation));
297  // now it gets ugly: find placeholder and remove it. Fix all other placeholders because the pointers are
298  // invalidated after moving. This is inefficent, but its the fault of the guy loading an invalid map, not ours.
299  auto& relation = relations.at(unresolvedRole.relation);
300  removeAndFixPlaceholders(unresolvedRole.location, relation.members, unresolvedRoles);
301  }
302  }
303  return relations;
304  }
305 
306  OsmFileParser() = default;
307  void reportParseError(Id id, const std::string& what) {
308  auto errstr = "Error reading primitive with id " + std::to_string(id) + " from file: " + what;
309  errors_.push_back(errstr);
310  }
312 };
313 } // namespace
314 
315 bool operator==(const Way& lhs, const Way& rhs) {
316  auto nodesEqual = [&lhs, &rhs]() {
317  for (auto i = 0u; i < lhs.nodes.size(); i++) {
318  if (lhs.nodes[i]->id != rhs.nodes[i]->id) {
319  return false;
320  }
321  }
322  return true;
323  };
324  return lhs.id == rhs.id && lhs.nodes.size() == rhs.nodes.size() && nodesEqual();
325 }
326 
327 bool operator==(const Relation& lhs, const Relation& rhs) {
328  auto membersEqual = [&lhs, &rhs]() {
329  for (auto itL = lhs.members.begin(), itR = rhs.members.begin(); itL != lhs.members.end(); ++itL, ++itR) {
330  if (itL->second->type() != itR->second->type() && itL->second->id != itR->second->id) {
331  return false;
332  }
333  }
334  return true;
335  };
336  return lhs.id == rhs.id && lhs.members.size() == rhs.members.size() && membersEqual();
337 }
338 
339 bool operator==(const File& lhs, const File& rhs) {
340  return lhs.nodes == rhs.nodes && lhs.ways == rhs.ways && lhs.relations == rhs.relations;
341 }
342 
343 File read(pugi::xml_document& node, Errors* errors) { return OsmFileParser::read(node, errors); }
344 
345 std::unique_ptr<pugi::xml_document> write(const File& file, const io::Configuration& params) {
346  return OsmFileWriter::write(file, params); }
347 } // namespace osm
348 } // namespace lanelet
lanelet::InvalId
constexpr Id InvalId
lanelet::osm::Way::nodes
std::vector< Node * > nodes
Definition: OsmFile.h:51
lanelet
location
Primitive ** location
Definition: OsmFile.cpp:39
lanelet::io::Configuration
std::map< std::string, Attribute > Configuration
Definition: Configuration.h:8
file
osm::File & file
Definition: OsmHandlerWrite.cpp:245
lanelet::osm::Relations
std::map< Id, Relation > Relations
Definition: OsmFile.h:65
lanelet::osm::write
std::unique_ptr< pugi::xml_document > write(const File &file, const io::Configuration &params=io::Configuration())
Definition: OsmFile.cpp:345
lanelet::osm::File::nodes
Nodes nodes
Definition: OsmFile.h:80
lanelet::Id
int64_t Id
Ids
std::vector< Id > Ids
lanelet::osm::Relation::members
Roles members
Definition: OsmFile.h:60
id
Id id
Definition: OsmHandlerWrite.cpp:243
lanelet::osm::Nodes
std::map< Id, Node > Nodes
Definition: OsmFile.h:63
referencedRelation
Id referencedRelation
Definition: OsmFile.cpp:38
lanelet::osm::Relation
Osm relation object.
Definition: OsmFile.h:55
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::utils::transform
auto transform(Container &&c, Func f)
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
AttributeName::Type
@ Type
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::operator==
bool operator==(const Node &lhs, const Node &rhs)
Definition: OsmFile.h:106
lanelet::osm::Attributes
std::map< std::string, std::string > Attributes
Definition: OsmFile.h:17
lanelet::osm::Roles
std::deque< Role > Roles
Definition: OsmFile.h:19
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
errors_
Errors errors_
Definition: OsmFile.cpp:311
lanelet::osm::Way
Osm way object.
Definition: OsmFile.h:46
OsmFile.h
relation
Id relation
Definition: OsmFile.cpp:37
d
double d
Utilities.h


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