Skip to content

Commit

Permalink
Merge branch 'main' into feat/lanelet2_map_validator/add_test_environ…
Browse files Browse the repository at this point in the history
…ment
  • Loading branch information
TaikiYamada4 committed Nov 21, 2024
2 parents 1504463 + 4fcb2d7 commit 8fdd418
Show file tree
Hide file tree
Showing 6 changed files with 170 additions and 102 deletions.
82 changes: 82 additions & 0 deletions map/autoware_lanelet2_map_validator/src/common/map_loader.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
// Copyright 2024 Autoware Foundation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "lanelet2_map_validator/map_loader.hpp"

#include <autoware_lanelet2_extension/projection/mgrs_projector.hpp>
#include <autoware_lanelet2_extension/projection/transverse_mercator_projector.hpp>

namespace lanelet::autoware::validation
{

namespace
{
namespace projector_names
{
constexpr const char * mgrs = "mgrs";
constexpr const char * transverse_mercator = "transverse_mercator";
constexpr const char * utm = "utm";
} // namespace projector_names
} // namespace

std::unique_ptr<lanelet::Projector> getProjector(
const std::string & projector_type, const lanelet::GPSPoint & origin)

{
if (projector_type == projector_names::mgrs) {
return std::make_unique<lanelet::projection::MGRSProjector>();
}
if (projector_type == projector_names::transverse_mercator) {
return std::make_unique<lanelet::projection::TransverseMercatorProjector>(
lanelet::Origin{origin});
}
if (projector_type == projector_names::utm) {
return std::make_unique<lanelet::projection::UtmProjector>(lanelet::Origin{origin});
}
return nullptr;
}

std::pair<lanelet::LaneletMapPtr, std::vector<lanelet::validation::DetectedIssues>>
loadAndValidateMap(
const std::string & projector_type, const std::string & map_file,
const lanelet::validation::ValidationConfig & val_config)
{
std::vector<lanelet::validation::DetectedIssues> issues;
lanelet::LaneletMapPtr map{nullptr};
lanelet::validation::Strings errors;
try {
const auto projector = getProjector(projector_type, val_config.origin);
if (!projector) {
errors.push_back("No valid map projection type specified!");
} else {
map = lanelet::load(map_file, *projector, &errors);
}
if (!map) {
errors.push_back("Failed to load map!");
}
issues.emplace_back("general", utils::transform(errors, [](auto & error) {
return lanelet::validation::Issue(
lanelet::validation::Severity::Error, error);
}));
} catch (lanelet::LaneletError & err) {
issues.emplace_back("general", utils::transform(errors, [](auto & error) {
return lanelet::validation::Issue(
lanelet::validation::Severity::Error, error);
}));
}

return {map, issues};
}

} // namespace lanelet::autoware::validation
99 changes: 25 additions & 74 deletions map/autoware_lanelet2_map_validator/src/common/validation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,6 @@

#include "lanelet2_map_validator/validation.hpp"

#include <autoware_lanelet2_extension/projection/mgrs_projector.hpp>
#include <autoware_lanelet2_extension/projection/transverse_mercator_projector.hpp>
#include <nlohmann/json.hpp>

