Skip to content

feat: add autoware_lanelet2_map_merger package#410

Open
mitsudome-r wants to merge 3 commits intoautowarefoundation:mainfrom
mitsudome-r:feat/add-autoware-lanelet2-map-merger
Open

feat: add autoware_lanelet2_map_merger package#410
mitsudome-r wants to merge 3 commits intoautowarefoundation:mainfrom
mitsudome-r:feat/add-autoware-lanelet2-map-merger

Conversation

@mitsudome-r
Copy link
Copy Markdown
Member

@mitsudome-r mitsudome-r commented Apr 22, 2026

Description

Part of autowarefoundation/autoware_core#887

Add a new autoware_lanelet2_map_merger package that merges a directory of divided Lanelet2 (.osm) map files into a single .osm file.

  • New ROS 2 node autoware_lanelet2_map_merger_node with launch file, parameter YAML, and JSON schema.
  • Loads every .osm file in the input directory using the projector described in map_projector_info.yaml (MGRS, LocalCartesianUTM, LocalCartesian, and TransverseMercator are supported).
  • Merges the loaded maps using the same logic as lanelet2_map_loader (merge_lanelet2_maps), deduplicating points shared across maps by ID so successor/predecessor relationships are preserved, then writes the merged map with lanelet::write.
  • Includes README and a gtest covering the merge behavior.

How was this PR tested?

  • Built the package with colcon build --packages-select autoware_lanelet2_map_merger.
  • Ran the included gtest suite (test_lanelet2_map_merger) via colcon test.
  • Verified end-to-end round-trip by running autoware_lanelet2_map_divider on a sample lanelet2_map.osm and then running this merger on its output, confirming the reconstructed map matches the original.

Notes for reviewers

None.

Effects on system behavior

None.

Signed-off-by: Ryohsuke Mitsudome <ryohsuke.mitsudome@tier4.jp>
@github-actions
Copy link
Copy Markdown

github-actions Bot commented Apr 22, 2026

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>
Copy link
Copy Markdown

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Adds a new ROS 2 “map tool” package that merges a directory of divided Lanelet2 .osm files back into a single .osm, using a projector described by map_projector_info.yaml and preserving shared-point IDs to keep topology consistent.

Changes:

  • Introduces autoware_lanelet2_map_merger library + component node to discover, load, merge, and write Lanelet2 maps.
  • Adds launch/config + parameter JSON schema and README documentation.
  • Adds a gtest that exercises merge/dedup and reload behavior.

Reviewed changes

Copilot reviewed 12 out of 12 changed files in this pull request and generated 7 comments.

Show a summary per file
File Description
map/autoware_lanelet2_map_merger/src/lanelet2_map_merger.cpp Core discovery/load/merge/write implementation.
map/autoware_lanelet2_map_merger/src/lanelet2_map_merger.hpp Merger class interface and state (loaded map lifetime).
map/autoware_lanelet2_map_merger/src/lanelet2_map_merger_node.cpp One-shot ROS 2 node wrapper that runs the merger from parameters.
map/autoware_lanelet2_map_merger/src/lanelet2_map_merger_node.hpp Node class declaration.
map/autoware_lanelet2_map_merger/src/local_projector.hpp Minimal projector used for LOCAL projector-type handling.
map/autoware_lanelet2_map_merger/test/test_lanelet2_map_merger.cpp Unit tests for merge/dedup + reload + non-crash behavior.
map/autoware_lanelet2_map_merger/CMakeLists.txt Build/test targets and component registration.
map/autoware_lanelet2_map_merger/package.xml Package metadata and dependencies.
map/autoware_lanelet2_map_merger/launch/lanelet2_map_merger.launch.xml Launch entrypoint wiring parameters.
map/autoware_lanelet2_map_merger/config/lanelet2_map_merger.param.yaml Default parameter file using launch substitutions.
map/autoware_lanelet2_map_merger/schema/lanelet2_map_merger.schema.json Parameter schema for documentation/validation.
map/autoware_lanelet2_map_merger/README.md Usage and behavior documentation.

💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

