Skip to content

Commit

Permalink
feat(lanelet2_map_validator): check local coordinates declaration (#194)
Browse files Browse the repository at this point in the history
* Implement mapping.lane.local_coordinates_declaration

Signed-off-by: TaikiYamada4 <[email protected]>

* Added test for mapping.lane.local_coordinates_declaration

Signed-off-by: TaikiYamada4 <[email protected]>

* Added documents for mapping.lane.local_coordinates_declaration

Signed-off-by: TaikiYamada4 <[email protected]>

---------

Signed-off-by: TaikiYamada4 <[email protected]>
  • Loading branch information
TaikiYamada4 authored Jan 27, 2025
1 parent 9c0fcc1 commit c12383c
Show file tree
Hide file tree
Showing 8 changed files with 670 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
# local_coordinates_declaration

## Validator name

mapping.lane.local_coordinates_declaration

## Feature

This validator checks whether local coordinates are declared to each point in a Lanelet2 map if one or more points have local coordinates. If a Lanelet2 map is made to have local coordinates, each point MUST have both a `local_x` tag and a `local_y` tag.

If the Lanelet2 map is NOT made to have local coordinates and doesn't have a single point with `local_x` or `local_y` declared, this validator ignores the map and outputs no issues.

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

| Issue Code | Message | Severity | Primitive | Description | Approach |
| ------------------------------------ | ---------------------------------------------------------- | -------- | --------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------ |
| Lane.LocalCoordinatesDeclaration-001 | This point doesn't have local coordinates while others do. | Error | Point | The map has a point that has tags `local_x` and `local_y` but this point doesn't have them. All points in a map must be set to have both tags or not at all. | Be sure to align whether each point has or does not have both tabs `local_x` and `local_y` |
| Lane.LocalCoordinatesDeclaration-002 | "local_x" is declared but "local_y" is not." | Error | Point | The point has a `local_x` tag but doesn't have a `local_y` tag. | Be sure that all points have both tags `local_x` and `local_y`. |
| Lane.LocalCoordinatesDeclaration-003 | "local_y" is declared but "local_x" is not." | Error | Point | The point has a `local_y` tag but doesn't have a `local_x` tag. | Be sure that all points have both tags `local_x` and `local_y`. |

## Related source codes

- local_coordinates_declaration.cpp
- local_coordinates_declaration.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
// 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__LANE__LOCAL_COORDINATES_DECLARATION_HPP_
#define LANELET2_MAP_VALIDATOR__VALIDATORS__LANE__LOCAL_COORDINATES_DECLARATION_HPP_

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

namespace lanelet::autoware::validation
{
class LocalCoordinatesDeclarationValidator : public lanelet::validation::MapValidator
{
public:
// Write the validator's name here
constexpr static const char * name() { return "mapping.lane.local_coordinates_declaration"; }

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

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

#endif // LANELET2_MAP_VALIDATOR__VALIDATORS__LANE__LOCAL_COORDINATES_DECLARATION_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,96 @@
// 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/lane/local_coordinates_declaration.hpp"

#include "lanelet2_core/LaneletMap.h"
#include "lanelet2_map_validator/utils.hpp"

#include <set>

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

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

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

return issues;
}

lanelet::validation::Issues
LocalCoordinatesDeclarationValidator::check_local_coordinates_declaration(
const lanelet::LaneletMap & map)
{
lanelet::validation::Issues issues;

bool is_local_mode = false;

std::set<lanelet::Id> non_local_point_ids;

for (const lanelet::ConstPoint3d & point : map.pointLayer) {
bool local_x = point.hasAttribute("local_x");
bool local_y = point.hasAttribute("local_y");

if (!is_local_mode) {
if (local_x || local_y) {
is_local_mode = true;
for (const lanelet::Id & id : non_local_point_ids) {
issues.emplace_back(
lanelet::validation::Severity::Error, lanelet::validation::Primitive::Point, id,
append_issue_code_prefix(
this->name(), 1, "This point doesn't have local coordinates while others do."));
}
} else {
non_local_point_ids.insert(point.id());
}
continue;
}

// Points are assumed to have local_x and local_y from here
if (!local_x && !local_y) {
issues.emplace_back(
lanelet::validation::Severity::Error, lanelet::validation::Primitive::Point, point.id(),
append_issue_code_prefix(
this->name(), 1, "This point doesn't have local coordinates while others do."));
}

// Only one coordinate (local_x or local_y) is defined
if (local_x && !local_y) {
issues.emplace_back(
lanelet::validation::Severity::Error, lanelet::validation::Primitive::Point, point.id(),
append_issue_code_prefix(
this->name(), 2, "\"local_x\" is declared but \"local_y\" is not."));
continue;
}

if (!local_x && local_y) {
issues.emplace_back(
lanelet::validation::Severity::Error, lanelet::validation::Primitive::Point, point.id(),
append_issue_code_prefix(
this->name(), 3, "\"local_y\" is declared but \"local_x\" is not."));
continue;
}
}

return issues;
}
} // namespace lanelet::autoware::validation
Original file line number Diff line number Diff line change
@@ -0,0 +1,105 @@
<?xml version="1.0" encoding="UTF-8"?>
<osm generator="VMB">
<MetaInfo format_version="1" map_version="2"/>
<node id="8" lat="35.90312398544" lon="139.93324675646">
<tag k="local_x" v="3736.8634"/>
<tag k="local_y" v="73729.1154"/>
<tag k="ele" v="19.3488"/>
</node>
<node id="9" lat="35.90313706429" lon="139.93327698894">
<tag k="local_x" v="3739.6075"/>
<tag k="local_y" v="73730.5363"/>
<tag k="ele" v="19.3413"/>
</node>
<node id="11" lat="35.90314993972" lon="139.93330675322">
<tag k="local_x" v="3742.3091"/>
<tag k="local_y" v="73731.9351"/>
<tag k="ele" v="19.3397"/>
</node>
<node id="12" lat="35.90316376045" lon="139.93333870223">
<tag k="local_x" v="3745.209"/>
<tag k="local_y" v="73733.4366"/>
<tag k="ele" v="19.3724"/>
</node>
<node id="13" lat="35.90317715959" lon="139.9333696751">
<tag k="local_x" v="3748.0203"/>
<tag k="local_y" v="73734.8923"/>
<tag k="ele" v="19.3259"/>
</node>
<node id="14" lat="35.90319132639" lon="139.93340242399">
<tag k="local_x" v="3750.9928"/>
<tag k="local_y" v="73736.4314"/>
<tag k="ele" v="19.3117"/>
</node>
<node id="15" lat="35.90320867521" lon="139.93344252692">
<tag k="local_x" v="3754.6328"/>
<tag k="local_y" v="73738.3162"/>
<tag k="ele" v="19.2979"/>
</node>
<node id="16" lat="35.90310010653" lon="139.93326236239">
<tag k="local_x" v="3738.2428"/>
<tag k="local_y" v="73726.4514"/>
<tag k="ele" v="19.3488"/>
</node>
<node id="17" lat="35.90311318447" lon="139.93329259488">
<tag k="local_x" v="3740.9869"/>
<tag k="local_y" v="73727.8722"/>
<tag k="ele" v="19.3413"/>
</node>
<node id="19" lat="35.9031260608" lon="139.93332235914">
<tag k="local_x" v="3743.6885"/>
<tag k="local_y" v="73729.2711"/>
<tag k="ele" v="19.3397"/>
</node>
<node id="20" lat="35.90313988152" lon="139.93335430814">
<tag k="local_x" v="3746.5884"/>
<tag k="local_y" v="73730.7726"/>
<tag k="ele" v="19.3724"/>
</node>
<node id="21" lat="35.90315328156" lon="139.933385281">
<tag k="local_x" v="3749.3997"/>
<tag k="local_y" v="73732.2284"/>
<tag k="ele" v="19.3259"/>
</node>
<node id="22" lat="35.90316744746" lon="139.93341802989">
<tag k="local_x" v="3752.3722"/>
<tag k="local_y" v="73733.7674"/>
<tag k="ele" v="19.3117"/>
</node>
<node id="23" lat="35.90318479537" lon="139.93345813282">
<tag k="local_x" v="3756.0122"/>
<tag k="local_y" v="73735.6521"/>
<tag k="ele" v="19.2979"/>
</node>
<way id="10">
<nd ref="8"/>
<nd ref="9"/>
<nd ref="11"/>
<nd ref="12"/>
<nd ref="13"/>
<nd ref="14"/>
<nd ref="15"/>
<tag k="type" v="line_thin"/>
<tag k="subtype" v="solid"/>
</way>
<way id="18">
<nd ref="16"/>
<nd ref="17"/>
<nd ref="19"/>
<nd ref="20"/>
<nd ref="21"/>
<nd ref="22"/>
<nd ref="23"/>
<tag k="type" v="line_thin"/>
<tag k="subtype" v="solid"/>
</way>
<relation id="24">
<member type="way" role="left" ref="10"/>
<member type="way" role="right" ref="18"/>
<tag k="type" v="lanelet"/>
<tag k="subtype" v="road"/>
<tag k="speed_limit" v="10"/>
<tag k="location" v="urban"/>
<tag k="one_way" v="yes"/>
</relation>
</osm>
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
<?xml version="1.0" encoding="UTF-8"?>
<osm generator="VMB">
<MetaInfo format_version="1" map_version="2"/>
<node id="8" lat="35.90312398544" lon="139.93324675646">
<tag k="ele" v="19.3488"/>
</node>
<node id="9" lat="35.90313706429" lon="139.93327698894">
<tag k="ele" v="19.3413"/>
</node>
<node id="11" lat="35.90314993972" lon="139.93330675322">
<tag k="ele" v="19.3397"/>
</node>
<node id="12" lat="35.90316376045" lon="139.93333870223">
<tag k="local_x" v="3745.209"/>
<tag k="local_y" v="73733.4366"/>
<tag k="ele" v="19.3724"/>
</node>
<node id="13" lat="35.90317715959" lon="139.9333696751">
<tag k="local_x" v="3748.0203"/>
<tag k="local_y" v="73734.8923"/>
<tag k="ele" v="19.3259"/>
</node>
<node id="14" lat="35.90319132639" lon="139.93340242399">
<tag k="local_x" v="3750.9928"/>
<tag k="local_y" v="73736.4314"/>
<tag k="ele" v="19.3117"/>
</node>
<node id="15" lat="35.90320867521" lon="139.93344252692">
<tag k="local_x" v="3754.6328"/>
<tag k="local_y" v="73738.3162"/>
<tag k="ele" v="19.2979"/>
</node>
<node id="16" lat="35.90310010653" lon="139.93326236239">
<tag k="local_x" v="3738.2428"/>
<tag k="local_y" v="73726.4514"/>
<tag k="ele" v="19.3488"/>
</node>
<node id="17" lat="35.90311318447" lon="139.93329259488">
<tag k="local_x" v="3740.9869"/>
<tag k="local_y" v="73727.8722"/>
<tag k="ele" v="19.3413"/>
</node>
<node id="19" lat="35.9031260608" lon="139.93332235914">
<tag k="local_x" v="3743.6885"/>
<tag k="local_y" v="73729.2711"/>
<tag k="ele" v="19.3397"/>
</node>
<node id="20" lat="35.90313988152" lon="139.93335430814">
<tag k="local_x" v="3746.5884"/>
<tag k="local_y" v="73730.7726"/>
<tag k="ele" v="19.3724"/>
</node>
<node id="21" lat="35.90315328156" lon="139.933385281">
<tag k="local_x" v="3749.3997"/>
<tag k="local_y" v="73732.2284"/>
<tag k="ele" v="19.3259"/>
</node>
<node id="22" lat="35.90316744746" lon="139.93341802989">
<tag k="local_x" v="3752.3722"/>
<tag k="local_y" v="73733.7674"/>
<tag k="ele" v="19.3117"/>
</node>
<node id="23" lat="35.90318479537" lon="139.93345813282">
<tag k="local_x" v="3756.0122"/>
<tag k="local_y" v="73735.6521"/>
<tag k="ele" v="19.2979"/>
</node>
<way id="10">
<nd ref="8"/>
<nd ref="9"/>
<nd ref="11"/>
<nd ref="12"/>
<nd ref="13"/>
<nd ref="14"/>
<nd ref="15"/>
<tag k="type" v="line_thin"/>
<tag k="subtype" v="solid"/>
</way>
<way id="18">
<nd ref="16"/>
<nd ref="17"/>
<nd ref="19"/>
<nd ref="20"/>
<nd ref="21"/>
<nd ref="22"/>
<nd ref="23"/>
<tag k="type" v="line_thin"/>
<tag k="subtype" v="solid"/>
</way>
<relation id="24">
<member type="way" role="left" ref="10"/>
<member type="way" role="right" ref="18"/>
<tag k="type" v="lanelet"/>
<tag k="subtype" v="road"/>
<tag k="speed_limit" v="10"/>
<tag k="location" v="urban"/>
<tag k="one_way" v="yes"/>
</relation>
</osm>
Loading

0 comments on commit c12383c

Please sign in to comment.