Program Listing for File Io.h

Return to documentation for file (include/lanelet2_io/Io.h)

#pragma once
#include <lanelet2_core/LaneletMap.h>

#include <string>
#include <vector>

#include "lanelet2_io/Configuration.h"
#include "lanelet2_io/Projection.h"

namespace lanelet {
using ErrorMessages = std::vector<std::string>;
std::unique_ptr<LaneletMap> load(const std::string& filename, const Origin& origin = Origin::defaultOrigin(),
                                 ErrorMessages* errors = nullptr,
                                 const io::Configuration& params = io::Configuration());

std::unique_ptr<LaneletMap> load(const std::string& filename, const Projector& projector,
                                 ErrorMessages* errors = nullptr,
                                 const io::Configuration& params = io::Configuration());

std::unique_ptr<LaneletMap> load(const std::string& filename, const std::string& parserName,
                                 const Origin& origin = Origin::defaultOrigin(), ErrorMessages* errors = nullptr,
                                 const io::Configuration& params = io::Configuration());

std::unique_ptr<LaneletMap> load(const std::string& filename, const std::string& parserName, const Projector& projector,
                                 ErrorMessages* errors = nullptr,
                                 const io::Configuration& params = io::Configuration());

std::vector<std::string> supportedParsers();

std::vector<std::string> supportedParserExtensions();

void write(const std::string& filename, const lanelet::LaneletMap& map, const Origin& origin = Origin::defaultOrigin(),
           ErrorMessages* errors = nullptr, const io::Configuration& params = io::Configuration());

void write(const std::string& filename, const LaneletMap& map, const Projector& projector,
           ErrorMessages* errors = nullptr, const io::Configuration& params = io::Configuration());

void write(const std::string& filename, const lanelet::LaneletMap& map, const std::string& writerName,
           const Origin& origin = Origin::defaultOrigin(), ErrorMessages* errors = nullptr,
           const io::Configuration& params = io::Configuration());

void write(const std::string& filename, const LaneletMap& map, const std::string& writerName,
           const Projector& projector, ErrorMessages* errors = nullptr,
           const io::Configuration& params = io::Configuration());

std::vector<std::string> supportedWriters();

std::vector<std::string> supportedWriterExtensions();
}  // namespace lanelet