feat: add autoware_lanelet2_map_divider package#409
feat: add autoware_lanelet2_map_divider package#409mitsudome-r wants to merge 3 commits intoautowarefoundation:mainfrom
Conversation
Signed-off-by: Ryohsuke Mitsudome <ryohsuke.mitsudome@tier4.jp>
|
Thank you for contributing to the Autoware project! 🚧 If your pull request is in progress, switch it to draft mode. Please ensure:
|
Signed-off-by: Ryohsuke Mitsudome <ryohsuke.mitsudome@tier4.jp>
There was a problem hiding this comment.
Pull request overview
Adds a new autoware_lanelet2_map_divider ROS 2 package to split a single Lanelet2 .osm into grid-aligned per-cell map files and emit lanelet2_map_metadata.yaml compatible with lanelet2_map_loader’s selected-map-loading mode.
Changes:
- Introduces
Lanelet2MapDividerlibrary andLanelet2MapDividerNodecomponent/executable for dividing and exporting per-cell.osmtiles + metadata. - Adds launch/config/schema + README documenting usage and output format.
- Adds a gtest suite that builds a synthetic map, runs the divider, and validates output tiles/metadata.
Reviewed changes
Copilot reviewed 12 out of 12 changed files in this pull request and generated 8 comments.
Show a summary per file
| File | Description |
|---|---|
| map/autoware_lanelet2_map_divider/src/lanelet2_map_divider.cpp | Core map loading, grid partitioning, tile writing, and metadata generation |
| map/autoware_lanelet2_map_divider/src/lanelet2_map_divider.hpp | Public API for configuring/running the divider |
| map/autoware_lanelet2_map_divider/src/lanelet2_map_divider_node.cpp | ROS 2 node wrapper to run divider from parameters |
| map/autoware_lanelet2_map_divider/src/lanelet2_map_divider_node.hpp | Node declaration |
| map/autoware_lanelet2_map_divider/src/local_projector.hpp | Local projector helper for projector_type: Local |
| map/autoware_lanelet2_map_divider/test/test_lanelet2_map_divider.cpp | gtest coverage for tiling + metadata behaviors |
| map/autoware_lanelet2_map_divider/launch/lanelet2_map_divider.launch.xml | Launch entrypoint with args and parameter wiring |
| map/autoware_lanelet2_map_divider/config/lanelet2_map_divider.param.yaml | Default parameter file used by launch |
| map/autoware_lanelet2_map_divider/schema/lanelet2_map_divider.schema.json | Parameter schema for documentation/validation |
| map/autoware_lanelet2_map_divider/README.md | User-facing documentation and format description |
| map/autoware_lanelet2_map_divider/CMakeLists.txt | Build/test targets and component registration |
| map/autoware_lanelet2_map_divider/package.xml | Package dependencies and metadata |
💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.
| void Lanelet2MapDivider::prepare_output_directory(const std::string & cell_dir) const | ||
| { | ||
| if (fs::exists(output_dir_)) { | ||
| fs::remove_all(output_dir_); | ||
| } | ||
| fs::create_directories(cell_dir); | ||
| } |
There was a problem hiding this comment.
prepare_output_directory() unconditionally calls remove_all(output_dir_). If output_dir_ is empty (""), this resolves to the current directory and can delete the entire working tree; similarly, passing "/" (or other critical paths) would be catastrophic. Add a hard safety check in run()/prepare_output_directory() to reject empty/relative/root paths (and ideally require an absolute output directory) before deleting anything, and fail fast with a clear error log.
| const auto gx_start = static_cast<int>(std::floor(min_x / grid_size_x_) * grid_size_x_); | ||
| const auto gy_start = static_cast<int>(std::floor(min_y / grid_size_y_) * grid_size_y_); | ||
| const auto gx_end = static_cast<int>(std::floor(max_x / grid_size_x_) * grid_size_x_); | ||
| const auto gy_end = static_cast<int>(std::floor(max_y / grid_size_y_) * grid_size_y_); | ||
|
|
||
| RCLCPP_INFO( | ||
| logger_, "Map bounding box: [%.3f, %.3f] to [%.3f, %.3f]", min_x, min_y, max_x, max_y); | ||
| RCLCPP_INFO( | ||
| logger_, "Grid range (coord-aligned): x=[%d, %d], y=[%d, %d]", gx_start, gx_end, gy_start, | ||
| gy_end); | ||
|
|
||
| const auto step_x = static_cast<int>(grid_size_x_); | ||
| const auto step_y = static_cast<int>(grid_size_y_); | ||
|
|
||
| for (int gx = gx_start; gx <= gx_end; gx += step_x) { | ||
| for (int gy = gy_start; gy <= gy_end; gy += step_y) { |
There was a problem hiding this comment.
Grid stepping is computed as step_x = static_cast<int>(grid_size_x_) / step_y = static_cast<int>(grid_size_y_). This truncates non-integer grid sizes and can become 0 when grid_size_* < 1.0, causing an infinite loop in the for (int gx = ...; gx += step_x) loops. Either validate grid_size_x_/grid_size_y_ are >= 1.0 (and integral if required by the file naming/metadata format) or change the iteration/indexing to use a non-truncating type (e.g., integer millimeters or doubles with a robust rounding strategy).
| file << "x_resolution: " << grid_size_x_ << "\n"; | ||
| file << "y_resolution: " << grid_size_y_ << "\n"; | ||
| for (const auto & cell : cells) { | ||
| const auto & [file_name, gx, gy] = cell; | ||
| file << file_name << ": [" << gx << ", " << gy << "]\n"; | ||
| } |
There was a problem hiding this comment.
out_cells stores (file_name, gx, gy) as integers and write_metadata() writes those as [gx, gy], but grid_size_* are doubles and the README/YAML format examples show floating coordinates. If non-integer grid sizes are allowed, this silently loses precision and produces incorrect metadata. Consider storing/writing gx/gy as doubles (or enforce/validate integer meter grid sizes and document that constraint).
| }, | ||
| "input_lanelet2_map": { | ||
| "type": "string", | ||
| "description": "Path to a single .osm file or a directory containing .osm files", |
There was a problem hiding this comment.
This schema claims input_lanelet2_map can be a directory of .osm files, but the implementation rejects directories (is_osm_file() returns false for directories) and the README says only a single .osm file is supported. Update the schema description (and/or implementation) so parameter docs match actual behavior.
| "description": "Path to a single .osm file or a directory containing .osm files", | |
| "description": "Path to a single .osm file", |
| <arg name="config_file_path" default="$(find-pkg-share autoware_lanelet2_map_divider)/config/lanelet2_map_divider.param.yaml" description="Path to the configuration YAML file"/> | ||
| <arg name="grid_size_x" default="100.0" description="The X size (m) of each output segment"/> | ||
| <arg name="grid_size_y" default="100.0" description="The Y size (m) of each output segment"/> | ||
| <arg name="input_lanelet2_map" description="Path to a single .osm file or a directory containing .osm files"/> |
There was a problem hiding this comment.
The launch argument description says input_lanelet2_map may be a directory of .osm files, but the node/tool currently rejects directory input and expects a single .osm file. Please align this description (and the param YAML/schema) with the actual supported input.
| <arg name="input_lanelet2_map" description="Path to a single .osm file or a directory containing .osm files"/> | |
| <arg name="input_lanelet2_map" description="Path to a single .osm file"/> |
| #include "../src/lanelet2_map_divider.hpp" | ||
| #include "../src/local_projector.hpp" | ||
|
|
||
| #include <rclcpp/logger.hpp> | ||
|
|
||
| #include <gtest/gtest.h> | ||
| #include <lanelet2_core/LaneletMap.h> | ||
| #include <lanelet2_core/primitives/Lanelet.h> | ||
| #include <lanelet2_core/primitives/LineString.h> | ||
| #include <lanelet2_core/primitives/Point.h> | ||
| #include <lanelet2_io/Io.h> | ||
| #include <yaml-cpp/yaml.h> | ||
|
|
||
| #include <filesystem> | ||
| #include <fstream> | ||
| #include <map> | ||
| #include <memory> | ||
| #include <set> | ||
| #include <string> | ||
| #include <vector> | ||
|
|
There was a problem hiding this comment.
This test uses std::fmod but does not include <cmath>. It may compile only via transitive includes, which is fragile. Add an explicit <cmath> include to ensure the declaration is available across toolchains.
| void SetUp() override | ||
| { | ||
| tmp_dir_ = fs::temp_directory_path() / "test_lanelet2_map_divider"; | ||
| fs::remove_all(tmp_dir_); | ||
| fs::create_directories(tmp_dir_); | ||
| } |
There was a problem hiding this comment.
The test fixture always uses the same temp directory name (.../test_lanelet2_map_divider). If tests are ever run concurrently (e.g., repeated invocations, parallel test runners), they can interfere with each other by deleting each other’s directories. Consider incorporating a unique suffix (PID, timestamp, random) into tmp_dir_ to avoid collisions.
| "grid_size_y", | ||
| "input_lanelet2_map", | ||
| "output_lanelet2_map_dir", | ||
| "map_projector_info_path" |
There was a problem hiding this comment.
The node declares prefix via declare_parameter<std::string>("prefix") without a default, so it is effectively required at runtime. However, the schema’s required list omits prefix, which can lead to generated/validated param files that crash the node on startup. Either add prefix to required here or change the node to declare it with a default (e.g., empty string).
| "map_projector_info_path" | |
| "map_projector_info_path", | |
| "prefix" |
Description
This is part of autowarefoundation/autoware_core#887
Add a new
autoware_lanelet2_map_dividerpackage that splits a single Lanelet2 (.osm) map into grid-aligned segments and emits a metadata file compatible withlanelet2_map_loader's selected-map-loading mode.autoware_lanelet2_map_divider_nodewith a launch filemap_projector_info.yaml(MGRS,LocalCartesianUTM,LocalCartesian,TransverseMercator, andLocalsupported), computes the axis-aligned bounding box of all points, and querieslaneletLayer,areaLayer,lineStringLayer, andpointLayerper cell to build per-cellLaneletMaps.<prefix>_<gx>_<gy>.osmfile per non-empty cell under<OUTPUT_DIR>/lanelet2_map.osm/with the same projector used at load time, pluslanelet2_map_metadata.yaml(x_resolution,y_resolution, andfile: [min_x, min_y]entries).test_lanelet2_map_divider).How was this PR tested?
colcon build --packages-select autoware_lanelet2_map_divider.test_lanelet2_map_divider) viacolcon test.lanelet2_map.osm, inspecting the generatedlanelet2_map.osm/<gx>_<gy>.osmfiles andlanelet2_map_metadata.yaml, and confirminglanelet2_map_loadercan consume the output in selected-map-loading mode.Notes for reviewers
None.
Effects on system behavior
None.