Function lanelet::load(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 Origin &origin = Origin::defaultOrigin(), ErrorMessages *errors = nullptr, const io::Configuration ¶ms = io::Configuration())
Loads a lanelet map from a file.
It can not be stressed enough that it is important to provide a valid origin to write/load maps with georeferenced (lat/lon) data. If no origin is specified, the loaded map will most likely be not correctly located and deformed.
- Parameters:
filename – name to load from. The extension decides how the file will be parsed.
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 or extension is not supported. If errors is not null, the loader will instead try to recover and only throw on unrecoverable errors (ie if the map did not exist). However, the loaded map will be incomplete if errors occurred. The loader will also throw if you did not provide a valid origin for a map that requires an origin for projections.
- Returns:
Loaded map. Pointer is aways valid. Otherwise, an exception will be thrown