|
| 1 | +// Copyright 2026 Autoware Foundation |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include "lanelet2_map_merger.hpp" |
| 16 | + |
| 17 | +#include "local_projector.hpp" |
| 18 | + |
| 19 | +#include <autoware/geography_utils/lanelet2_projector.hpp> |
| 20 | +#include <autoware/map_projection_loader/map_projection_loader.hpp> |
| 21 | +#include <autoware_lanelet2_extension/io/autoware_osm_parser.hpp> |
| 22 | + |
| 23 | +#include <lanelet2_io/Io.h> |
| 24 | + |
| 25 | +#include <algorithm> |
| 26 | +#include <filesystem> |
| 27 | +#include <memory> |
| 28 | +#include <string> |
| 29 | +#include <vector> |
| 30 | + |
| 31 | +namespace fs = std::filesystem; |
| 32 | + |
| 33 | +namespace autoware::lanelet2_map_merger |
| 34 | +{ |
| 35 | + |
| 36 | +namespace |
| 37 | +{ |
| 38 | + |
| 39 | +bool is_osm_file(const fs::path & path) |
| 40 | +{ |
| 41 | + if (fs::is_directory(path)) { |
| 42 | + return false; |
| 43 | + } |
| 44 | + const std::string ext = path.extension().string(); |
| 45 | + return ext == ".osm" || ext == ".OSM"; |
| 46 | +} |
| 47 | + |
| 48 | +} // namespace |
| 49 | + |
| 50 | +std::vector<std::string> Lanelet2MapMerger::discover_osm_files(const std::string & input_dir) const |
| 51 | +{ |
| 52 | + std::vector<std::string> osm_files; |
| 53 | + fs::path input_path(input_dir); |
| 54 | + |
| 55 | + if (!fs::exists(input_path) || !fs::is_directory(input_path)) { |
| 56 | + RCLCPP_ERROR(logger_, "Input is not a valid directory: %s", input_dir.c_str()); |
| 57 | + return osm_files; |
| 58 | + } |
| 59 | + |
| 60 | + for (const auto & entry : fs::directory_iterator(input_path)) { |
| 61 | + if (is_osm_file(entry.path())) { |
| 62 | + osm_files.push_back(entry.path().string()); |
| 63 | + } |
| 64 | + } |
| 65 | + std::sort(osm_files.begin(), osm_files.end()); |
| 66 | + |
| 67 | + RCLCPP_INFO(logger_, "Found %zu .osm files in %s", osm_files.size(), input_dir.c_str()); |
| 68 | + return osm_files; |
| 69 | +} |
| 70 | + |
| 71 | +std::unique_ptr<lanelet::Projector> Lanelet2MapMerger::create_projector( |
| 72 | + const autoware_map_msgs::msg::MapProjectorInfo & projector_info) const |
| 73 | +{ |
| 74 | + if (projector_info.projector_type == autoware_map_msgs::msg::MapProjectorInfo::LOCAL) { |
| 75 | + return std::make_unique<LocalProjector>(); |
| 76 | + } |
| 77 | + return autoware::geography_utils::get_lanelet2_projector(projector_info); |
| 78 | +} |
| 79 | + |
| 80 | +lanelet::LaneletMapPtr Lanelet2MapMerger::load_and_merge_maps( |
| 81 | + const std::vector<std::string> & osm_files, |
| 82 | + const autoware_map_msgs::msg::MapProjectorInfo & projector_info, |
| 83 | + lanelet::Projector & projector) |
| 84 | +{ |
| 85 | + auto merged = std::make_shared<lanelet::LaneletMap>(); |
| 86 | + |
| 87 | + const bool is_local = |
| 88 | + projector_info.projector_type == autoware_map_msgs::msg::MapProjectorInfo::LOCAL; |
| 89 | + |
| 90 | + for (const auto & path : osm_files) { |
| 91 | + RCLCPP_INFO(logger_, "Loading %s", path.c_str()); |
| 92 | + lanelet::ErrorMessages errors; |
| 93 | + lanelet::LaneletMapPtr map = |
| 94 | + lanelet::load(path, "autoware_osm_handler", projector, &errors); |
| 95 | + for (const auto & error : errors) { |
| 96 | + RCLCPP_ERROR(logger_, "Error loading %s: %s", path.c_str(), error.c_str()); |
| 97 | + } |
| 98 | + if (!errors.empty() || !map) { |
| 99 | + return nullptr; |
| 100 | + } |
| 101 | + |
| 102 | + if (is_local) { |
| 103 | + for (lanelet::Point3d point : map->pointLayer) { |
| 104 | + if (point.hasAttribute("local_x")) { |
| 105 | + point.x() = point.attribute("local_x").asDouble().value(); |
| 106 | + } |
| 107 | + if (point.hasAttribute("local_y")) { |
| 108 | + point.y() = point.attribute("local_y").asDouble().value(); |
| 109 | + } |
| 110 | + } |
| 111 | + } |
| 112 | + |
| 113 | + // Merge with deduplication of shared points (same id), matching |
| 114 | + // lanelet2_map_loader's merge_lanelet2_maps behavior. |
| 115 | + for (lanelet::Lanelet & llt : map->laneletLayer) { |
| 116 | + merged->add(llt); |
| 117 | + } |
| 118 | + for (lanelet::Area & area : map->areaLayer) { |
| 119 | + merged->add(area); |
| 120 | + } |
| 121 | + for (lanelet::RegulatoryElementPtr & reg : map->regulatoryElementLayer) { |
| 122 | + merged->add(reg); |
| 123 | + } |
| 124 | + for (lanelet::LineString3d & ls : map->lineStringLayer) { |
| 125 | + for (lanelet::Point3d & pt : ls) { |
| 126 | + if (merged->pointLayer.find(pt.id()) != merged->pointLayer.end()) { |
| 127 | + pt = merged->pointLayer.get(pt.id()); |
| 128 | + } |
| 129 | + } |
| 130 | + merged->add(ls); |
| 131 | + } |
| 132 | + for (lanelet::Polygon3d & poly : map->polygonLayer) { |
| 133 | + merged->add(poly); |
| 134 | + } |
| 135 | + for (lanelet::Point3d & pt : map->pointLayer) { |
| 136 | + if (merged->pointLayer.find(pt.id()) == merged->pointLayer.end()) { |
| 137 | + merged->add(pt); |
| 138 | + } |
| 139 | + } |
| 140 | + |
| 141 | + // Keep the source map alive so weak references from regulatory elements |
| 142 | + // (e.g., parameters referencing other lanelets/linestrings) do not expire. |
| 143 | + loaded_maps_.push_back(map); |
| 144 | + } |
| 145 | + |
| 146 | + return merged; |
| 147 | +} |
| 148 | + |
| 149 | +void Lanelet2MapMerger::run() |
| 150 | +{ |
| 151 | + const auto osm_files = discover_osm_files(input_dir_); |
| 152 | + if (osm_files.empty()) { |
| 153 | + RCLCPP_ERROR(logger_, "No .osm files found under %s", input_dir_.c_str()); |
| 154 | + return; |
| 155 | + } |
| 156 | + |
| 157 | + autoware_map_msgs::msg::MapProjectorInfo projector_info; |
| 158 | + try { |
| 159 | + projector_info = |
| 160 | + autoware::map_projection_loader::load_info_from_yaml(map_projector_info_path_); |
| 161 | + } catch (const std::exception & e) { |
| 162 | + RCLCPP_ERROR( |
| 163 | + logger_, "Failed to load map projector info from %s: %s", map_projector_info_path_.c_str(), |
| 164 | + e.what()); |
| 165 | + return; |
| 166 | + } |
| 167 | + RCLCPP_INFO(logger_, "Projector type: %s", projector_info.projector_type.c_str()); |
| 168 | + |
| 169 | + std::unique_ptr<lanelet::Projector> projector; |
| 170 | + try { |
| 171 | + projector = create_projector(projector_info); |
| 172 | + } catch (const std::exception & e) { |
| 173 | + RCLCPP_ERROR(logger_, "Failed to create projector: %s", e.what()); |
| 174 | + return; |
| 175 | + } |
| 176 | + |
| 177 | + lanelet::LaneletMapPtr merged = load_and_merge_maps(osm_files, projector_info, *projector); |
| 178 | + if (!merged) { |
| 179 | + RCLCPP_ERROR(logger_, "Failed to load Lanelet2 maps from %s", input_dir_.c_str()); |
| 180 | + return; |
| 181 | + } |
| 182 | + |
| 183 | + const fs::path out_path(output_); |
| 184 | + if (out_path.has_parent_path()) { |
| 185 | + fs::create_directories(out_path.parent_path()); |
| 186 | + } |
| 187 | + if (fs::exists(out_path)) { |
| 188 | + fs::remove(out_path); |
| 189 | + } |
| 190 | + |
| 191 | + lanelet::write(output_, *merged, *projector); |
| 192 | + RCLCPP_INFO(logger_, "Saved merged map: %s", output_.c_str()); |
| 193 | +} |
| 194 | + |
| 195 | +} // namespace autoware::lanelet2_map_merger |
0 commit comments