Skip to content

Commit

Permalink
chore: use LaneletMapPtr
Browse files Browse the repository at this point in the history
Signed-off-by: Barış Zeren <[email protected]>
  • Loading branch information
StepTurtle committed Oct 2, 2024
1 parent 44d429d commit 2ddb81f
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -47,12 +47,12 @@ class MultiOsmParser : public Parser
std::unique_ptr<LaneletMap> parse(
const std::string & lanelet2_filename, ErrorMessages & errors) const override;

std::unique_ptr<LaneletMap> parse(
lanelet::LaneletMapPtr parse(
const std::vector<std::string> & lanelet2_filenames, ErrorMessages & errors) const;

std::unique_ptr<LaneletMap> fromOsmFile(const osm::File & file, ErrorMessages & errors) const;
lanelet::LaneletMapPtr fromOsmFile(const osm::File & file, ErrorMessages & errors) const;

std::unique_ptr<LaneletMap> fromOsmFile(
lanelet::LaneletMapPtr fromOsmFile(
const std::map<std::string, osm::File> & files_map, ErrorMessages & errors) const;

static void parseVersions(
Expand All @@ -70,7 +70,7 @@ RegisterParser<MultiOsmParser> regParser;
class MultiFileLoader
{
public:
static std::unique_ptr<LaneletMap> loadMap(
static lanelet::LaneletMapPtr loadMap(
const osm::File & file, const Projector & projector, ErrorMessages & errors)
{
MultiFileLoader loader;
Expand All @@ -88,7 +88,7 @@ class MultiFileLoader
loader.lineStrings_, loader.points_);
}

static std::unique_ptr<LaneletMap> loadMap(
static lanelet::LaneletMapPtr loadMap(
const std::map<std::string, osm::File> & files_map, const Projector & projector,
ErrorMessages & errors)
{
Expand Down
8 changes: 4 additions & 4 deletions autoware_lanelet2_extension/lib/autoware_multi_osm_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -445,7 +445,7 @@ void testAndPrintLocaleWarning(ErrorMessages & errors)
}
}

std::unique_ptr<LaneletMap> MultiOsmParser::parse(
lanelet::LaneletMapPtr MultiOsmParser::parse(
const std::vector<std::string> & lanelet2_filenames, lanelet::ErrorMessages & errors) const
{
std::map<std::string, osm::File> files;
Expand Down Expand Up @@ -506,16 +506,16 @@ std::unique_ptr<LaneletMap> MultiOsmParser::parse(
registerIds(file.relations);
errors = buildErrorMessage(
"Errors ocurred while parsing Lanelet Map:", utils::concatenate({osmReadErrors, errors}));
return map;
return std::unique_ptr<LaneletMap>(map.get());
}

std::unique_ptr<LaneletMap> MultiOsmParser::fromOsmFile(
lanelet::LaneletMapPtr MultiOsmParser::fromOsmFile(
const std::map<std::string, osm::File> & files_map, ErrorMessages & errors) const
{
return MultiFileLoader::loadMap(files_map, projector(), errors);
}

std::unique_ptr<LaneletMap> MultiOsmParser::fromOsmFile(
lanelet::LaneletMapPtr MultiOsmParser::fromOsmFile(
const osm::File & file, lanelet::ErrorMessages & errors) const
{
return MultiFileLoader::loadMap(file, projector(), errors);
Expand Down

0 comments on commit 2ddb81f

Please sign in to comment.