#include <algorithm>
Expand All @@ -42,56 +40,11 @@
namespace lanelet::autoware::validation
{

std::unique_ptr<lanelet::Projector> getProjector(
const std::string & projector_type, const lanelet::GPSPoint & origin)

std::vector<lanelet::validation::DetectedIssues> apply_validation(
const lanelet::LaneletMap & lanelet_map, const lanelet::validation::ValidationConfig & val_config)
{
if (projector_type == projector_names::mgrs) {
return std::make_unique<lanelet::projection::MGRSProjector>();
}
if (projector_type == projector_names::transverse_mercator) {
return std::make_unique<lanelet::projection::TransverseMercatorProjector>(
lanelet::Origin{origin});
}
if (projector_type == projector_names::utm) {
return std::make_unique<lanelet::projection::UtmProjector>(lanelet::Origin{origin});
}
return nullptr;
}

std::vector<lanelet::validation::DetectedIssues> validateMap(
const std::string & projector_type, const std::string & map_file,
const lanelet::validation::ValidationConfig & val_config)
{
std::vector<lanelet::validation::DetectedIssues> issues;
lanelet::LaneletMapPtr map{nullptr};
lanelet::validation::Strings errors;
try {
const auto projector = getProjector(projector_type, val_config.origin);
if (!projector) {
errors.push_back("No valid map projection type specified!");
} else {
map = lanelet::load(map_file, *projector, &errors);
}
if (map) {
appendIssues(issues, lanelet::validation::validateMap(*map, val_config));
} else {
errors.push_back("Failed to load map!");
}
if (!errors.empty()) {
issues.emplace_back("general", utils::transform(errors, [](auto & error) {
return lanelet::validation::Issue(
lanelet::validation::Severity::Error, error);
}));
}
} catch (lanelet::LaneletError & err) {
issues.emplace_back("general", utils::transform(errors, [](auto & error) {
return lanelet::validation::Issue(
lanelet::validation::Severity::Error, error);
}));
}

return issues;
return lanelet::validation::validateMap(
const_cast<lanelet::LaneletMap &>(lanelet_map), val_config);
}

Validators parse_validators(const json & json_data)
Expand Down Expand Up @@ -326,9 +279,10 @@ lanelet::validation::ValidationConfig replace_validator(
return temp;
}

void process_requirements(json json_data, const MetaConfig & validator_config)
void process_requirements(
json json_data, const MetaConfig & validator_config, const lanelet::LaneletMap & lanelet_map)
{
std::vector<lanelet::validation::DetectedIssues> issues;
std::vector<lanelet::validation::DetectedIssues> total_issues;

// List up validators in order
Validators validators = parse_validators(json_data);
Expand All @@ -338,44 +292,41 @@ void process_requirements(json json_data, const MetaConfig & validator_config)
if (auto unused_validator_issues =
describe_unused_validators_to_json(json_data, remaining_validators);
!unused_validator_issues.empty()) {
appendIssues(issues, std::move(unused_validator_issues));
appendIssues(total_issues, std::move(unused_validator_issues));
}

// Main validation process
while (!validation_queue.empty()) {
std::string validator_name = validation_queue.front();
const std::string validator_name = validation_queue.front();
validation_queue.pop();

std::vector<lanelet::validation::DetectedIssues> temp_issues;

// Check prerequisites are OK
appendIssues(temp_issues, check_prerequisite_completion(validators, validator_name));

if (temp_issues.size() == 0) {
// Validate map
appendIssues(
temp_issues,
validateMap(
validator_config.projector_type, validator_config.command_line_config.mapFile,
replace_validator(
validator_config.command_line_config.validationConfig, validator_name)));
}
const auto prerequisite_issues = check_prerequisite_completion(validators, validator_name);
appendIssues(total_issues, prerequisite_issues);

// NOTE: if prerequisite_issues is not empty, skip the content validation process
const auto issues =
prerequisite_issues.empty()
? apply_validation(
lanelet_map, replace_validator(
validator_config.command_line_config.validationConfig, validator_name))
: std::vector<lanelet::validation::DetectedIssues>();

// Add validation results to the json data
json & validator_json = find_validator_block(json_data, validator_name);
if (temp_issues.size() == 0) {
if (issues.empty()) {
validator_json["passed"] = true;
continue;
}

if (temp_issues[0].warnings().size() + temp_issues[0].errors().size() == 0) {
if (issues[0].warnings().size() + issues[0].errors().size() == 0) {
validator_json["passed"] = true;
} else {
validator_json["passed"] = false;
}
if (temp_issues[0].issues.size() > 0) {
if (!issues[0].issues.empty()) {
json issues_json;
for (const auto & issue : temp_issues[0].issues) {
for (const auto & issue : issues[0].issues) {
json issue_json;
issue_json["severity"] = lanelet::validation::toString(issue.severity);
issue_json["primitive"] = lanelet::validation::toString(issue.primitive);
Expand All @@ -392,12 +343,12 @@ void process_requirements(json json_data, const MetaConfig & validator_config)
}
validator_json["issues"] = issues_json;
}
appendIssues(issues, std::move(temp_issues));
appendIssues(total_issues, issues);
}

// Show results
summarize_validator_results(json_data);
lanelet::validation::printAllIssues(issues);
lanelet::validation::printAllIssues(total_issues);

// Save results
if (!validator_config.output_file_path.empty()) {
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
// Copyright 2024 Autoware Foundation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef LANELET2_MAP_VALIDATOR__MAP_LOADER_HPP_ // NOLINT
#define LANELET2_MAP_VALIDATOR__MAP_LOADER_HPP_ // NOLINT

#include <lanelet2_io/Io.h>
#include <lanelet2_projection/UTM.h>
#include <lanelet2_validation/Validation.h>

#include <memory>
#include <string>
#include <utility>
#include <vector>

namespace lanelet::autoware::validation
{

std::pair<lanelet::LaneletMapPtr, std::vector<lanelet::validation::DetectedIssues>>
loadAndValidateMap(
const std::string & projector_type, const std::string & map_file,
const lanelet::validation::ValidationConfig & val_config);

} // namespace lanelet::autoware::validation

#endif // LANELET2_MAP_VALIDATOR__MAP_LOADER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,21 @@
#include <lanelet2_validation/ValidatorFactory.h>

#include <string>
#include <type_traits>
#include <vector>

namespace lanelet::autoware::validation
{
template <typename T>
void appendIssues(std::vector<T> & to, std::vector<T> && from)
template <typename Container, typename T>
auto appendIssues(std::vector<T> & to, Container && from) ->
typename std::enable_if_t<std::is_same_v<T, typename std::decay_t<Container>::value_type>, void>
{
to.insert(to.end(), std::make_move_iterator(from.begin()), std::make_move_iterator(from.end()));
if constexpr (std::is_rvalue_reference<decltype(from)>::value) {
to.insert(to.end(), std::make_move_iterator(from.begin()), std::make_move_iterator(from.end()));
}
if constexpr (std::is_lvalue_reference<decltype(from)>::value) {
to.insert(to.end(), from.begin(), from.end());
}
}

template <typename T>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,9 @@

#include <nlohmann/json.hpp>

#include <lanelet2_io/Io.h>
#include <lanelet2_projection/UTM.h>
#include <lanelet2_validation/Cli.h>
#include <lanelet2_validation/Validation.h>

#include <memory>
#include <queue>
#include <regex>
#include <string>
Expand All @@ -36,16 +33,6 @@

using json = nlohmann::json;

namespace
{
namespace projector_names
{
constexpr const char * mgrs = "mgrs";
constexpr const char * transverse_mercator = "transverse_mercator";
constexpr const char * utm = "utm";
} // namespace projector_names
} // namespace

namespace lanelet::autoware::validation
{
struct ValidatorInfo
Expand All @@ -58,11 +45,8 @@ struct ValidatorInfo

using Validators = std::unordered_map<std::string, ValidatorInfo>;

std::unique_ptr<lanelet::Projector> getProjector(
const std::string & projector_type, const lanelet::GPSPoint & origin);

std::vector<lanelet::validation::DetectedIssues> validateMap(
const std::string & projector_type, const std::string & map_file,
std::vector<lanelet::validation::DetectedIssues> apply_validation(
const lanelet::LaneletMap & lanelet_map,
const lanelet::validation::ValidationConfig & val_config);

Validators parse_validators(const json & json_data);
Expand All @@ -85,7 +69,8 @@ lanelet::validation::ValidationConfig replace_validator(
const lanelet::validation::ValidationConfig & input, const std::string & validator_name);

void process_requirements(
json json_data, const lanelet::autoware::validation::MetaConfig & validator_config);
json json_data, const lanelet::autoware::validation::MetaConfig & validator_config,
const lanelet::LaneletMap & lanelet_map);
} // namespace lanelet::autoware::validation

#endif // LANELET2_MAP_VALIDATOR__VALIDATION_HPP_
Loading

0 comments on commit 8fdd418

Please sign in to comment.