Comment on lines +147 to +153
void Lanelet2MapMerger::run()
{
const auto osm_files = discover_osm_files(input_dir_);
if (osm_files.empty()) {
RCLCPP_ERROR(logger_, "No .osm files found under %s", input_dir_.c_str());
return;
}
Copy link

Copilot AI Apr 22, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

loaded_maps_ is an instance member used to keep source maps alive, but it is never cleared. If run() is called more than once on the same Lanelet2MapMerger instance, maps from previous runs will accumulate, increasing memory usage unnecessarily. Clearing loaded_maps_ at the start of run() (or before loading a new set of maps) avoids this.

Copilot uses AI. Check for mistakes.
Comment on lines +61 to +73
for (auto ls : {ls_left_a, ls_right_a, ls_right_b}) {
ls.attributes()["type"] = "line_thin";
ls.attributes()["subtype"] = "solid";
}

lanelet::Lanelet ll_a(100, ls_left_a, ls_right_a);
lanelet::Lanelet ll_b(101, ls_right_a, ls_right_b);
for (auto ll : {ll_a, ll_b}) {
ll.attributes()["type"] = "lanelet";
ll.attributes()["subtype"] = "road";
ll.attributes()["location"] = "urban";
ll.attributes()["one_way"] = "yes";
}
Copy link

Copilot AI Apr 22, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In make_sample_map(), this loop iterates the line strings by value (for (auto ls : {ls_left_a, ...})), so the attribute assignments are applied to temporary copies and do not affect ls_left_a/ls_right_a/ls_right_b. If these attributes are intended to be written into the generated .osm, iterate by reference (e.g., for (auto & ls : ...)) or set attributes directly on each linestring.

Suggested change
for (auto ls : {ls_left_a, ls_right_a, ls_right_b}) {
ls.attributes()["type"] = "line_thin";
ls.attributes()["subtype"] = "solid";
}
lanelet::Lanelet ll_a(100, ls_left_a, ls_right_a);
lanelet::Lanelet ll_b(101, ls_right_a, ls_right_b);
for (auto ll : {ll_a, ll_b}) {
ll.attributes()["type"] = "lanelet";
ll.attributes()["subtype"] = "road";
ll.attributes()["location"] = "urban";
ll.attributes()["one_way"] = "yes";
}
ls_left_a.attributes()["type"] = "line_thin";
ls_left_a.attributes()["subtype"] = "solid";
ls_right_a.attributes()["type"] = "line_thin";
ls_right_a.attributes()["subtype"] = "solid";
ls_right_b.attributes()["type"] = "line_thin";
ls_right_b.attributes()["subtype"] = "solid";
lanelet::Lanelet ll_a(100, ls_left_a, ls_right_a);
lanelet::Lanelet ll_b(101, ls_right_a, ls_right_b);
ll_a.attributes()["type"] = "lanelet";
ll_a.attributes()["subtype"] = "road";
ll_a.attributes()["location"] = "urban";
ll_a.attributes()["one_way"] = "yes";
ll_b.attributes()["type"] = "lanelet";
ll_b.attributes()["subtype"] = "road";
ll_b.attributes()["location"] = "urban";
ll_b.attributes()["one_way"] = "yes";

Copilot uses AI. Check for mistakes.
Comment on lines +61 to +73
for (auto ls : {ls_left_a, ls_right_a, ls_right_b}) {
ls.attributes()["type"] = "line_thin";
ls.attributes()["subtype"] = "solid";
}

lanelet::Lanelet ll_a(100, ls_left_a, ls_right_a);
lanelet::Lanelet ll_b(101, ls_right_a, ls_right_b);
for (auto ll : {ll_a, ll_b}) {
ll.attributes()["type"] = "lanelet";
ll.attributes()["subtype"] = "road";
ll.attributes()["location"] = "urban";
ll.attributes()["one_way"] = "yes";
}
Copy link

Copilot AI Apr 22, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Similarly, this loop iterates lanelets by value (for (auto ll : {ll_a, ll_b})), so the lanelet attribute assignments won't be applied to ll_a/ll_b before adding them to the map. If the test intends to produce realistic lanelet relations (type/subtype/etc.), iterate by reference or set the attributes on ll_a and ll_b directly.

Suggested change
for (auto ls : {ls_left_a, ls_right_a, ls_right_b}) {
ls.attributes()["type"] = "line_thin";
ls.attributes()["subtype"] = "solid";
}
lanelet::Lanelet ll_a(100, ls_left_a, ls_right_a);
lanelet::Lanelet ll_b(101, ls_right_a, ls_right_b);
for (auto ll : {ll_a, ll_b}) {
ll.attributes()["type"] = "lanelet";
ll.attributes()["subtype"] = "road";
ll.attributes()["location"] = "urban";
ll.attributes()["one_way"] = "yes";
}
ls_left_a.attributes()["type"] = "line_thin";
ls_left_a.attributes()["subtype"] = "solid";
ls_right_a.attributes()["type"] = "line_thin";
ls_right_a.attributes()["subtype"] = "solid";
ls_right_b.attributes()["type"] = "line_thin";
ls_right_b.attributes()["subtype"] = "solid";
lanelet::Lanelet ll_a(100, ls_left_a, ls_right_a);
lanelet::Lanelet ll_b(101, ls_right_a, ls_right_b);
ll_a.attributes()["type"] = "lanelet";
ll_a.attributes()["subtype"] = "road";
ll_a.attributes()["location"] = "urban";
ll_a.attributes()["one_way"] = "yes";
ll_b.attributes()["type"] = "lanelet";
ll_b.attributes()["subtype"] = "road";
ll_b.attributes()["location"] = "urban";
ll_b.attributes()["one_way"] = "yes";

Copilot uses AI. Check for mistakes.
Comment on lines +131 to +134
tmp_dir_ = fs::temp_directory_path() / "test_lanelet2_map_merger";
fs::remove_all(tmp_dir_);
fs::create_directories(tmp_dir_);
}
Copy link

