Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] authored and StepTurtle committed Sep 26, 2024
1 parent 9727af7 commit 44d429d
Show file tree
Hide file tree
Showing 2 changed files with 619 additions and 619 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef LANELET2_EXTENSION__IO__AUTOWARE_MULTI_OSM_PARSER_HPP_
#define LANELET2_EXTENSION__IO__AUTOWARE_MULTI_OSM_PARSER_HPP_
#ifndef AUTOWARE_LANELET2_EXTENSION__IO__AUTOWARE_MULTI_OSM_PARSER_HPP_
#define AUTOWARE_LANELET2_EXTENSION__IO__AUTOWARE_MULTI_OSM_PARSER_HPP_

#include "lanelet2_io/Exceptions.h"
#include "lanelet2_io/io_handlers/Factory.h"
Expand All @@ -36,153 +36,153 @@ using std::string_literals::operator""s;

namespace lanelet
{
namespace io_handlers
{

class MultiOsmParser : public Parser
{
public:
using Parser::Parser;

std::unique_ptr<LaneletMap> parse(
const std::string & lanelet2_filename, ErrorMessages & errors) const override;

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

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

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

class MultiOsmParser : public Parser
{
public:
using Parser::Parser;

std::unique_ptr<LaneletMap> parse(
const std::string & lanelet2_filename, ErrorMessages & errors) const override;

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

static void parseVersions(
const std::string & filename, std::string * format_version, std::string * map_version);
std::unique_ptr<LaneletMap> fromOsmFile(const osm::File & file, ErrorMessages & errors) const;

static constexpr const char * extension() { return ".osm"; }

static constexpr const char * name() { return "autoware_multi_osm_handler"; }
};
std::unique_ptr<LaneletMap> fromOsmFile(
const std::map<std::string, osm::File> & files_map, ErrorMessages & errors) const;

namespace
{
RegisterParser<MultiOsmParser> regParser;
static void parseVersions(
const std::string & filename, std::string * format_version, std::string * map_version);

class MultiFileLoader
{
public:
static std::unique_ptr<LaneletMap> loadMap(
const osm::File & file, const Projector & projector, ErrorMessages & errors)
{
MultiFileLoader loader;
loader.loadNodes(file.nodes, projector);
loader.loadWays(file.ways);
auto laneletsWithRelation = loader.loadLanelets(file.relations);
auto areasWithRelation = loader.loadAreas(file.relations);
loader.loadRegulatoryElements(file.relations);
loader.addRegulatoryElements(laneletsWithRelation);
loader.addRegulatoryElements(areasWithRelation);
errors = std::move(loader.errors_);
static constexpr const char * extension() { return ".osm"; }

static constexpr const char * name() { return "autoware_multi_osm_handler"; }
};

namespace
{
RegisterParser<MultiOsmParser> regParser;

class MultiFileLoader
{
public:
static std::unique_ptr<LaneletMap> loadMap(
const osm::File & file, const Projector & projector, ErrorMessages & errors)
{
MultiFileLoader loader;
loader.loadNodes(file.nodes, projector);
loader.loadWays(file.ways);
auto laneletsWithRelation = loader.loadLanelets(file.relations);
auto areasWithRelation = loader.loadAreas(file.relations);
loader.loadRegulatoryElements(file.relations);
loader.addRegulatoryElements(laneletsWithRelation);
loader.addRegulatoryElements(areasWithRelation);
errors = std::move(loader.errors_);

return std::make_unique<LaneletMap>(
loader.lanelets_, loader.areas_, loader.regulatoryElements_, loader.polygons_,
loader.lineStrings_, loader.points_);
}
return std::make_unique<LaneletMap>(
loader.lanelets_, loader.areas_, loader.regulatoryElements_, loader.polygons_,
loader.lineStrings_, loader.points_);
}

static std::unique_ptr<LaneletMap> loadMap(
const std::map<std::string, osm::File> & files_map, const Projector & projector,
ErrorMessages & errors)
{
MultiFileLoader loader;
static std::unique_ptr<LaneletMap> loadMap(
const std::map<std::string, osm::File> & files_map, const Projector & projector,
ErrorMessages & errors)
{
MultiFileLoader loader;

std::for_each(files_map.begin(), files_map.end(), [&loader, &projector](const auto & file) {
loader.loadNodes(file.second.nodes, projector);
});
std::for_each(files_map.begin(), files_map.end(), [&loader, &projector](const auto & file) {
loader.loadNodes(file.second.nodes, projector);
});

std::for_each(files_map.begin(), files_map.end(), [&loader](const auto & file) {
loader.loadWays(file.second.ways);
});
std::for_each(files_map.begin(), files_map.end(), [&loader](const auto & file) {
loader.loadWays(file.second.ways);
});

LaneletsWithRegulatoryElements laneletsWithRelation;
for (const auto & file : files_map) {
laneletsWithRelation = loader.loadLanelets(file.second.relations);
}
LaneletsWithRegulatoryElements laneletsWithRelation;
for (const auto & file : files_map) {
laneletsWithRelation = loader.loadLanelets(file.second.relations);
}

AreasWithRegulatoryElements areasWithRelation;
for (const auto & file : files_map) {
areasWithRelation = loader.loadAreas(file.second.relations);
}
AreasWithRegulatoryElements areasWithRelation;
for (const auto & file : files_map) {
areasWithRelation = loader.loadAreas(file.second.relations);
}

for (const auto & file : files_map) {
loader.loadRegulatoryElements(file.second.relations);
}
loader.addRegulatoryElements(laneletsWithRelation);
loader.addRegulatoryElements(areasWithRelation);
for (const auto & file : files_map) {
loader.loadRegulatoryElements(file.second.relations);
}
loader.addRegulatoryElements(laneletsWithRelation);
loader.addRegulatoryElements(areasWithRelation);

errors = std::move(loader.errors_);
return std::make_unique<LaneletMap>(
loader.lanelets_, loader.areas_, loader.regulatoryElements_, loader.polygons_,
loader.lineStrings_, loader.points_);
}
errors = std::move(loader.errors_);
return std::make_unique<LaneletMap>(
loader.lanelets_, loader.areas_, loader.regulatoryElements_, loader.polygons_,
loader.lineStrings_, loader.points_);
}

private:
std::vector<std::string> errors_;
LaneletLayer::Map lanelets_;
AreaLayer::Map areas_;
RegulatoryElementLayer::Map regulatoryElements_;
PolygonLayer::Map polygons_;
LineStringLayer::Map lineStrings_;
PointLayer::Map points_;
private:
std::vector<std::string> errors_;
LaneletLayer::Map lanelets_;
AreaLayer::Map areas_;
RegulatoryElementLayer::Map regulatoryElements_;
PolygonLayer::Map polygons_;
LineStringLayer::Map lineStrings_;
PointLayer::Map points_;

public:
template <typename PrimT>
using PrimitiveWithRegulatoryElement = std::pair<PrimT, const osm::Relation *>;
public:
template <typename PrimT>
using PrimitiveWithRegulatoryElement = std::pair<PrimT, const osm::Relation *>;

template <typename PrimT>
using PrimitivesWithRegulatoryElement = std::vector<PrimitiveWithRegulatoryElement<PrimT>>;
template <typename PrimT>
using PrimitivesWithRegulatoryElement = std::vector<PrimitiveWithRegulatoryElement<PrimT>>;

using AreasWithRegulatoryElements = PrimitivesWithRegulatoryElement<Area>;
using LaneletsWithRegulatoryElements = PrimitivesWithRegulatoryElement<Lanelet>;
using AreasWithRegulatoryElements = PrimitivesWithRegulatoryElement<Area>;
using LaneletsWithRegulatoryElements = PrimitivesWithRegulatoryElement<Lanelet>;

MultiFileLoader() = default;
MultiFileLoader() = default;

void loadNodes(const lanelet::osm::Nodes & nodes, const Projector & projector);
void loadNodes(const lanelet::osm::Nodes & nodes, const Projector & projector);

void loadWays(const lanelet::osm::Ways & ways);
void loadWays(const lanelet::osm::Ways & ways);

LaneletsWithRegulatoryElements loadLanelets(const lanelet::osm::Relations & relations);
LaneletsWithRegulatoryElements loadLanelets(const lanelet::osm::Relations & relations);

AreasWithRegulatoryElements loadAreas(const lanelet::osm::Relations & relations);
AreasWithRegulatoryElements loadAreas(const lanelet::osm::Relations & relations);

void loadRegulatoryElements(const osm::Relations & relations);
void loadRegulatoryElements(const osm::Relations & relations);

template <typename PrimT>
void addRegulatoryElements(std::vector<std::pair<PrimT, const osm::Relation *>> & addTos);
template <typename PrimT>
void addRegulatoryElements(std::vector<std::pair<PrimT, const osm::Relation *>> & addTos);

template <const char * Type>
bool isType(const lanelet::osm::Relation & relation);
template <const char * Type>
bool isType(const lanelet::osm::Relation & relation);

static lanelet::AttributeMap getAttributes(const lanelet::osm::Attributes & osmAttributes);
static lanelet::AttributeMap getAttributes(const lanelet::osm::Attributes & osmAttributes);

LineString3d getLaneletBorder(const osm::Relation & llElem, const std::string & role);
LineString3d getLaneletBorder(const osm::Relation & llElem, const std::string & role);

LineStrings3d getLinestrings(const osm::Roles & roles, const std::string & roleName, Id refId);
LineStrings3d getLinestrings(const osm::Roles & roles, const std::string & roleName, Id refId);

LineStrings3d getOuterRing(const osm::Relation & area);
LineStrings3d getOuterRing(const osm::Relation & area);

std::vector<LineStrings3d> getInnerRing(const osm::Relation & area);
std::vector<LineStrings3d> getInnerRing(const osm::Relation & area);

RuleParameterMap getRulesForRegulatoryElement(Id currElemId, const osm::Roles & roles);
RuleParameterMap getRulesForRegulatoryElement(Id currElemId, const osm::Roles & roles);

std::vector<LineStrings3d> assembleBoundary(LineStrings3d lineStrings, Id id);
std::vector<LineStrings3d> assembleBoundary(LineStrings3d lineStrings, Id id);

template <typename PrimT>
PrimT getOrGetDummy(
const typename std::unordered_map<Id, PrimT> & map, Id id, Id currentPrimitiveId);
template <typename PrimT>
PrimT getOrGetDummy(
const typename std::unordered_map<Id, PrimT> & map, Id id, Id currentPrimitiveId);

void parserError(Id id, const std::string & what);
};
} // namespace
} // namespace io_handlers
void parserError(Id id, const std::string & what);
};
} // namespace
} // namespace io_handlers
}; // namespace lanelet

#endif // LANELET2_EXTENSION__IO__AUTOWARE_MULTI_OSM_PARSER_HPP_
#endif // AUTOWARE_LANELET2_EXTENSION__IO__AUTOWARE_MULTI_OSM_PARSER_HPP_
Loading

0 comments on commit 44d429d

Please sign in to comment.