Skip to content

Commit 11206bc

Browse files
committed
check major version in map_loader and route_handler
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent be93711 commit 11206bc

File tree

2 files changed

+24
-9
lines changed

2 files changed

+24
-9
lines changed

map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp

+13-9
Original file line numberDiff line numberDiff line change
@@ -93,15 +93,19 @@ void Lanelet2MapLoaderNode::on_map_projector_info(
9393
throw std::invalid_argument(
9494
"allow_unsupported_version is false, so stop loading lanelet map");
9595
}
96-
} else if (const int map_major_ver = static_cast<int>(format_version[0] - '0');
97-
map_major_ver > static_cast<int>(version)) {
98-
RCLCPP_WARN(
99-
get_logger(),
100-
"format_version(%d) of the provided map(%s) is larger than the supported version(%d)",
101-
map_major_ver, lanelet2_filename.c_str(), static_cast<int>(version));
102-
if (!allow_unsupported_version) {
103-
throw std::invalid_argument(
104-
"allow_unsupported_version is false, so stop loading lanelet map");
96+
} else if (const auto map_major_ver_opt = lanelet::io_handlers::parseMajorVersion(format_version);
97+
map_major_ver_opt.has_value()) {
98+
const auto map_major_ver = map_major_ver_opt.value();
99+
if (map_major_ver > static_cast<uint64_t>(lanelet::autoware::version)) {
100+
RCLCPP_WARN(
101+
get_logger(),
102+
"format_version(%ld) of the provided map(%s) is larger than the supported version(%ld)",
103+
map_major_ver, lanelet2_filename.c_str(),
104+
static_cast<uint64_t>(lanelet::autoware::version));
105+
if (!allow_unsupported_version) {
106+
throw std::invalid_argument(
107+
"allow_unsupported_version is false, so stop loading lanelet map");
108+
}
105109
}
106110
}
107111
RCLCPP_INFO(get_logger(), "Loaded map format_version: %s", format_version.c_str());

planning/autoware_route_handler/src/route_handler.cpp

+11
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#include "autoware_route_handler/route_handler.hpp"
1616

1717
#include <autoware_utils/math/normalization.hpp>
18+
#include <lanelet2_extension/io/autoware_osm_parser.hpp>
1819
#include <lanelet2_extension/utility/message_conversion.hpp>
1920
#include <lanelet2_extension/utility/query.hpp>
2021
#include <lanelet2_extension/utility/route_checker.hpp>
@@ -186,6 +187,16 @@ void RouteHandler::setMap(const LaneletMapBin & map_msg)
186187
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
187188
lanelet::utils::conversion::fromBinMsg(
188189
map_msg, lanelet_map_ptr_, &traffic_rules_ptr_, &routing_graph_ptr_);
190+
const auto map_major_version_opt =
191+
lanelet::io_handlers::parseMajorVersion(map_msg.version_map_format);
192+
if (!map_major_version_opt) {
193+
RCLCPP_WARN(
194+
logger_, "setMap() for invalid version map: %s", map_msg.version_map_format.c_str());
195+
} else if (map_major_version_opt.value() > static_cast<uint64_t>(lanelet::autoware::version)) {
196+
RCLCPP_WARN(
197+
logger_, "setMap() for a map(version %s) newer than lanelet2_extension support version(%d)",
198+
map_msg.version_map_format.c_str(), static_cast<int>(lanelet::autoware::version));
199+
}
189200

190201
const auto traffic_rules = lanelet::traffic_rules::TrafficRulesFactory::create(
191202
lanelet::Locations::Germany, lanelet::Participants::Vehicle);

0 commit comments

Comments
 (0)