Copilot AI Apr 22, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The test uses a fixed temp directory name (fs::temp_directory_path() / "test_lanelet2_map_merger"). If tests are run in parallel (e.g., ctest -j), multiple instances can race on remove_all/create_directories, causing flaky failures. Prefer creating a unique per-test directory (PID + random suffix) and cleaning it up in TearDown().

Copilot uses AI. Check for mistakes.
Comment on lines +18 to +24
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()

ament_add_gtest(test_lanelet2_map_merger test/test_lanelet2_map_merger.cpp)
target_link_libraries(test_lanelet2_map_merger ${PROJECT_NAME})
endif()
Copy link

Copilot AI Apr 22, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The test block calls ament_add_gtest(...) but does not find_package(ament_cmake_gtest REQUIRED) first. In this repo, other packages that use ament_add_gtest explicitly find ament_cmake_gtest in the BUILD_TESTING block; without it, CMake configuration can fail because the macro isn't defined.

Copilot uses AI. Check for mistakes.
Comment on lines +100 to +108
if (is_local) {
for (lanelet::Point3d point : map->pointLayer) {
if (point.hasAttribute("local_x")) {
point.x() = point.attribute("local_x").asDouble().value();
}
if (point.hasAttribute("local_y")) {
point.y() = point.attribute("local_y").asDouble().value();
}
}
Copy link

Copilot AI Apr 22, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In the LOCAL-projector path, the loop iterates map->pointLayer by value (for (lanelet::Point3d point : ...)). Any updates to point.x()/point.y() are applied to the temporary copy and do not modify the points stored in the map, so the merged output will keep the (projector-generated) coordinates (likely all zeros). Iterate by reference (e.g., auto & point) so the loaded map geometry is actually updated before merging/writing.

Copilot uses AI. Check for mistakes.
Comment on lines +103 to +106
point.x() = point.attribute("local_x").asDouble().value();
}
if (point.hasAttribute("local_y")) {
point.y() = point.attribute("local_y").asDouble().value();
Copy link

Copilot AI Apr 22, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

point.attribute("local_x").asDouble().value() (and the same for local_y) will throw if the attribute exists but cannot be parsed as a double. Consider checking the optional returned by asDouble() and logging/handling invalid values to avoid an unexpected exception when merging maps with malformed tags.

Suggested change
point.x() = point.attribute("local_x").asDouble().value();
}
if (point.hasAttribute("local_y")) {
point.y() = point.attribute("local_y").asDouble().value();
const auto local_x = point.attribute("local_x").asDouble();
if (!local_x) {
RCLCPP_ERROR(
logger_, "Invalid local_x attribute in %s for point id %ld", path.c_str(), point.id());
return nullptr;
}
point.x() = *local_x;
}
if (point.hasAttribute("local_y")) {
const auto local_y = point.attribute("local_y").asDouble();
if (!local_y) {
RCLCPP_ERROR(
logger_, "Invalid local_y attribute in %s for point id %ld", path.c_str(), point.id());
return nullptr;
}
point.y() = *local_y;

Copilot uses AI. Check for mistakes.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants