diff --git a/map/autoware_lanelet2_map_validator/CMakeLists.txt b/map/autoware_lanelet2_map_validator/CMakeLists.txt new file mode 100644 index 00000000..a8065ed1 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/CMakeLists.txt @@ -0,0 +1,46 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_lanelet2_map_validator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_find_build_dependencies() +find_package(nlohmann_json REQUIRED) + +include_directories( + src +) + +file(GLOB_RECURSE autoware_lanelet2_map_validator_lib_src + src/common/*.cpp + src/validators/*.cpp +) +ament_auto_add_library(autoware_lanelet2_map_validator_lib SHARED + ${autoware_lanelet2_map_validator_lib_src} +) + +ament_auto_add_executable(autoware_lanelet2_map_validator src/main.cpp) +add_dependencies(autoware_lanelet2_map_validator autoware_lanelet2_map_validator_lib) +target_link_libraries(autoware_lanelet2_map_validator + autoware_lanelet2_map_validator_lib + nlohmann_json +) + +if(BUILD_TESTING) + function(add_validation_test VALIDATION_NAME) + ament_add_ros_isolated_gtest( + ${VALIDATION_NAME}_test + test/src/test_${VALIDATION_NAME}.cpp + ) + target_link_libraries( + ${VALIDATION_NAME}_test + autoware_lanelet2_map_validator_lib + nlohmann_json + ) + endfunction() + + add_validation_test(missing_regulatory_elements) + add_validation_test(regulatory_element_details) +endif() + +ament_auto_package() diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md new file mode 100644 index 00000000..f20eab92 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/README.md @@ -0,0 +1,313 @@ +# autoware_lanelet2_map_validator + +`autoware_lanelet2_map_validator` is a tool to validate Lanelet2 maps to ensure that Autoware can work properly with it. + +This validation tool is an extension of [lanelet2_validation](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/tree/master/lanelet2_validation) so that Autoware specific rules can be applied. As you can see from the codes in the `src/validators` directory, the group of validators belong to this tool inherits the [lanelet::validation::MapValidator class](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/blob/master/lanelet2_validation/include/lanelet2_validation/BasicValidator.h#L17) from the original `lanelet2_validation`. Therefore, we believe that reading the source code of the `lanelet2_validation` will help you understand this tool better. + +**Note that this validator is still on construction that there are only a few rules and a template to define those rules.** + +The official Autoware requirements for lanelet2 maps are described in [Vector Map creation requirement specifications (in Autoware Documentation)](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/). + +## Design concept + +The `autoware_lanelet2_map_validator` is designed to validate `.osm` map files by using and extending the [lanelet2_validation](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/tree/master/lanelet2_validation) package for Autoware. + +`autoware_lanelet2_map_validator` takes the lanelet2 map (.osm file) and requirement set (JSON file, optional) as the input, and output validation results to the console. + +If a requirement set is given, `autoware_lanelet2_map_validator` also outputs validation results reflecting the input requirement set. +See ["Run with a requirement set"](#run-with-a-requirement-set) for further information, ["Input file"](#input-file) to understand the input format, and ["Output file"](#output-file) to understand the output format. + +![autoware_lanelet2_map_validator_architecture](./media/autoware_lanelet2_map_validator_architecture.drawio.svg) + +## How to use + +Basically, you can use the following command to execute `autoware_lanelet2_map_validator`. However, note that `autoware_lanelet2_map_validator` is a ROS/rclcpp free tool, so you can just run the built executable whatever way. + +```bash +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator +``` + +### Run ALL validators + +You can use `autoware_lanelet2_map_validator` with the following command. This will run all validators including the default built-in validators in the [lanelet2_validation](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/tree/master/lanelet2_validation). + +```bash +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --map_file path/to_your/lanelet2_map.osm +``` + +### Run a specific validator + +`autoware_lanelet2_map_validator` consists of multiple small validators in order to realize complex requirements with a combination of them. +If you want to call a few validators, you can select them with the `--validator, -v` option. + +```bash +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --map_file path/to_your/lanelet2_map.osm --validator mapping.traffic_light.missing_regulatory_elements +``` + +You can get a list of available validators with the `--print, -p` option. + +```bash +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --print +``` + +### Run with a requirement set + +`autoware_lanelet2_map_validator` can manage to run a group of validators by a list of validator names. +`autoware_lanelet2_map_validator` will scan through the input JSON file given by the `--input_requirements, -i` option, and output the validation results to the directory given by the `--output_directory, -o` option. +The output filename will be `lanelet2_validation_results.json`. + +```bash +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --input_requirements autoware_requirements_set.json --output_directory ./ +``` + +#### Input file + +The JSON file input should follow the structure like this example. + +```json +{ + "version": "0.1.0", + "requirements": [ + { + "id": "example-01-01", + "validators": [ + { + "name": "mapping.crosswalk.missing_regulatory_elements" + }, + { + "name": "mapping.crosswalk.regulatory_element_details" + } + ] + }, + { + "id": "example-01-02", + "validators": [ + { + "name": "mapping.traffic_light.missing_regulatory_elements" + }, + { + "name": "mapping.traffic_light.regulatory_element_details" + } + ] + }, + { + "id": "example-01-03", + "validators": [ + { + "name": "mapping.stop_line.missing_regulatory_elements" + } + ] + } + ] +} +``` + +- MUST have a single `requirements` field. +- The `requirements` field MUST be a list of requirements. A requirement MUST have + - `id` : The id of the requirement. Its name is arbitrary. + - `validators` : A list of validators that structures the requirement. + - A validator MUST be given with its name on the `name` field. + - The name list of available validators can be obtained from the `--print` option. +- The user can write any other field (like `version`) besides `requirements`. + +#### Output file + +When the `input_requirements` is thrown to `autoware_lanelet2_map_validator`, it will output a `lanelet2_validation_results.json` file which looks like the following example. + +```json +{ + "requirements": [ + { + "id": "example-01-01", + "passed": false, + "validators": [ + { + "issues": [ + { + "id": 163, + "message": "No regulatory element refers to this crosswalk.", + "primitive": "lanelet", + "severity": "Error" + }, + { + "id": 164, + "message": "No regulatory element refers to this crosswalk.", + "primitive": "lanelet", + "severity": "Error" + }, + { + "id": 165, + "message": "No regulatory element refers to this crosswalk.", + "primitive": "lanelet", + "severity": "Error" + }, + { + "id": 166, + "message": "No regulatory element refers to this crosswalk.", + "primitive": "lanelet", + "severity": "Error" + } + ], + "name": "mapping.crosswalk.missing_regulatory_elements", + "passed": false + }, + { + "name": "mapping.crosswalk.regulatory_element_details", + "passed": true + } + ] + }, + { + "id": "example-01-02", + "passed": false, + "validators": [ + { + "name": "mapping.traffic_light.missing_regulatory_elements", + "passed": true + }, + { + "issues": [ + { + "id": 9896, + "message": "Regulatory element of traffic light must have a stop line(ref_line).", + "primitive": "regulatory element", + "severity": "Error" + }, + { + "id": 9918, + "message": "Regulatory element of traffic light must have a stop line(ref_line).", + "primitive": "regulatory element", + "severity": "Error" + }, + { + "id": 9838, + "message": "Regulatory element of traffic light must have a stop line(ref_line).", + "primitive": "regulatory element", + "severity": "Error" + }, + { + "id": 9874, + "message": "Regulatory element of traffic light must have a stop line(ref_line).", + "primitive": "regulatory element", + "severity": "Error" + } + ], + "name": "mapping.traffic_light.regulatory_element_details", + "passed": false + } + ] + }, + { + "id": "example-01-03", + "passed": true, + "validators": [ + { + "name": "mapping.stop_line.missing_regulatory_elements", + "passed": true + } + ] + } + ], + "version": "0.1.0" +} +``` + +- `lanelet2_validation_results.json` inherits the JSON file of `input_requirements` and add results to it. + - So non-required fields (line `version`) remains in the output. +- `autoware_lanelet2_map_validator` adds a boolean `passed` field to each requirement. If all validators of the requirement have been passed, the `passed` field of the requirement will be `true` (`false` if not). +- The `passed` field is also given to each validator. If the validator found any issues the `passed` field will turn to be `false` (`true` if not), and adds an `issues` field which is a list of issues found. Each issue contains information of `severity`, `primitive`, `id`, and `message`. + +### Available command options + +| option | description | +| -------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `-h, --help` | Explains about this tool and show a list of options | +| `--print` | Print all available checker without running them | +| `-m, --map_file` | Path to the map to be validated | +| `-i, --input_requirements` | Path to the JSON file where the list of requirements and validations is written | +| `-o, --output_directory` | Directory to save the list of validation results in a JSON format | +| `-v, --validator` | Comma separated list of regexes to filter the applicable validators. Will run all validators by default. Example: `mapping.*` to run all checks for the mapping | +| `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | +| `-l, --location` | Location of the map (for instantiating the traffic rules), e.g. de for Germany | +| `--participants` | Participants for which the routing graph will be instantiated (default: vehicle) | +| `--lat` | latitude coordinate of map origin. This is required for the transverse mercator and utm projector. | +| `--lon` | longitude coordinate of map origin. This is required for the transverse mercator and utm projector. | + +### Available validators + +Since there will be hundreds of validators in the future, the documents for each validator should categorized in the docs file. +The directory structure should be the same to that of the `src/validators` directory. + +#### Stop Line + +- [mapping.stop_line.missing_regulatory_elements](./docs/stop_line/missing_regulatory_elements_for_stop_lines.md) + +#### Traffic Light + +- [mapping.traffic_light.missing_regulatory_elements](./docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md) +- [mapping.traffic_light.regulatory_element_details](./docs/traffic_light/regulatory_element_details_for_traffic_lights.md) + +#### Crosswalk + +- [mapping.crosswalk.missing_regulatory_elements](./docs/crosswalk/missing_regulatory_elements_for_crosswalk.md) +- [mapping.crosswalk.regulatory_element_details](./docs/crosswalk/regulatory_element_details_for_crosswalks.md) + +## Relationship between requirements and validators + +This is a table describing the correspondence between the validators that each requirement consists of. +The "Validators" column will be blank if it hasn't be implemented. + +| ID | Requirements | Validators | +| -------- | ------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| vm-01-01 | Lanelet basics | | +| vm-01-02 | Allowance for lane changes | | +| vm-01-03 | Linestring sharing | | +| vm-01-04 | Sharing of the centerline of lanes for opposing traffic | | +| vm-01-05 | Lane geometry | | +| vm-01-06 | Line position (1) | | +| vm-01-07 | Line position (2) | | +| vm-01-08 | Line position (3) | | +| vm-01-09 | Speed limits | | +| vm-01-10 | Centerline | | +| vm-01-11 | Centerline connection (1) | | +| vm-01-12 | Centerline connection (2) | | +| vm-01-13 | Roads with no centerline (1) | | +| vm-01-14 | Roads with no centerline (2) | | +| vm-01-15 | Road shoulder | | +| vm-01-16 | Road shoulder Linestring sharing | | +| vm-01-17 | Side strip | | +| vm-01-18 | Side strip Linestring sharing | | +| vm-01-19 | Walkway | | +| vm-02-01 | Stop line alignment | | +| vm-02-02 | Stop sign | [mapping.stop_line.missing_regulatory_elements](./docs/stop_line/missing_regulatory_elements_for_stop_lines.md) | +| vm-03-01 | Intersection criteria | | +| vm-03-02 | Lanelet's turn direction and virtual | | +| vm-03-03 | Lanelet width in the intersection | | +| vm-03-04 | Lanelet creation in the intersection | | +| 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-09 | Range of Lanelet in the intersection | | +| vm-03-10 | Right of way (with signal) | | +| vm-03-11 | Right of way (without signal) | | +| vm-03-12 | Right of way supplements | | +| vm-03-13 | Merging from private area, sidewalk | | +| vm-03-14 | Road marking | | +| vm-03-15 | Exclusive bicycle lane | | +| vm-04-01 | Traffic light basics | [mapping.traffic_light.missing_regulatory_elements](./docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md), [mapping.traffic_light.regulatory_element_details](./docs/traffic_light/regulatory_element_details_for_traffic_lights.md) (Undone) | +| vm-04-02 | Traffic light position and size | | +| vm-04-03 | Traffic light lamps | | +| vm-05-01 | Crosswalks across the road | [mapping.crosswalk.missing_regulatory_elements](./docs/crosswalk/missing_regulatory_elements_for_crosswalk.md), [mapping.crosswalk.regulatory_element_details](./docs/crosswalk/regulatory_element_details_for_crosswalks.md) | +| vm-05-02 | Crosswalks with pedestrian signals | | +| vm-05-03 | Deceleration for safety at crosswalks | | +| vm-05-04 | Fences | | +| vm-06-01 | Buffer Zone | | +| vm-06-02 | No parking signs | | +| vm-06-03 | No stopping signs | | +| vm-06-04 | No stopping sections | | +| vm-06-05 | Detection area | | +| vm-07-01 | Vector Map creation range | | +| vm-07-02 | Range of detecting pedestrians who enter the road | | +| vm-07-03 | Guardrails, guard pipes, fences | | +| vm-07-04 | Ellipsoidal height | | diff --git a/map/autoware_lanelet2_map_validator/autoware_requirement_set.json b/map/autoware_lanelet2_map_validator/autoware_requirement_set.json new file mode 100644 index 00000000..6277a712 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/autoware_requirement_set.json @@ -0,0 +1,26 @@ +{ + "requirements": [ + { + "id": "vm-04-01", + "validators": [ + { + "name": "mapping.crosswalk.missing_regulatory_elements" + }, + { + "name": "mapping.crosswalk.regulatory_element_details" + } + ] + }, + { + "id": "vm-05-01", + "validators": [ + { + "name": "mapping.traffic_light.missing_regulatory_elements" + }, + { + "name": "mapping.traffic_light.regulatory_element_details" + } + ] + } + ] +} diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md new file mode 100644 index 00000000..c96ec6d4 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md @@ -0,0 +1,21 @@ +# missing_regulator_elements_for_crosswalk + +## Validator name + +mapping.crosswalk.missing_regulatory_elements + +## Feature + +This validator checks whether each `crosswalk` subtype lanelet has a relevant regulatory element. +Required information for a crosswalk is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_crosswalk/#vm-05-01-crosswalks-across-the-road). + +The output issue marks "lanelet" as the **primitive**, and the lanelet ID is written together as **ID**. + +| Message | Severity | Description | Approach | +| ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------- | +| "No regulatory element refers to this crosswalk." | Error | There is a `crosswalk` subtype lanelet that hasn't been referred to any regulatory element. | Create a `crosswalk` subtype regulatory element and refer to the crosswalk lanelet. | + +## Related source codes + +- missing_regulatory_elements_for_crosswalk.hpp +- missing_regulatory_elements_for_crosswalk.cpp diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md new file mode 100644 index 00000000..62d003e7 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md @@ -0,0 +1,29 @@ +# regulatory_element_details_for_crosswalks + +## Validator name + +mapping.crosswalk.regulatory_element_details + +## Feature + +This validator checks whether the details in the `crosswalk` subtype regulatory elements are valid. +Required information for a crosswalk is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_crosswalk/#vm-05-01-crosswalks-across-the-road). +This validator checks eight types of issues. + +The output issue marks "lanelet", "linestring" or "regulatory_element" as the **primitive**, and the regulatory element ID is written together as **ID**. + +| Message | Severity | Primitive | Description | Approach | +| ---------------------------------------------------------------------------------------- | -------- | ------------------ | ---------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| "Refers of crosswalk regulatory element must have type of crosswalk." | Error | lanelet | There is a `crosswalk` subtype regulatory element whose `refers` is not a `crosswalk` subtype lanelet. | Check that the `refers` is a `crosswalk` subtype lanelet | +| "ref_line of crosswalk regulatory element must have type of stopline." | Error | linestring | There is a `crosswalk` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | Check that the `ref_line` is a `stop_line` type linestring | +| "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon." | Error | polygon | There is a `crosswalk` subtype regulatory element whose `crosswalk_polygon` is not a `crosswalk_polygon` type polygon. | Check that the `crosswalk_polygon` mentioned in the regulatory element refers to a `crosswalk_polygon` type area. | +| "Regulatory element of crosswalk must have lanelet of crosswalk(refers)." | Error | regulatory element | There is a `crosswalk` subtype regulatory element that has no `refers`es. | Write `refers` referring to a `crosswalk` subtype lanelet in the regulatory element | +| "Regulatory element of crosswalk must have only one lanelet of crosswalk(refers)." | Error | regulatory element | There is a `crosswalk` subtype regulatory element that has multiple `refers`es. | A `crosswalk` subtype regulatory element can have only one `refers`. Remove the `refers` that is not a crosswalk lanelet. | +| "Regulatory element of crosswalk does not have stop line(ref_line)." | Info | regulatory element | There is a `crosswalk` subtype regulatory element that has no `ref_line`s | Generally, there should be a stop line for the crosswalk. Be sure that the stop line exists or doesn't. | +| "Regulatory element of crosswalk is nice to have crosswalk_polygon." | Warning | regulatory element | There is a `crosswalk` subtype regulatory element that has no `crosswalk_polygon`s. | It is recommended to surround a crosswalk with a `crosswalk_polygon`. Create one and add a `crosswalk_polygon` role member to the regulatory element with the polygon ID. | +| "Regulatory element of crosswalk must have only one crosswalk_polygon." | Error | regulatory element | There is a `crosswalk` subtype regulatory element that has multiple `crosswalk_polygon`s. | Only one `crosswalk_polygon` is allowed per polygon. Remove the unnecessary ones. | + +## Related source codes + +- regulatory_element_details_for_crosswalks.hpp +- regulatory_element_details_for_crosswalks.cpp diff --git a/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md b/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md new file mode 100644 index 00000000..fb286208 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md @@ -0,0 +1,21 @@ +# missing_regulator_elements_for_stop_lines + +## Validator name + +mapping.stop_line.missing_regulatory_elements + +## Feature + +This validator checks whether each `stop_line` type linestring has a relevant regulatory element. +Required information for a stop line is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_stop_line/#vm-02-02-stop-sign). + +The output issue marks "linestring" as the **primitive**, and the linestring ID is written together as **ID**. + +| Message | Severity | Description | Approach | +| ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | ---------------------------------------------------------- | +| "No regulatory element refers to this stop line." | Error | There is a `stop_line` type linestring that hasn't been referred to any regulatory element. | Create a regulatory element that refers to this stop line. | + +## Related source codes + +- missing_regulatory_elements_for_stop_line.cpp +- missing_regulatory_elements_for_stop_line.hpp diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md new file mode 100644 index 00000000..4bcb311d --- /dev/null +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md @@ -0,0 +1,21 @@ +# missing_regulator_elements_for_traffic_lights + +## Validator name + +mapping.traffic_light.missing_regulatory_elements + +## Feature + +This validator checks whether each `traffic_light` type linestring has a relevant regulatory element. +Required information for traffic lights is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_traffic_light/#vm-04-01-traffic-light-basics). + +The output issue marks "linestring" as the **primitive**, and the linestring ID is written together as **ID**. + +| Message | Severity | Description | Approach | +| ----------------------------------------------------- | -------- | ----------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------- | +| "No regulatory element refers to this traffic light." | Error | There is a `traffic_light` type linestring that hasn't been referred to any regulatory element. | Create a `traffic_light` subtype regulatory element that refers to this linestring | + +## Related source codes + +- missing_regulatory_elements_for_traffic_light.hpp +- missing_regulatory_elements_for_traffic_light.cpp diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md new file mode 100644 index 00000000..29a585d4 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md @@ -0,0 +1,25 @@ +# regulatory_element_details_for_traffic_lights + +## Validator name + +mapping.traffic_light.regulatory_element_details + +## Feature + +This validator checks whether the details in the `traffic_light` subtype regulatory elements are valid. +Required information for traffic lights is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_traffic_light/#vm-04-01-traffic-light-basics). +This validator checks four types of issues. + +The output issue marks "linestring" or "regulatory element" as the **primitive**, and the lanelet ID is written together as **ID**. + +| Message | Severity | Primitive | Description | Approach | +| ----------------------------------------------------------------------------- | -------- | ------------------ | -------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------- | +| "Refers of traffic light regulatory element must have type of traffic_light." | Error | linestring | There is a `traffic_light` subtype regulatory element whose `refers` is not a `traffic_light` type linestring. | Check that the `refers` in the regulatory element is a `traffic_light` type linestring. | +| "ref_line of traffic light regulatory element must have type of stop_line." | Error | linestring | There is a `traffic_light` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | Check that the `ref_line` in the regulatory element is a `stop_line` type linestring | +| "Regulatory element of traffic light must have a traffic light(refers)." | Error | regulatory element | There is a `traffic_light` subtype regulatory element that has no `refers`es. | Add `refers` to the regulatory element that refers to the id of the traffic light linestring. | +| "Regulatory element of traffic light must have a stop line(ref_line)." | Error | regulatory element | There is a `traffic_light` subtype regulatory element that has no `ref_line`s | Add `ref_line` to the regulatory element that refers to the id of the stop line linestring. | + +## Related source codes + +- regulatory_element_details_for_traffic_lights.hpp +- regulatory_element_details_for_traffic_lights.cpp diff --git a/map/autoware_lanelet2_map_validator/media/autoware_lanelet2_map_validator_architecture.drawio.svg b/map/autoware_lanelet2_map_validator/media/autoware_lanelet2_map_validator_architecture.drawio.svg new file mode 100644 index 00000000..1bdada5c --- /dev/null +++ b/map/autoware_lanelet2_map_validator/media/autoware_lanelet2_map_validator_architecture.drawio.svg @@ -0,0 +1,795 @@ + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ autoware_lanelet2_map_validator +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + +
+
+
+ lanelet2_map.osm +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + +
+
+
+ requirement_set.json +
+
+
+
+ +
+
+
+
+ + + + + + + + + + +
+
+
+ lanelet2_validation_results.json +
+
+
+
+ +
+
+
+
+ + + + + + + + + + +
+
+
+ traffic light +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ - mapping.traffic_light.missing_regulatory_elements +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ - mapping.traffic_light.regulatory_element_details +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ - + and more... +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + +
+
+
+ crosswalk +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ - mapping.crosswalk.missing_regulatory_elements +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ - mapping.crosswalk.regulatory_element_details +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ - + and more... +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + +
+
+
+ stop line +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ - mapping.stop_line.missing_regulatory_elements +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + - + + and more... +
+
+
+
+
+
+
+ +
+
+
+
+
+ + + + + + + + +
+
+
+ autoware_lanelet2_map_validator contains a bunch of validators, and calls the ones written in the requirement_set.yaml +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Input +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Output +
+
+
+
+ +
+
+
+
+ + + + + + + + + +
+
+
+ + + and more other categories... +
+
+
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ console output +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ + Only if a requirement set input is given + +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + + Optional, but recommended +
+
+
+
+
+
+
+ +
+
+
+
+
+
+
+
diff --git a/map/autoware_lanelet2_map_validator/package.xml b/map/autoware_lanelet2_map_validator/package.xml new file mode 100644 index 00000000..b147d461 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/package.xml @@ -0,0 +1,28 @@ + + + + autoware_lanelet2_map_validator + 0.1.0 + Validation tool for lanelet2 maps especially for Autoware usage + Taiki Yamada + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_lanelet2_extension + lanelet2_core + lanelet2_io + lanelet2_maps + lanelet2_projection + lanelet2_routing + lanelet2_traffic_rules + lanelet2_validation + nlohmann-json-dev + + ament_cmake_ros + + + ament_cmake + + diff --git a/map/autoware_lanelet2_map_validator/src/common/cli.cpp b/map/autoware_lanelet2_map_validator/src/common/cli.cpp new file mode 100644 index 00000000..a86dd804 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/common/cli.cpp @@ -0,0 +1,107 @@ +// 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 "common/cli.hpp" + +namespace po = boost::program_options; + +namespace lanelet +{ +namespace autoware +{ +namespace validation +{ + +MetaConfig parseCommandLine(int argc, const char * argv[]) +{ + MetaConfig config; + auto & validation_config = config.command_line_config.validationConfig; + po::options_description desc( + "Runs a set of validators on a map. Think of it like a linter. The following checks are " + "available"); + + // clang-format off + desc.add_options() + ( + "help,h", "This help message" + )( + "map_file,m", po::value(), "Path to the map to be validated" + )( + "input_requirements,i", po::value(), + "Path to the yaml file where the list of requirements and validators is written" + )( + "output_directory,o", po::value(), + "Directory to save the list of validation results in a yaml format" + )( + "validator,v", po::value(&validation_config.checksFilter), + "Comma separated list of regexes to filter the applicable validators. Will run all " + "validators by default. Example: routing_graph.* to run all checks for the routing graph" + )( + "projector,p", po::value(&config.projector_type)->composing(), + "Projector used for loading lanelet map. Available projectors are: mgrs, utm, " + "transverse_mercator. (default: mgrs)" + )( + "location,l", po::value(&validation_config.location)->default_value(validation_config.location), + "Location of the map (for instantiating the traffic rules), e.g. de for Germany" + )( + "participants", po::value(&validation_config.participants)->composing(), + "Participants for which the routing graph will be instantiated (default: vehicle)" + )( + "lat", po::value(&validation_config.origin.lat)->default_value(validation_config.origin.lat), + "Latitude coordinate of map origin. This is required for the transverse mercator " + "and utm projector." + )( + "lon", po::value(&validation_config.origin.lon)->default_value(validation_config.origin.lon), + "Longitude coordinate of map origin. This is required for the transverse mercator " + "and utm projector." + )( + "print", "Print all available checker without running them" + ); + // clang-format on + + po::variables_map vm; + po::positional_options_description pos; + pos.add("map_file", 1); + po::store(po::command_line_parser(argc, argv).options(desc).positional(pos).run(), vm); + po::notify(vm); + config.command_line_config.help = vm.count("help") != 0; + config.command_line_config.print = vm.count("print") != 0; + if (vm.count("map_file") != 0) { + config.command_line_config.mapFile = + vm["map_file"].as(); + } + if (vm.count("input_requirements") != 0) { + config.requirements_file = vm["input_requirements"].as(); + } + if (vm.count("output_directory") != 0) { + config.output_file_path = vm["output_directory"].as(); + } + if ( + (vm.count("lat") != 0 && vm.count("lon") != 0) && + (config.projector_type == "tm" || config.projector_type == "utm")) { + throw std::runtime_error( + "Please set latitude and longitude. These are required for " + config.projector_type + + " projector. Please refer to the help message."); + } + if (config.command_line_config.help) { + std::cout << '\n' << desc; + } else if (config.command_line_config.mapFile.empty() && !config.command_line_config.print) { + std::cout << "Please pass either a valid file or '--print' or '--help'!\n"; + } + return config; +} + +} // namespace validation +} // namespace autoware +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/common/cli.hpp b/map/autoware_lanelet2_map_validator/src/common/cli.hpp new file mode 100644 index 00000000..f4d1a805 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/common/cli.hpp @@ -0,0 +1,45 @@ +// 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 COMMON__CLI_HPP_ +#define COMMON__CLI_HPP_ + +#include + +#include + +#include +#include + +namespace lanelet +{ +namespace autoware +{ +namespace validation +{ +struct MetaConfig +{ + lanelet::validation::CommandLineConfig command_line_config; + std::string projector_type; + std::string requirements_file; + std::string output_file_path; +}; + +MetaConfig parseCommandLine(int argc, const char * argv[]); + +} // namespace validation +} // namespace autoware +} // namespace lanelet + +#endif // COMMON__CLI_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/common/utils.hpp b/map/autoware_lanelet2_map_validator/src/common/utils.hpp new file mode 100644 index 00000000..d086f30c --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/common/utils.hpp @@ -0,0 +1,83 @@ +// 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 COMMON__UTILS_HPP_ +#define COMMON__UTILS_HPP_ + +#include +#include + +#include +#include + +namespace lanelet +{ +namespace autoware +{ +namespace validation +{ +template +void appendIssues(std::vector & to, std::vector && from) +{ + to.insert(to.end(), std::make_move_iterator(from.begin()), std::make_move_iterator(from.end())); +} + +template +void checkPrimitivesType( + std::vector & in_vec, const std::string & expected_type, + const lanelet::validation::Issue & issue, lanelet::validation::Issues & issues) +{ + for (auto iter = in_vec.begin(); iter != in_vec.end(); ++iter) { + const auto & item = *iter; + const auto & attrs = item.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + if (it == attrs.end() || it->second != expected_type) { + issues.emplace_back(issue.severity, issue.primitive, item.id(), issue.message); + const auto new_it = in_vec.erase(iter); + if (new_it == in_vec.end()) { + break; + } + iter = new_it; + } + } +} + +template +void checkPrimitivesType( + std::vector & in_vec, const std::string & expected_type, const std::string & expected_subtype, + const lanelet::validation::Issue & issue, lanelet::validation::Issues & issues) +{ + for (auto iter = in_vec.begin(); iter != in_vec.end(); ++iter) { + const auto & item = *iter; + const auto & attrs = item.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + const auto & it_sub = attrs.find(lanelet::AttributeName::Subtype); + if ( + it == attrs.end() || it->second != expected_type || it_sub == attrs.end() || + it_sub->second != expected_subtype) { + issues.emplace_back(issue.severity, issue.primitive, item.id(), issue.message); + const auto new_it = in_vec.erase(iter); + if (new_it == in_vec.end()) { + break; + } + iter = new_it; + } + } +} + +} // namespace validation +} // namespace autoware +} // namespace lanelet + +#endif // COMMON__UTILS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/common/validation.cpp b/map/autoware_lanelet2_map_validator/src/common/validation.cpp new file mode 100644 index 00000000..f55cdc45 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/common/validation.cpp @@ -0,0 +1,74 @@ +// Copyright 2023 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 "common/validation.hpp" + +#include +#include + +#include +#include + +namespace lanelet +{ +namespace autoware +{ +namespace validation +{ + +std::unique_ptr getProjector(const MetaConfig & config) +{ + const auto & val_config = config.command_line_config.validationConfig; + if (config.projector_type == projector_names::mgrs) { + return std::make_unique(); + } else if (config.projector_type == projector_names::transverse_mercator) { + return std::make_unique( + lanelet::Origin{val_config.origin}); + } else if (config.projector_type == projector_names::utm) { + return std::make_unique(lanelet::Origin{val_config.origin}); + } + return std::make_unique(); +} + +std::vector validateMap(const MetaConfig & config) +{ + const auto & cm_config = config.command_line_config; + const auto & val_config = config.command_line_config.validationConfig; + + std::vector issues; + lanelet::LaneletMapPtr map; + lanelet::validation::Strings errors; + try { + const auto & projector = getProjector(config); + map = lanelet::load(cm_config.mapFile, *projector, &errors); + 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); + })); + } + + appendIssues(issues, lanelet::validation::validateMap(*map, val_config)); + return issues; +} + +} // namespace validation +} // namespace autoware +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/common/validation.hpp b/map/autoware_lanelet2_map_validator/src/common/validation.hpp new file mode 100644 index 00000000..e1ca55d1 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/common/validation.hpp @@ -0,0 +1,52 @@ +// 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 COMMON__VALIDATION_HPP_ +#define COMMON__VALIDATION_HPP_ + +#include "common/cli.hpp" +#include "common/utils.hpp" + +#include +#include +#include +#include + +#include +#include +#include + +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 +{ +namespace autoware +{ +namespace validation +{ +std::unique_ptr getProjector(const MetaConfig & config); +std::vector validateMap(const MetaConfig & config); +} // namespace validation +} // namespace autoware +} // namespace lanelet + +#endif // COMMON__VALIDATION_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp new file mode 100644 index 00000000..07804c0f --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -0,0 +1,184 @@ +// 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 "common/cli.hpp" +#include "common/utils.hpp" +#include "common/validation.hpp" +#include "lanelet2_validation/Validation.h" + +#include + +#include +#include +#include + +// Use nlohmann::json for JSON handling +using json = nlohmann::json; + +// ANSI color codes for console output +#define BOLD_ONLY "\033[1m" +#define BOLD_GREEN "\033[1;32m" +#define BOLD_YELLOW "\033[1;33m" +#define BOLD_RED "\033[1;31m" +#define NORMAL_GREEN "\033[32m" +#define NORMAL_RED "\033[31m" +#define FONT_RESET "\033[0m" + +void process_requirements( + json json_config, const lanelet::autoware::validation::MetaConfig & validator_config) +{ + uint64_t warning_count = 0; + uint64_t error_count = 0; + lanelet::autoware::validation::MetaConfig temp_validator_config = validator_config; + + for (auto & requirement : json_config["requirements"]) { + std::string id = requirement["id"]; + bool requirement_passed = true; + + std::vector issues; + std::map temp_validation_results; + + for (auto & validator : requirement["validators"]) { + std::string validator_name = validator["name"]; + temp_validator_config.command_line_config.validationConfig.checksFilter = validator_name; + + std::vector temp_issues = + lanelet::autoware::validation::validateMap(temp_validator_config); + + if (temp_issues.empty()) { + // Validator passed + temp_validation_results[validator_name] = true; + validator["passed"] = true; + } else { + // Validator failed + requirement_passed = false; + warning_count += temp_issues[0].warnings().size(); + error_count += temp_issues[0].errors().size(); + temp_validation_results[validator_name] = false; + validator["passed"] = false; + + json issues_json; + for (const auto & issue : temp_issues[0].issues) { + json issue_json; + issue_json["severity"] = lanelet::validation::toString(issue.severity); + issue_json["primitive"] = lanelet::validation::toString(issue.primitive); + issue_json["id"] = issue.id; + issue_json["message"] = issue.message; + issues_json.push_back(issue_json); + } + validator["issues"] = issues_json; + } + + lanelet::autoware::validation::appendIssues(issues, std::move(temp_issues)); + } + + std::cout << BOLD_ONLY << "[" << id << "] "; + + if (requirement_passed) { + requirement["passed"] = true; + std::cout << BOLD_GREEN << "Passed" << FONT_RESET << std::endl; + } else { + requirement["passed"] = false; + std::cout << BOLD_RED << "Failed" << FONT_RESET << std::endl; + } + + for (const auto & result : temp_validation_results) { + if (result.second) { + std::cout << " - " << result.first << ": " << NORMAL_GREEN << "Passed" << FONT_RESET + << std::endl; + } else { + std::cout << " - " << result.first << ": " << NORMAL_RED << "Failed" << FONT_RESET + << std::endl; + } + } + lanelet::validation::printAllIssues(issues); + std::cout << std::endl; + } + + if (warning_count + error_count == 0) { + std::cout << BOLD_GREEN << "No issues were found from " << FONT_RESET + << validator_config.command_line_config.mapFile << std::endl; + } else { + if (warning_count > 0) { + std::cout << BOLD_YELLOW << "Total of " << warning_count << " warnings were found from " + << FONT_RESET << validator_config.command_line_config.mapFile << std::endl; + } + if (error_count > 0) { + std::cout << BOLD_RED << "Total of " << error_count << " errors were found from " + << FONT_RESET << validator_config.command_line_config.mapFile << std::endl; + } + } + + if (!validator_config.output_file_path.empty()) { + if (!std::filesystem::is_directory(validator_config.output_file_path)) { + throw std::invalid_argument("Output path doesn't exist or is not a directory!"); + } + std::filesystem::path file_directory = validator_config.output_file_path; + std::filesystem::path file_path = file_directory / "lanelet2_validation_results.json"; + std::ofstream output_file(file_path); + output_file << std::setw(4) << json_config; + std::cout << "Results are output to " << file_path << std::endl; + } +} + +int main(int argc, char * argv[]) +{ + lanelet::autoware::validation::MetaConfig meta_config = + lanelet::autoware::validation::parseCommandLine( + argc, const_cast(argv)); // NOLINT + + // Print help (Already done in parseCommandLine) + if (meta_config.command_line_config.help) { + return 0; + } + + // Print available validators + if (meta_config.command_line_config.print) { + auto checks = lanelet::validation::availabeChecks( // cspell:disable-line + meta_config.command_line_config.validationConfig.checksFilter); + if (checks.empty()) { + std::cout << "No checks found matching to '" + << meta_config.command_line_config.validationConfig.checksFilter << "'" + << std::endl; + } else { + std::cout << "The following checks are available:" << std::endl; + for (auto & check : checks) { + std::cout << check << std::endl; + } + } + return 0; + } + + // Validation start + if (meta_config.command_line_config.mapFile.empty()) { + throw std::invalid_argument("No map file specified!"); + } else if (!std::filesystem::is_regular_file(meta_config.command_line_config.mapFile)) { + throw std::invalid_argument("Map file doesn't exist or is not a file!"); + } + + if (!meta_config.requirements_file.empty()) { + if (!std::filesystem::is_regular_file(meta_config.requirements_file)) { + throw std::invalid_argument("Input file doesn't exist or is not a file!"); + } + std::ifstream input_file(meta_config.requirements_file); + json json_config; + input_file >> json_config; + process_requirements(json_config, meta_config); + } else { + auto issues = lanelet::autoware::validation::validateMap(meta_config); + lanelet::validation::printAllIssues(issues); + } + + return 0; +} diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp new file mode 100644 index 00000000..96f7a11f --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp @@ -0,0 +1,95 @@ +// 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 "common/utils.hpp" +#include "validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp" + +#include + +#include + +#include + +namespace lanelet +{ +namespace validation +{ +namespace +{ +lanelet::validation::RegisterMapValidator reg; +} + +lanelet::validation::Issues MissingRegulatoryElementsForCrosswalksValidator::operator()( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + + lanelet::autoware::validation::appendIssues( + issues, checkMissingRegulatoryElementsForCrosswalks(map)); + + return issues; +} + +lanelet::validation::Issues +MissingRegulatoryElementsForCrosswalksValidator::checkMissingRegulatoryElementsForCrosswalks( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + + // Get all lanelets whose type is crosswalk + std::set cw_ids; + + for (const auto & ll : map.laneletLayer) { + const auto & attrs = ll.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + // Check if this lanelet is crosswalk + if (it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk) { + cw_ids.insert(ll.id()); + } + } + + // Filter regulatory elements whose type is crosswalk and has refers + auto reg_elem_cw = + map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + return it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk; + }) | + ranges::views::filter([](auto && elem) { + const auto & param = elem->getParameters(); + return param.find(lanelet::RoleNameString::Refers) != param.end(); + }); + + // Get all lanelets of crosswalk referred by regulatory elements + std::set cw_ids_reg_elem; + for (const auto & elem : reg_elem_cw) { + const auto & refers = elem->getParameters(lanelet::RoleName::Refers); + for (const lanelet::ConstLanelet & refer : refers) { + cw_ids_reg_elem.insert(refer.id()); + } + } + + // Check if all lanelets of crosswalk referred by regulatory elements + for (const auto & cw_id : cw_ids) { + if (cw_ids_reg_elem.find(cw_id) == cw_ids_reg_elem.end()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, cw_id, + "No regulatory element refers to this crosswalk."); + } + } + + return issues; +} +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp new file mode 100644 index 00000000..38f83c15 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp @@ -0,0 +1,39 @@ +// 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 VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +#define VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ + +#include +#include + +namespace lanelet +{ +namespace validation +{ +class MissingRegulatoryElementsForCrosswalksValidator : public lanelet::validation::MapValidator +{ +public: + constexpr static const char * name() { return "mapping.crosswalk.missing_regulatory_elements"; } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: + lanelet::validation::Issues checkMissingRegulatoryElementsForCrosswalks( + const lanelet::LaneletMap & map); +}; +} // namespace validation +} // namespace lanelet + +#endif // VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp new file mode 100644 index 00000000..6d04e223 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp @@ -0,0 +1,129 @@ +// 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 "validators/crosswalk/regulatory_element_details_for_crosswalks.hpp" + +#include "common/utils.hpp" + +#include +#include + +#include +#include + +namespace lanelet +{ +namespace validation +{ +namespace +{ +lanelet::validation::RegisterMapValidator reg; +} // namespace + +lanelet::validation::Issues RegulatoryElementsDetailsForCrosswalksValidator::operator()( + const lanelet::LaneletMap & map) +{ + // All issues found by all validators + lanelet::validation::Issues issues; + + // Append issues found by each validator + lanelet::autoware::validation::appendIssues(issues, checkRegulatoryElementOfCrosswalks(map)); + return issues; +} + +lanelet::validation::Issues +RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswalks( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + // filter elem whose Subtype is crosswalk + auto elems = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + return it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk; + }); + + for (const auto & elem : elems) { + // Get lanelet of crosswalk referred by regulatory element + auto refers = elem->getParameters(lanelet::RoleName::Refers); + // Get stop line referred by regulatory element + auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); + // Get crosswalk polygon referred by regulatory element + auto crosswalk_polygons = elem->getParameters( + lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon); + + // If this is a crosswalk type regulatory element, the "refers" has to be a "crosswalk" subtype + // lanelet + const auto & issue_cw = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, + lanelet::utils::getId(), + "Refers of crosswalk regulatory element must have type of crosswalk."); + lanelet::autoware::validation::checkPrimitivesType( + refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, + issue_cw, issues); + + // If this is a crosswalk type regulatory element, the "ref_line" has to be a "stop_line" type + // linestring + const auto & issue_sl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "ref_line of crosswalk regulatory element must have type of stopline."); + lanelet::autoware::validation::checkPrimitivesType( + ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); + + // If this is a crosswalk type regulatory element, the "crosswalk_polygon" has to be a + // "crosswalk_polygon" type polygon + const auto & issue_poly = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon, + lanelet::utils::getId(), + "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); + lanelet::autoware::validation::checkPrimitivesType( + crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, + issue_poly, issues); + + // Report warning if regulatory element does not have crosswalk polygon + if (crosswalk_polygons.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Warning, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of crosswalk is nice to have crosswalk_polygon."); + } else if (crosswalk_polygons.size() > 1) { // Report error if regulatory element has two or + // more crosswalk polygon + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of crosswalk must have only one crosswalk_polygon."); + } + // Report Info if regulatory element does not have stop line + if (ref_lines.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Info, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of crosswalk does not have stop line(ref_line)."); + } + // Report error if regulatory element does not have lanelet of crosswalk + if (refers.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of crosswalk must have lanelet of crosswalk(refers)."); + } else if (refers.size() > 1) { // Report error if regulatory element has two or more lanelet + // of crosswalk + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), + "Regulatory element of crosswalk must have only one lanelet of crosswalk(refers)."); + } + } + return issues; +} + +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp new file mode 100644 index 00000000..b0a1bc48 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp @@ -0,0 +1,39 @@ +// 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 VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ +#define VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ + +#include +#include + +namespace lanelet +{ +namespace validation +{ +class RegulatoryElementsDetailsForCrosswalksValidator : public lanelet::validation::MapValidator +{ +public: + // Write the validator's name here + constexpr static const char * name() { return "mapping.crosswalk.regulatory_element_details"; } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: + lanelet::validation::Issues checkRegulatoryElementOfCrosswalks(const lanelet::LaneletMap & map); +}; +} // namespace validation +} // namespace lanelet + +#endif // VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp new file mode 100644 index 00000000..1d48153e --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp @@ -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 "validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp" + +#include "common/utils.hpp" + +#include +#include +#include + +#include + +#include +#include + +namespace lanelet +{ +namespace validation +{ +namespace +{ +lanelet::validation::RegisterMapValidator reg; +} + +lanelet::validation::Issues MissingRegulatoryElementsForStopLinesValidator::operator()( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + + lanelet::autoware::validation::appendIssues( + issues, checkMissingRegulatoryElementsForStopLines(map)); + + return issues; +} + +lanelet::validation::Issues +MissingRegulatoryElementsForStopLinesValidator::checkMissingRegulatoryElementsForStopLines( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + + // Get all line strings whose type is stop line + auto sl_ids = map.lineStringLayer | ranges::views::filter([](auto && ls) { + const auto & attrs = ls.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + return it != attrs.end() && it->second == lanelet::AttributeValueString::StopLine; + }) | + ranges::views::transform([](auto && ls) { return ls.id(); }) | + ranges::views::unique; + + // Filter regulatory elements whose ref_line type is stop line + auto reg_elem_sl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & params = elem->getParameters(); + return params.find(lanelet::RoleNameString::RefLine) != params.end(); + }); + + // Get all line strings of stop line referred by regulatory elements + std::set sl_ids_reg_elem; + for (const auto & elem : reg_elem_sl) { + const auto & ref_lines = + elem->getParameters(lanelet::RoleName::RefLine); + for (const auto & ref_line : ref_lines) { + const auto & attrs = ref_line.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + if (it != attrs.end() && it->second == lanelet::AttributeValueString::StopLine) { + sl_ids_reg_elem.insert(ref_line.id()); + } + } + } + + // Check if all line strings of stop line referred by regulatory elements + for (const auto & sl_id : sl_ids) { + if (sl_ids_reg_elem.find(sl_id) == sl_ids_reg_elem.end()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, sl_id, + "No regulatory element refers to this stop line."); + } + } + + return issues; +} + +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp new file mode 100644 index 00000000..e1b8682e --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp @@ -0,0 +1,39 @@ +// 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 VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ +#define VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ + +#include +#include + +namespace lanelet +{ +namespace validation +{ +class MissingRegulatoryElementsForStopLinesValidator : public lanelet::validation::MapValidator +{ +public: + constexpr static const char * name() { return "mapping.stop_line.missing_regulatory_elements"; } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: + lanelet::validation::Issues checkMissingRegulatoryElementsForStopLines( + const lanelet::LaneletMap & map); +}; +} // namespace validation +} // namespace lanelet + +#endif // VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp new file mode 100644 index 00000000..91ddd4a1 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp @@ -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 "validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp" + +#include "common/utils.hpp" + +#include +#include +#include + +#include + +#include +#include + +namespace lanelet +{ +namespace validation +{ +namespace +{ +lanelet::validation::RegisterMapValidator reg; +} + +lanelet::validation::Issues MissingRegulatoryElementsForTrafficLightsValidator::operator()( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + + lanelet::autoware::validation::appendIssues( + issues, checkMissingRegulatoryElementsForTrafficLights(map)); + + return issues; +} + +lanelet::validation::Issues +MissingRegulatoryElementsForTrafficLightsValidator::checkMissingRegulatoryElementsForTrafficLights( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + + // Get all line strings whose type is traffic light + auto tl_ids = + map.lineStringLayer | ranges::views::filter([](auto && ls) { + const auto & attrs = ls.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + return it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight; + }) | + ranges::views::transform([](auto && ls) { return ls.id(); }) | ranges::views::unique; + + // Filter regulatory elements whose type is traffic light and has refers + auto reg_elem_tl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + const auto & params = elem->getParameters(); + return it != attrs.end() && + it->second == lanelet::AttributeValueString::TrafficLight && + params.find(lanelet::RoleNameString::Refers) != params.end(); + }); + + // Get all line strings of traffic light referred by regulatory elements + std::set tl_ids_reg_elem; + for (const auto & elem : reg_elem_tl) { + const auto & refers = + elem->getParameters(lanelet::RoleName::Refers); + for (const auto & refer : refers) { + tl_ids_reg_elem.insert(refer.id()); + } + } + + // Check if all line strings of traffic light referred by regulatory elements + for (const auto & tl_id : tl_ids) { + if (tl_ids_reg_elem.find(tl_id) == tl_ids_reg_elem.end()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, tl_id, + "No regulatory element refers to this traffic light."); + } + } + + return issues; +} + +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp new file mode 100644 index 00000000..4bb1c4d6 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp @@ -0,0 +1,42 @@ +// 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 VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ +#define VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ + +#include +#include + +namespace lanelet +{ +namespace validation +{ +class MissingRegulatoryElementsForTrafficLightsValidator : public lanelet::validation::MapValidator +{ +public: + constexpr static const char * name() + { + return "mapping.traffic_light.missing_regulatory_elements"; + } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: + lanelet::validation::Issues checkMissingRegulatoryElementsForTrafficLights( + const lanelet::LaneletMap & map); +}; +} // namespace validation +} // namespace lanelet + +#endif // VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp new file mode 100644 index 00000000..fe500178 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp @@ -0,0 +1,114 @@ +// 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 "validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp" + +#include "common/utils.hpp" + +#include + +#include +#include + +namespace lanelet +{ +namespace validation +{ +namespace +{ +lanelet::validation::RegisterMapValidator reg; +} // namespace + +lanelet::validation::Issues RegulatoryElementsDetailsForTrafficLightsValidator::operator()( + const lanelet::LaneletMap & map) +{ + // All issues found by all validators + lanelet::validation::Issues issues; + + // Append issues found by each validator + lanelet::autoware::validation::appendIssues(issues, checkRegulatoryElementOfTrafficLights(map)); + return issues; +} + +bool RegulatoryElementsDetailsForTrafficLightsValidator::isPedestrianTrafficLight( + const std::vector & traffic_lights) +{ + for (const auto & tl : traffic_lights) { + const auto & attrs = tl.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + if (it == attrs.end() || it->second != "red_green") { + return false; + } + } + return true; +} + +lanelet::validation::Issues +RegulatoryElementsDetailsForTrafficLightsValidator::checkRegulatoryElementOfTrafficLights( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + // filter regulatory element whose Subtype is traffic light + auto elems = + map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + return it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight; + }); + + for (const auto & elem : elems) { + // Get line strings of traffic light referred by regulatory element + auto refers = elem->getParameters(lanelet::RoleName::Refers); + // Get stop line referred by regulatory element + auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); + const auto & issue_tl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "Refers of traffic light regulatory element must have type of traffic_light."); + lanelet::autoware::validation::checkPrimitivesType( + refers, lanelet::AttributeValueString::TrafficLight, issue_tl, issues); + + const auto & issue_sl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "ref_line of traffic light regulatory element must have type of stop_line."); + lanelet::autoware::validation::checkPrimitivesType( + ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); + + if (refers.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of traffic light must have a traffic light(refers)."); + } + // TODO(sgk-000): Check correct behavior if regulatory element has two or more traffic light + // else if (refers.size() != 1) { + // issues.emplace_back( + // lanelet::validation::Severity::Error, + // lanelet::validation::Primitive::RegulatoryElement, elem->id(), "Regulatory element of + // traffic light must have only one traffic light(refers)."); + // } + + // Report error if regulatory element does not have stop line and this is not a pedestrian + // traffic light + if (ref_lines.empty() && !isPedestrianTrafficLight(refers)) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of traffic light must have a stop line(ref_line)."); + } + } + return issues; +} + +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp new file mode 100644 index 00000000..321bd35f --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp @@ -0,0 +1,46 @@ +// 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 VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +#define VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ + +#include +#include + +#include + +namespace lanelet +{ +namespace validation +{ +class RegulatoryElementsDetailsForTrafficLightsValidator : public lanelet::validation::MapValidator +{ +public: + // Write the validator's name here + constexpr static const char * name() + { + return "mapping.traffic_light.regulatory_element_details"; + } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: + bool isPedestrianTrafficLight(const std::vector & traffic_lights); + lanelet::validation::Issues checkRegulatoryElementOfTrafficLights( + const lanelet::LaneletMap & map); +}; +} // namespace validation +} // namespace lanelet + +#endif // VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp b/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp new file mode 100644 index 00000000..e50644be --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp @@ -0,0 +1,33 @@ +// 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 "validator_template.hpp" + +namespace lanelet +{ +namespace validation +{ +lanelet::validation::RegisterMapValidator reg; + +lanelet::validation::Issues ValidatorTemplate::operator()(const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + + // Remove this line and write down how to append issues + (void)map; + + return issues; +} +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp b/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp new file mode 100644 index 00000000..e541f4e0 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp @@ -0,0 +1,38 @@ +// 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 VALIDATORS__VALIDATOR_TEMPLATE_HPP_ +#define VALIDATORS__VALIDATOR_TEMPLATE_HPP_ + +#include +#include + +namespace lanelet +{ +namespace validation +{ +class ValidatorTemplate : public lanelet::validation::MapValidator +{ +public: + // Write the validator's name here + constexpr static const char * name() { return "mapping.validator.template"; } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: +}; +} // namespace validation +} // namespace lanelet + +#endif // VALIDATORS__VALIDATOR_TEMPLATE_HPP_ diff --git a/map/autoware_lanelet2_map_validator/test/example_requirement_set.json b/map/autoware_lanelet2_map_validator/test/example_requirement_set.json new file mode 100644 index 00000000..445be17a --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/example_requirement_set.json @@ -0,0 +1,35 @@ +{ + "version": "0.1.0", + "requirements": [ + { + "id": "example-01-01", + "validators": [ + { + "name": "mapping.crosswalk.missing_regulatory_elements" + }, + { + "name": "mapping.crosswalk.regulatory_element_details" + } + ] + }, + { + "id": "example-01-02", + "validators": [ + { + "name": "mapping.traffic_light.missing_regulatory_elements" + }, + { + "name": "mapping.traffic_light.regulatory_element_details" + } + ] + }, + { + "id": "example-01-03", + "validators": [ + { + "name": "mapping.stop_line.missing_regulatory_elements" + } + ] + } + ] +} diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp new file mode 100644 index 00000000..e8fe1cef --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp @@ -0,0 +1,245 @@ +// Copyright 2023 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 "validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp" +#include "validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp" +#include "validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp" + +#include +#include + +#include +#include + +using lanelet::AttributeMap; +using lanelet::AttributeName; +using lanelet::AttributeValueString; +using lanelet::Lanelet; +using lanelet::LaneletMapPtr; +using lanelet::LineString3d; +using lanelet::Point3d; +using lanelet::Polygon3d; +using lanelet::RegulatoryElementPtr; +using lanelet::TrafficLight; +using lanelet::autoware::Crosswalk; +using lanelet::utils::getId; +class TestSuite : public ::testing::Test +{ +public: + TestSuite() { initializeAttributes(); } + + ~TestSuite() override = default; + + void initializeAttributes() + { + // Stop Line + sl_attr_[AttributeName::Type] = AttributeValueString::StopLine; + + // Traffic Light + tl_attr_[AttributeName::Type] = AttributeValueString::TrafficLight; + tl_attr_[AttributeName::Subtype] = "red_yellow_green"; + tl_attr_["height"] = "0.5"; + + // Crosswalk polygon + cw_poly_attr_[AttributeName::Type] = + lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon; + + // Crosswalk + cw_attr_[AttributeName::Type] = AttributeValueString::Lanelet; + cw_attr_[AttributeName::Subtype] = AttributeValueString::Crosswalk; + cw_attr_[AttributeName::SpeedLimit] = "10"; + cw_attr_[AttributeName::OneWay] = "no"; + cw_attr_[AttributeName::Location] = AttributeValueString::Urban; + cw_attr_[AttributeName::ParticipantPedestrian] = "yes"; + + // Regulatory element of traffic light + AttributeMap tl_re_attr_ = AttributeMap(); + tl_re_attr_[AttributeName::Type] = AttributeValueString::RegulatoryElement; + tl_re_attr_[AttributeName::Subtype] = AttributeValueString::TrafficLight; + + // Regulatory element of crosswalk + AttributeMap cw_re_attr_ = AttributeMap(); + cw_re_attr_[AttributeName::Type] = AttributeValueString::RegulatoryElement; + cw_re_attr_[AttributeName::Subtype] = AttributeValueString::Crosswalk; + } + + void addTestMap(LaneletMapPtr in_map_ptr) + { + // Create test map + + // Points for stop line + Point3d p0 = Point3d(getId(), 0.0, 0.0, 0.1); + Point3d p1 = Point3d(getId(), 0.0, 1.0, 0.1); + Point3d p2 = Point3d(getId(), 0.0, 2.0, 0.1); + // Points for traffic light + Point3d p3 = Point3d(getId(), 0.0, 0.0, 5.0); + Point3d p4 = Point3d(getId(), 0.0, 1.0, 5.0); + Point3d p5 = Point3d(getId(), 0.0, 2.0, 5.0); + // Points for crosswalk + Point3d p6 = Point3d(getId(), 1.0, 0.0, 0.1); + Point3d p7 = Point3d(getId(), 1.0, 1.0, 0.1); + Point3d p8 = Point3d(getId(), 1.0, 2.0, 0.1); + Point3d p9 = Point3d(getId(), 2.0, 0.0, 0.1); + Point3d p10 = Point3d(getId(), 2.0, 1.0, 0.1); + Point3d p11 = Point3d(getId(), 2.0, 2.0, 0.1); + + // Stop line + LineString3d sl1 = LineString3d(getId(), {p0, p1}, sl_attr_); + LineString3d sl2 = LineString3d(getId(), {p1, p2}, sl_attr_); + + LineString3d tl1 = LineString3d(getId(), {p3, p4}, tl_attr_); + LineString3d tl2 = LineString3d(getId(), {p4, p5}, tl_attr_); + + // LineStrings for crosswalk + LineString3d cw_ls1 = LineString3d(getId(), {p6, p7}); + LineString3d cw_ls2 = LineString3d(getId(), {p7, p8}); + LineString3d cw_ls3 = LineString3d(getId(), {p9, p10}); + LineString3d cw_ls4 = LineString3d(getId(), {p10, p11}); + + Polygon3d cw_poly1 = Polygon3d(getId(), {p7, p6, p9, p10, p7}, cw_poly_attr_); + Polygon3d cw_poly2 = Polygon3d(getId(), {p8, p7, p10, p11, p8}, cw_poly_attr_); + // Lanelets for crosswalk + Lanelet cw1 = Lanelet(getId(), cw_ls1, cw_ls3, cw_attr_); + Lanelet cw2 = Lanelet(getId(), cw_ls2, cw_ls4, cw_attr_); + + // Traffic light regulatory element + RegulatoryElementPtr tl_reg_elem1, tl_reg_elem2; + tl_reg_elem1 = TrafficLight::make(getId(), tl_re_attr_, {tl1}, {sl1}); + tl_reg_elem2 = TrafficLight::make(getId(), tl_re_attr_, {tl2}, {sl2}); + + // Crosswalk regulatory element + RegulatoryElementPtr cw_reg_elem1, cw_reg_elem2; + cw_reg_elem1 = Crosswalk::make(getId(), cw_re_attr_, cw1, cw_poly1, {sl1}); + cw_reg_elem2 = Crosswalk::make(getId(), cw_re_attr_, cw2, cw_poly2, {sl2}); + + cw1.addRegulatoryElement(cw_reg_elem1); + cw2.addRegulatoryElement(cw_reg_elem2); + + // Add elements to map + for (const auto & re : {tl_reg_elem1, tl_reg_elem2}) { + in_map_ptr->add(re); + } + for (const auto & cw : {cw1, cw2}) { + in_map_ptr->add(cw); + } + } + AttributeMap sl_attr_, tl_attr_, cw_attr_, cw_poly_attr_, tl_re_attr_, cw_re_attr_; + +private: +}; + +TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest +{ + std::string expected_validators_concat = + "mapping.crosswalk.missing_regulatory_elements," + "mapping.stop_line.missing_regulatory_elements," + "mapping.traffic_light.missing_regulatory_elements"; + + lanelet::validation::Strings validators = + lanelet::validation::availabeChecks(expected_validators_concat); // cspell:disable-line + uint8_t expected_num_validators = 3; + std::cout << "size: " << validators.size() << std::endl; + EXPECT_EQ(expected_num_validators, validators.size()); + + std::set expected_validators_set = { + "mapping.crosswalk.missing_regulatory_elements", + "mapping.stop_line.missing_regulatory_elements", + "mapping.traffic_light.missing_regulatory_elements"}; + + std::set testing_validators_set = { + lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator::name(), + lanelet::validation::MissingRegulatoryElementsForStopLinesValidator::name(), + lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator::name()}; + + for (const auto & name : testing_validators_set) { + std::cout << name << std::endl; + EXPECT_TRUE(expected_validators_set.find(name) != expected_validators_set.end()) + << "Unexpected validator found: " << name; + } +} + +TEST_F(TestSuite, MissingRegulatoryElementOfTrafficLight) // NOLINT for gtest +{ + // Check missing regulatory element of traffic light + + const auto & tl_no_reg_elem = LineString3d( + 99999, {Point3d(getId(), 0.0, 3.0, 5.0), Point3d(getId(), 0.0, 4.0, 5.0)}, tl_attr_); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({tl_no_reg_elem}); + addTestMap(test_map_ptr); + + lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator checker; + const auto & issues = checker(*test_map_ptr); + + uint8_t expected_num_issues = 1; + static constexpr const char * expected_message = + "No regulatory element refers to this traffic light."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + EXPECT_EQ(99999, issue.id); + EXPECT_EQ(expected_message, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::LineString, issue.primitive); + } +} + +TEST_F(TestSuite, MissingRegulatoryElementOfCrosswalk) // NOLINT for gtest +{ + // Check missing regulatory element of crosswalk + + const auto & cw_no_reg_elem = Lanelet( + 99999, + LineString3d(getId(), {Point3d(getId(), 3.0, 0.0, 0.1), Point3d(getId(), 3.0, 1.0, 0.1)}), + LineString3d(getId(), {Point3d(getId(), 3.0, 1.0, 0.1), Point3d(getId(), 3.0, 2.0, 0.1)}), + cw_attr_); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({cw_no_reg_elem}); + addTestMap(test_map_ptr); + + lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator checker; + const auto & issues = checker(*test_map_ptr); + + uint8_t expected_num_issues = 1; + static constexpr const char * expected_message = + "No regulatory element refers to this crosswalk."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + EXPECT_EQ(99999, issue.id); + EXPECT_EQ(expected_message, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::Lanelet, issue.primitive); + } +} + +TEST_F(TestSuite, MissingRegulatoryElementOfStopLine) // NOLINT for gtest +{ + // Check missing regulatory element of stop line + + const auto & sl_no_reg_elem = LineString3d( + 99999, {Point3d(getId(), 0.0, 3.0, 5.0), Point3d(getId(), 0.0, 4.0, 5.0)}, sl_attr_); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({sl_no_reg_elem}); + addTestMap(test_map_ptr); + + lanelet::validation::MissingRegulatoryElementsForStopLinesValidator checker; + const auto & issues = checker(*test_map_ptr); + + uint8_t expected_num_issues = 1; + static constexpr const char * expected_message = + "No regulatory element refers to this stop line."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + EXPECT_EQ(99999, issue.id); + EXPECT_EQ(expected_message, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::LineString, issue.primitive); + } +} diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp new file mode 100644 index 00000000..6a14d51e --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -0,0 +1,368 @@ +// Copyright 2023 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 "validators/crosswalk/regulatory_element_details_for_crosswalks.hpp" +#include "validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp" + +#include +#include + +#include +#include + +using lanelet::AttributeMap; +using lanelet::AttributeName; +using lanelet::AttributeValueString; +using lanelet::Lanelet; +using lanelet::LaneletMapPtr; +using lanelet::LineString3d; +using lanelet::Point3d; +using lanelet::Polygon3d; +using lanelet::RegulatoryElementPtr; +using lanelet::TrafficLight; +using lanelet::autoware::Crosswalk; +using lanelet::utils::getId; +class TestSuite : public ::testing::Test +{ +public: + TestSuite() { initializeAttributes(); } + + ~TestSuite() override = default; + + void initializeAttributes() + { + // Stop Line + sl_attr[AttributeName::Type] = AttributeValueString::StopLine; + + // Traffic Light + tl_attr[AttributeName::Type] = AttributeValueString::TrafficLight; + tl_attr[AttributeName::Subtype] = "red_yellow_green"; + tl_attr["height"] = "0.5"; + + // Crosswalk polygon + cw_poly_attr[AttributeName::Type] = + lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon; + + // Crosswalk + cw_attr[AttributeName::Type] = AttributeValueString::Lanelet; + cw_attr[AttributeName::Subtype] = AttributeValueString::Crosswalk; + cw_attr[AttributeName::SpeedLimit] = "10"; + cw_attr[AttributeName::OneWay] = "no"; + cw_attr[AttributeName::Location] = AttributeValueString::Urban; + cw_attr[AttributeName::ParticipantPedestrian] = "yes"; + + // Regulatory element of traffic light + AttributeMap tl_re_attr = AttributeMap(); + tl_re_attr[AttributeName::Type] = AttributeValueString::RegulatoryElement; + tl_re_attr[AttributeName::Subtype] = AttributeValueString::TrafficLight; + + // Regulatory element of crosswalk + AttributeMap cw_re_attr = AttributeMap(); + cw_re_attr[AttributeName::Type] = AttributeValueString::RegulatoryElement; + cw_re_attr[AttributeName::Subtype] = AttributeValueString::Crosswalk; + } + + void addTestMap(LaneletMapPtr in_map_ptr) + { + // Create test map + + // Points for stop line + Point3d p0 = Point3d(getId(), 0.0, 0.0, 0.1); + Point3d p1 = Point3d(getId(), 0.0, 1.0, 0.1); + Point3d p2 = Point3d(getId(), 0.0, 2.0, 0.1); + // Points for traffic light + Point3d p3 = Point3d(getId(), 0.0, 0.0, 5.0); + Point3d p4 = Point3d(getId(), 0.0, 1.0, 5.0); + Point3d p5 = Point3d(getId(), 0.0, 2.0, 5.0); + // Points for crosswalk + Point3d p6 = Point3d(getId(), 1.0, 0.0, 0.1); + Point3d p7 = Point3d(getId(), 1.0, 1.0, 0.1); + Point3d p8 = Point3d(getId(), 1.0, 2.0, 0.1); + Point3d p9 = Point3d(getId(), 2.0, 0.0, 0.1); + Point3d p10 = Point3d(getId(), 2.0, 1.0, 0.1); + Point3d p11 = Point3d(getId(), 2.0, 2.0, 0.1); + + // Stop line + LineString3d sl1 = LineString3d(getId(), {p0, p1}, sl_attr); + LineString3d sl2 = LineString3d(getId(), {p1, p2}, sl_attr); + + LineString3d tl1 = LineString3d(getId(), {p3, p4}, tl_attr); + LineString3d tl2 = LineString3d(getId(), {p4, p5}, tl_attr); + + // LineStrings for crosswalk + LineString3d cw_ls1 = LineString3d(getId(), {p6, p7}); + LineString3d cw_ls2 = LineString3d(getId(), {p7, p8}); + LineString3d cw_ls3 = LineString3d(getId(), {p9, p10}); + LineString3d cw_ls4 = LineString3d(getId(), {p10, p11}); + + Polygon3d cw_poly1 = Polygon3d(getId(), {p7, p6, p9, p10, p7}, cw_poly_attr); + Polygon3d cw_poly2 = Polygon3d(getId(), {p8, p7, p10, p11, p8}, cw_poly_attr); + // Lanelets for crosswalk + Lanelet cw1 = Lanelet(getId(), cw_ls1, cw_ls3, cw_attr); + Lanelet cw2 = Lanelet(getId(), cw_ls2, cw_ls4, cw_attr); + + // Traffic light regulatory element + RegulatoryElementPtr tl_reg_elem1, tl_reg_elem2; + tl_reg_elem1 = TrafficLight::make(getId(), tl_re_attr, {tl1}, {sl1}); + tl_reg_elem2 = TrafficLight::make(getId(), tl_re_attr, {tl2}, {sl2}); + + // Crosswalk regulatory element + RegulatoryElementPtr cw_reg_elem1, cw_reg_elem2; + cw_reg_elem1 = Crosswalk::make(getId(), cw_re_attr, cw1, cw_poly1, {sl1}); + cw_reg_elem2 = Crosswalk::make(getId(), cw_re_attr, cw2, cw_poly2, {sl2}); + + cw1.addRegulatoryElement(cw_reg_elem1); + cw2.addRegulatoryElement(cw_reg_elem2); + + // Add elements to map + for (const auto & re : {tl_reg_elem1, tl_reg_elem2}) { + in_map_ptr->add(re); + } + for (const auto & cw : {cw1, cw2}) { + in_map_ptr->add(cw); + } + } + AttributeMap sl_attr, tl_attr, cw_attr, cw_poly_attr, tl_re_attr, cw_re_attr; + +private: +}; + +TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest +{ + std::string expected_validators_concat = + "mapping.crosswalk.regulatory_element_details," + "mapping.traffic_light.regulatory_element_details"; + + lanelet::validation::Strings validators = + lanelet::validation::availabeChecks(expected_validators_concat); // cspell:disable-line + uint8_t expected_num_validators = 2; + std::cout << "size: " << validators.size() << std::endl; + EXPECT_EQ(expected_num_validators, validators.size()); + + std::set expected_validators_set = { + "mapping.crosswalk.regulatory_element_details", + "mapping.traffic_light.regulatory_element_details"}; + + std::set testing_validators_set = { + lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator::name(), + lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator::name()}; + + for (const auto & name : testing_validators_set) { + std::cout << name << std::endl; + EXPECT_TRUE(expected_validators_set.find(name) != expected_validators_set.end()) + << "Unexpected validator found: " << name; + } +} + +TEST_F(TestSuite, RegulatoryElementOfTrafficLightWithoutTrafficLight) // NOLINT for gtest +{ + // Check regulatory element of traffic light without traffic light + + RegulatoryElementPtr tl_reg_elem_no_tl; + // Line string without traffic light attribute + const auto & ls = LineString3d(99998, {}); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({ls}); + // Traffic light regulatory element without traffic light. It refers to the line string without + // traffic light attribute. + tl_reg_elem_no_tl = TrafficLight::make( + 99999, tl_re_attr, {ls}, + {LineString3d( + getId(), {Point3d(getId(), 3.0, 3.0, 0.1), Point3d(getId(), 3.0, 4.0, 0.1)}, sl_attr)}); + test_map_ptr->add(tl_reg_elem_no_tl); + addTestMap(test_map_ptr); + + lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; + const auto & issues = checker(*test_map_ptr); + + uint8_t expected_num_issues = 2; + static constexpr const char * expected_message1 = + "Refers of traffic light regulatory element must have type of traffic_light."; + static constexpr const char * expected_message2 = + "Regulatory element of traffic light must have a traffic light(refers)."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + if (issue.id == 99998) { + EXPECT_EQ(expected_message1, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::LineString, issue.primitive); + } else if (issue.id == 99999) { + EXPECT_EQ(expected_message2, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); + } else { + FAIL() << "Unexpected issue id: " << issue.id; + } + } +} + +TEST_F(TestSuite, RegulatoryElementOfTrafficLightWithoutStopLine) // NOLINT for gtest +{ + // Check regulatory element of traffic light without stop line + + RegulatoryElementPtr tl_reg_elem_no_sl; + // Line string without stop line attribute + const auto & ls = LineString3d(99998, {}); + const auto & tl = LineString3d( + getId(), {Point3d(getId(), 0.0, 3.0, 5.0), Point3d(getId(), 0.0, 4.0, 5.0)}, tl_attr); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({tl}); + // Traffic light regulatory element without stop line. It refers to the line string without stop + // line attribute. + tl_reg_elem_no_sl = TrafficLight::make(99999, tl_re_attr, {tl}, {ls}); + test_map_ptr->add(tl_reg_elem_no_sl); + addTestMap(test_map_ptr); + + lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; + const auto & issues = checker(*test_map_ptr); + + uint8_t expected_num_issues = 2; + static constexpr const char * expected_message1 = + "ref_line of traffic light regulatory element must have type of stop_line."; + static constexpr const char * expected_message2 = + "Regulatory element of traffic light must have a stop line(ref_line)."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + if (issue.id == 99998) { + EXPECT_EQ(expected_message1, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::LineString, issue.primitive); + } else if (issue.id == 99999) { + EXPECT_EQ(expected_message2, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); + } else { + FAIL() << "Unexpected issue id: " << issue.id; + } + } +} + +TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutPolygon) // NOLINT for gtest +{ + // Check regulatory element of crosswalk without polygon + + RegulatoryElementPtr cw_reg_elem_no_poly; + Lanelet cw_no_poly = Lanelet( + getId(), + LineString3d(getId(), {Point3d(getId(), 3.0, 0.0, 0.1), Point3d(getId(), 3.0, 1.0, 0.1)}), + LineString3d(getId(), {Point3d(getId(), 3.0, 1.0, 0.1), Point3d(getId(), 3.0, 2.0, 0.1)}), + cw_attr); + + // Crosswalk regulatory element without crosswalk polygon. It refers to the polygon without cross + // walk polygon attribute. + RegulatoryElementPtr reg_elem = Crosswalk::make( + 99999, cw_re_attr, cw_no_poly, Polygon3d(99998), + {LineString3d( + getId(), {Point3d(getId(), 3.0, 3.0, 0.1), Point3d(getId(), 3.0, 4.0, 0.1)}, sl_attr)}); + cw_no_poly.addRegulatoryElement(reg_elem); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({cw_no_poly}); + addTestMap(test_map_ptr); + + lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*test_map_ptr); + + uint8_t expected_num_issues = 2; + static constexpr const char * expected_message1 = + "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."; + static constexpr const char * expected_message2 = + "Regulatory element of crosswalk is nice to have crosswalk_polygon."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + if (issue.id == 99998) { + EXPECT_EQ(expected_message1, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::Polygon, issue.primitive); + } else if (issue.id == 99999) { + EXPECT_EQ(expected_message2, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Warning, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); + } else { + FAIL() << "Unexpected issue id: " << issue.id; + } + } +} + +TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutStopline) // NOLINT for gtest +{ + // Check regulatory element of crosswalk without stop line + + Lanelet cw_no_sl = Lanelet( + getId(), + LineString3d(getId(), {Point3d(getId(), 3.0, 0.0, 0.1), Point3d(getId(), 3.0, 1.0, 0.1)}), + LineString3d(getId(), {Point3d(getId(), 3.0, 1.0, 0.1), Point3d(getId(), 3.0, 2.0, 0.1)}), + cw_attr); + + // Crosswalk regulatory element without stop line. + RegulatoryElementPtr reg_elem = Crosswalk::make( + 99999, cw_re_attr, cw_no_sl, + Polygon3d(getId(), {Point3d(getId(), 3.0, 3.0, 0.1)}, cw_poly_attr), {}); + cw_no_sl.addRegulatoryElement(reg_elem); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({cw_no_sl}); + addTestMap(test_map_ptr); + + lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*test_map_ptr); + + uint8_t expected_num_issues = 1; + static constexpr const char * expected_message = + "Regulatory element of crosswalk does not have stop line(ref_line)."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + EXPECT_EQ(expected_message, issue.message); + EXPECT_EQ(99999, issue.id); + EXPECT_EQ(lanelet::validation::Severity::Info, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); + } +} + +TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutCrosswalk) // NOLINT for gtest +{ + // Check regulatory element of crosswalk without crosswalk + + const auto poly = Polygon3d(getId(), {Point3d(getId(), 3.0, 3.0, 0.1)}, cw_poly_attr); + // Lanelet without crosswalk attribute + const auto ll = Lanelet( + 99998, + LineString3d(getId(), {Point3d(getId(), 3.0, 0.0, 0.1), Point3d(getId(), 3.0, 1.0, 0.1)}), + LineString3d(getId(), {Point3d(getId(), 3.0, 1.0, 0.1), Point3d(getId(), 3.0, 2.0, 0.1)})); + // Crosswalk regulatory element without crosswalk. It refers to the lanelet without crosswalk + RegulatoryElementPtr reg_elem = Crosswalk::make( + 99999, cw_re_attr, ll, poly, + {LineString3d( + getId(), {Point3d(getId(), 3.0, 3.0, 0.1), Point3d(getId(), 3.0, 4.0, 0.1)}, sl_attr)}); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({poly}); + addTestMap(test_map_ptr); + test_map_ptr->add(reg_elem); + + lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*test_map_ptr); + + uint8_t expected_num_issues = 2; + static constexpr const char * expected_message1 = + "Refers of crosswalk regulatory element must have type of crosswalk."; + static constexpr const char * expected_message2 = + "Regulatory element of crosswalk must have lanelet of crosswalk(refers)."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + if (issue.id == 99998) { + EXPECT_EQ(expected_message1, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::Lanelet, issue.primitive); + } else if (issue.id == 99999) { + EXPECT_EQ(expected_message2, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); + } else { + FAIL() << "Unexpected issue id: " << issue.id; + } + } +}