Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(lanelet2_map_validator): check whether intersection_area satisfies vm-03-08 #171

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions map/autoware_lanelet2_map_validator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,8 @@ if(BUILD_TESTING)
add_validation_test(regulatory_elements_details_for_traffic_lights)
add_validation_test(traffic_light_facing)
add_validation_test(missing_referrers_for_traffic_lights)
add_validation_test(intersection_area_validity)
add_validation_test(intersection_area_segment_type)
endif()

ament_auto_package(
Expand Down
2 changes: 1 addition & 1 deletion map/autoware_lanelet2_map_validator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -322,7 +322,7 @@ The "Validators" column will be blank if it hasn't be implemented.
| vm-03-05 | Lanelet division in the intersection | |
| vm-03-06 | Guide lines in the intersection | |
| vm-03-07 | Multiple lanelets in the intersection | |
| vm-03-08 | Intersection Area range | |
| vm-03-08 | Intersection Area range | [mapping.intersection.intersection_area_validity](./docs/intersection/intersection_area_validity.md), [mapping.intersection.intersection_area_segment_type](./docs/intersection/intersection_area_segment_type.md) |
| vm-03-09 | Range of Lanelet in the intersection | |
| vm-03-10 | Right of way (with signal) | |
| vm-03-11 | Right of way (without signal) | |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,17 @@
}
]
},
{
"id": "vm-03-08",
"validators": [
{
"name": "mapping.intersection.intersection_area_validity"
},
{
"name": "mapping.intersection.intersection_area_segment_type"
}
]
},
{
"id": "vm-04-01",
"validators": [
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
# intersection_area_segment_type

## Validator name

mapping.intersection.intersection_area_segment_type

## Feature

This validator check whether each `intersection_area` type polygon is made from points that belong to `road_border` type linestrings or the starting/ending edge of a lanelet.

This is achieved by the following procedure.

1. Create a 2D bounding box that circumscribes the polygon.
2. Collect `road_border` type linestrings within or intersecting the 2D bounding box.
3. Collect starting/ending edges of lanelets within or intersecting the 2D bounding box.
4. Examine each point that constitutes the polygon whether it belongs to the collection above.

The validator outputs the following issue with the corresponding ID of the primitive.

| Issue Code | Message | Severity | Primitive | Description | Approach |
| -------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------- | -------- | --------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------- |
| Intersection.IntersectionAreaSegmentType-001 | "This intersection area is not made by points from road_border linestrings or lanelet edges. (Point ID: \<POINT ID LIST\>)" | Error | Polygon | The `intersection_area` polygon has points that doesn't belong to `road_border` type linestrings or lanelet edges. The violating points are listed up at \<POINT ID LIST\>. | Ensure that the `intersection_area` is formed ONLY by `road_border` linestrings and lanelet edges. |

### Supplementary information

Note that this validator only examines what type of linestring the points constituting the polygon belongs to, and doesn't examine they have a valid connection. Use the `mapping.intersection.intersection_area_validity` to check whether the polygon is `boost::geometry::is_valid()`.

## Related source codes

- intersection_area_segment_type.hpp
- intersection_area_segment_type.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
# intersection_area_validity

## Validator name

mapping.intersection.intersection_area_validity

## Feature

This validator check whether each `intersection_area` type polygon satisfies [`boost::geometry::is_valid`](https://www.boost.io/doc/libs/1_86_0/libs/geometry/doc/html/geometry/reference/algorithms/is_valid/is_valid_2_with_message.html).

The validator outputs the following issue with the corresponding ID of the primitive.

| Issue Code | Message | Severity | Primitive | Description | Approach |
| ----------------------------------------- | --------------------------------------------------------------------------------------- | -------- | --------- | --------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
| Intersection.IntersectionAreaValidity-001 | "This intersection_area doesn't satisfy boost::geometry::is_valid (reason: \<MESSAGE\>) | Error | Polygon | The `intersection_area` polygon didn't satisfy `boost::geometry::is_valid`. | There are several reasons expected and it is written in "(reason: \<MESSAGE\>)". The \<MESSAGE\> is a copy of [the output message defined in the `boost::geometry` library](https://www.boost.org/doc/libs/1_86_0/boost/geometry/policies/is_valid/failing_reason_policy.hpp). |

## Related source codes

- intersection_area_validity.hpp
- intersection_area_validity.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
// 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__VALIDATORS__INTERSECTION__INTERSECTION_AREA_SEGMENT_TYPE_HPP_ // NOLINT
#define LANELET2_MAP_VALIDATOR__VALIDATORS__INTERSECTION__INTERSECTION_AREA_SEGMENT_TYPE_HPP_ // NOLINT

#include <lanelet2_validation/Validation.h>
#include <lanelet2_validation/ValidatorFactory.h>

#include <string>
#include <utility>

namespace lanelet::autoware::validation
{
class IntersectionAreaSegmentTypeValidator : public lanelet::validation::MapValidator
{
public:
constexpr static const char * name()
{
return "mapping.intersection.intersection_area_segment_type";
}

lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override;

private:
/**
* @brief The main validation process
*
* @param map
* @return lanelet::validation::Issues
*/
lanelet::validation::Issues check_intersection_area_segment_type(const lanelet::LaneletMap & map);

/**
* @brief Create a submap consisting of road_border linestrings and lanelet edges only.
*
* @param map
* @param intersection_area
* @return lanelet::LaneletSubmapUPtr
*/
lanelet::LaneletSubmapUPtr create_nearby_borders_submap(
const lanelet::LaneletMap & map, const lanelet::ConstPolygon3d & intersection_area);

/**
* @brief Create a list-up-string from Ids=vector<Id>
*
* @param ids
* @return std::string
*/
std::string ids_to_string(const lanelet::Ids ids);
};
} // namespace lanelet::autoware::validation

// clang-format off
#endif // LANELET2_MAP_VALIDATOR__VALIDATORS__INTERSECTION__INTERSECTION_AREA_SEGMENT_TYPE_HPP_ // NOLINT
// clang-format on
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__VALIDATORS__INTERSECTION__INTERSECTION_AREA_VALIDITY_HPP_ // NOLINT
#define LANELET2_MAP_VALIDATOR__VALIDATORS__INTERSECTION__INTERSECTION_AREA_VALIDITY_HPP_ // NOLINT

#include <lanelet2_validation/Validation.h>
#include <lanelet2_validation/ValidatorFactory.h>

namespace lanelet::autoware::validation
{
class IntersectionAreaValidityValidator : public lanelet::validation::MapValidator
{
public:
constexpr static const char * name() { return "mapping.intersection.intersection_area_validity"; }

lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override;

private:
lanelet::validation::Issues check_intersection_area_validity(const lanelet::LaneletMap & map);
};
} // namespace lanelet::autoware::validation

// clang-format off
#endif // LANELET2_MAP_VALIDATOR__VALIDATORS__INTERSECTION__INTERSECTION_AREA_VALIDITY_HPP_ // NOLINT
// clang-format on
Original file line number Diff line number Diff line change
@@ -0,0 +1,152 @@
// 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/validators/intersection/intersection_area_segment_type.hpp"

#include "lanelet2_map_validator/utils.hpp"

#include <boost/geometry/algorithms/is_valid.hpp>

#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_core/geometry/Polygon.h>
#include <lanelet2_core/primitives/Polygon.h>

#include <limits>

namespace lanelet::autoware::validation
{
namespace
{
lanelet::validation::RegisterMapValidator<IntersectionAreaSegmentTypeValidator> reg;
}

lanelet::validation::Issues IntersectionAreaSegmentTypeValidator::operator()(
const lanelet::LaneletMap & map)
{
lanelet::validation::Issues issues;

lanelet::autoware::validation::appendIssues(issues, check_intersection_area_segment_type(map));

return issues;
}

lanelet::validation::Issues
IntersectionAreaSegmentTypeValidator::check_intersection_area_segment_type(
const lanelet::LaneletMap & map)
{
lanelet::validation::Issues issues;

for (const lanelet::ConstPolygon3d & polygon3d : map.polygonLayer) {
if (
!polygon3d.hasAttribute(lanelet::AttributeName::Type) ||
polygon3d.attribute(lanelet::AttributeName::Type).value() != "intersection_area") {
continue;
}

const auto borders_submap = create_nearby_borders_submap(map, polygon3d);
lanelet::Ids invalid_point_ids = {};
for (const lanelet::ConstPoint3d & point : polygon3d) {
lanelet::LineStrings3d search_results = borders_submap->lineStringLayer.findUsages(point);
if (search_results.empty()) {
invalid_point_ids.push_back(point.id());
}
}
if (!invalid_point_ids.empty()) {
issues.emplace_back(
lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon,
polygon3d.id(),
append_issue_code_prefix(
this->name(), 1,
"This intersection area is not made by points from road_border linestrings or lanelet "
"edges. (Point ID: " +
ids_to_string(invalid_point_ids) + ")"));
}
}

return issues;
}

lanelet::LaneletSubmapUPtr IntersectionAreaSegmentTypeValidator::create_nearby_borders_submap(
const lanelet::LaneletMap & map, const lanelet::ConstPolygon3d & intersection_area)
{
lanelet::BoundingBox2d bbox2d =
lanelet::geometry::boundingBox2d(lanelet::traits::toBasicPolygon2d(intersection_area));

lanelet::ConstLanelets nearby_lanelets = map.laneletLayer.search(bbox2d);
lanelet::ConstLineStrings3d nearby_linestrings = map.lineStringLayer.search(bbox2d);

lanelet::LineStrings3d nearby_borders;

// Collect lanelet edges intersecting the intersection area
for (const auto & lanelet : nearby_lanelets) {
if (
!lanelet.hasAttribute(lanelet::AttributeName::Subtype) ||
lanelet.attribute(lanelet::AttributeName::Subtype).value() !=
lanelet::AttributeValueString::Road) {
continue;
}

if (bbox2d.contains(lanelet.leftBound2d().front().basicPoint2d())) {
lanelet::Point3d left_point(lanelet.leftBound().front());
lanelet::Point3d right_point(lanelet.rightBound().front());

lanelet::AttributeMap attribute;
attribute["type"] = "lanelet_edge"; // An instant linestring type for this code

lanelet::LineString3d lanelet_front_edge(
lanelet::utils::getId(), {left_point, right_point}, attribute);
nearby_borders.push_back(lanelet_front_edge);
}

if (bbox2d.contains(lanelet.leftBound2d().back().basicPoint2d())) {
lanelet::Point3d left_point(lanelet.leftBound().back());
lanelet::Point3d right_point(lanelet.rightBound().back());

lanelet::AttributeMap attribute;
attribute["type"] = "lanelet_edge"; // An instant linestring type for this code

lanelet::LineString3d lanelet_back_edge(
lanelet::utils::getId(), {left_point, right_point}, attribute);
nearby_borders.push_back(lanelet_back_edge);
}
}

// Collect road_border subtype linestrings
for (const auto & linestring : nearby_linestrings) {
if (
linestring.hasAttribute(lanelet::AttributeName::Type) &&
linestring.attribute(lanelet::AttributeName::Type).value() ==
lanelet::AttributeValueString::RoadBorder) {
auto data = std::const_pointer_cast<LineStringData>(linestring.constData());
nearby_borders.push_back(lanelet::LineString3d(data, linestring.inverted()));
}
}

return lanelet::utils::createSubmap(nearby_borders);
}

std::string IntersectionAreaSegmentTypeValidator::ids_to_string(const lanelet::Ids ids)
{
std::string result = "(";
for (size_t i = 0; i < ids.size(); i++) {
result += std::to_string(ids[i]);
if (i < ids.size() - 1) {
result += ", ";
}
}
result += ")";
return result;
}

} // namespace lanelet::autoware::validation
Loading
Loading