Function lanelet::load(const std::string&, const std::string&, const Origin&, ErrorMessages *, const io::Configuration&)
Defined in File Io.h
Function Documentation
-
std::unique_ptr<LaneletMap> lanelet::load(const std::string &filename, const std::string &parserName, const Origin &origin = Origin::defaultOrigin(), ErrorMessages *errors = nullptr, const io::Configuration ¶ms = io::Configuration())
Loads a lanelet map from a file.
- Parameters:
filename – name to load from
parserName – name of the parser to use. Available parsers can be queried with supportedParsers()
origin – origin for the lat/lon -> x/y conversion. This must not be the default origin if the specified format requires an origin (e.g. you must always provide an origin if you load .osm data).
errors – if this points to a valid object, errors occured during parsing the map will be passed via this parameter. If this is nullptr, an exception will be thrown if errors have occurred.
params – optional params for loading. It depends on the parser that is used which parameters are required. If no params are passed, default values will be used
- Throws:
lanelet2::IOError – if the file did not exist, could not be parsed, the default origin was provided for a map that requires osm conversion or extension is not supported
- Returns:
Loaded map. Pointer is aways valid. Otherwise, an exception will be thrown