Parser.h
Go to the documentation of this file.
1 #pragma once
3 
4 #include <memory>
5 
9 
10 namespace lanelet {
11 namespace io_handlers {
22 class Parser : public IOHandler {
23  public:
25  Parser() = default;
26  using Ptr = std::shared_ptr<Parser>;
27  virtual std::unique_ptr<LaneletMap> parse(const std::string& filename, ErrorMessages& errors) const = 0;
28 
29  private:
31  void handleDefaultProjector() const final {
32  throw lanelet::IOError("You must pass an origin when loading a map with georeferenced (lat/lon) data!");
33  }
34 };
35 } // namespace io_handlers
36 } // namespace lanelet
lanelet::ErrorMessages
std::vector< std::string > ErrorMessages
Definition: Io.h:11
LaneletMap.h
lanelet
lanelet::io_handlers::Parser::Parser
Parser()=default
lanelet::io_handlers::IOHandler::Ptr
std::shared_ptr< IOHandler > Ptr
Definition: IoHandler.h:15
IoHandler.h
lanelet::io_handlers::Parser
Base object for parsers. To create a new parser, you have to do the following steps:
Definition: Parser.h:22
lanelet::IOError
Generic error for all errors in this module.
Definition: Exceptions.h:13
lanelet::io_handlers::Parser::parse
virtual std::unique_ptr< LaneletMap > parse(const std::string &filename, ErrorMessages &errors) const =0
lanelet::io_handlers::Parser::handleDefaultProjector
void handleDefaultProjector() const final
loading a map with a default origin throws an error
Definition: Parser.h:31
lanelet::io_handlers::IOHandler::IOHandler
IOHandler()=default
lanelet::io_handlers::IOHandler
Base class for all handlers (writers and parsers)
Definition: IoHandler.h:13
Projection.h
Exceptions.h


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