04_reading_and_writing/main.cpp
Go to the documentation of this file.
1 #include <lanelet2_core/primitives/Lanelet.h>
2 #include <lanelet2_io/Io.h>
6 
7 #include <cstdio>
8 
9 #pragma GCC diagnostic ignored "-Wunused-but-set-variable"
10 
11 // we want assert statements to work in release mode
12 #undef NDEBUG
13 
14 namespace {
15 std::string exampleMapPath = std::string(PKG_DIR) + "/../lanelet2_maps/res/mapping_example.osm";
16 
17 std::string tempfile(const std::string& name) {
18  char tmpDir[] = "/tmp/lanelet2_example_XXXXXX";
19  auto* file = mkdtemp(tmpDir);
20  if (file == nullptr) {
21  throw lanelet::IOError("Failed to open a temporary file for writing");
22  }
23  return std::string(file) + '/' + name;
24 }
25 } // namespace
26 
28 void part2Projectors();
30 
31 int main() {
32  // this tutorial shows you how to load and write lanelet maps. It is divided into three parts:
36  return 0;
37 }
38 
40  using namespace lanelet;
41  // loading a map requires two things: the path and either an origin or a projector that does the lat/lon->x/y
42  // conversion.
43  projection::UtmProjector projector(Origin({49, 8.4})); // we will go into details later
44  LaneletMapPtr map = load(exampleMapPath, projector);
45 
46  // the load and write functions are agnostic to the file extension. Depending on the extension, a different loading
47  // algorithm will be chosen. Here we chose osm.
48 
49  // we can also load and write into an internal binary format. It is not human readable but loading is much faster
50  // than from .osm:
51  write(tempfile("map.bin"), *map); // we do not need a projector to write to bin
52 
53  // if the map could not be parsed, exceptoins are thrown. Alternatively, you can provide an error struct. Then
54  // lanelet2 will load the map as far as possible and write all the errors that occured to the error object that you
55  // passed:
56  ErrorMessages errors;
57  map = load(exampleMapPath, projector, &errors);
58  assert(errors.empty()); // of no errors occurred, the map could be fully parsed.
59 }
60 
62  using namespace lanelet;
63  // as mentioned, projectors do the lat/lon->x/y conversion. This conversion is not trivial and only works when an
64  // origin close to the actual map position is chosen. Otherwise the loaded map will be distorted.
65  projection::UtmProjector projector(Origin({49, 8.4}));
66  BasicPoint3d projection = projector.forward(GPSPoint{49, 8.4, 0});
67  assert(std::abs(projection.x()) < 1e-6);
68 
69  // by default, lanele2 picks a projector that implements the mercator projection. However this is only due to legacy
70  // reasons and because it is cheap and efficient to implement. In general, we recommend to use the UTM projector (we
71  // already used it above). if you load a map from osm without providing a suitable projector or origin, an exception
72  // will be thrown.
73  // LaneletMapPtr map = load(exampleMapPath); // throws: loading from osm without projector
74 }
75 
76 // you can easily add new parsers and writers so that they will be picked by load/write.
77 // here we write a writer that simply does nothing. We will not write a reader, but it works similarly.
78 namespace example {
80  public:
81  using Writer::Writer;
82  void write(const std::string& /*filename*/, const lanelet::LaneletMap& /*laneletMap*/,
83  lanelet::ErrorMessages& /*errors*/, const lanelet::io::Configuration& /*params*/) const override {
84  // this writer does just nothing
85  }
86  static constexpr const char* extension() {
87  return ".fake"; // this is the extension that we support
88  }
89 
90  static constexpr const char* name() {
91  return "fake_writer"; // this is the name of the writer. Users can also pick the writer by its name.
92  }
93 };
94 } // namespace example
95 
96 namespace {
97 // this registers our new class for lanelet2_io
99 } // namespace
100 
102  using namespace lanelet;
103  // now we can test our writer:
104  LaneletMap map;
105  write("anypath.fake", map);
106 }
Writer.h
part1LoadingAndWriting
void part1LoadingAndWriting()
Definition: 04_reading_and_writing/main.cpp:39
ErrorMessages
std::vector< std::string > ErrorMessages
example::FakeWriter
Definition: 04_reading_and_writing/main.cpp:79
UTM.h
LaneletMapPtr
std::shared_ptr< LaneletMap > LaneletMapPtr
lanelet
example::FakeWriter::name
static constexpr const char * name()
Definition: 04_reading_and_writing/main.cpp:90
lanelet::io::Configuration
std::map< std::string, Attribute > Configuration
BasicPoint3d
Eigen::Vector3d BasicPoint3d
main
int main()
Definition: 04_reading_and_writing/main.cpp:31
lanelet::projection::UtmProjector::forward
BasicPoint3d forward(const GPSPoint &gps) const override
Factory.h
file
osm::File & file
example::FakeWriter::extension
static constexpr const char * extension()
Definition: 04_reading_and_writing/main.cpp:86
Io.h
lanelet::projection::UtmProjector
example
Definition: 02_regulatory_elements/main.cpp:88
lanelet::LaneletMap
lanelet::IOError
lanelet::load
std::unique_ptr< LaneletMap > load(const std::string &filename, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
lanelet::io_handlers::Writer
lanelet::Origin
map
map
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())
part2Projectors
void part2Projectors()
Definition: 04_reading_and_writing/main.cpp:61
part3AddingNewParsersAndWriters
void part3AddingNewParsersAndWriters()
Definition: 04_reading_and_writing/main.cpp:101
lanelet::io_handlers::RegisterWriter
example::FakeWriter::write
void write(const std::string &, const lanelet::LaneletMap &, lanelet::ErrorMessages &, const lanelet::io::Configuration &) const override
Definition: 04_reading_and_writing/main.cpp:82
lanelet::GPSPoint


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