Skip to content

Commit

Permalink
check major version in map_loader and route_handler
Browse files Browse the repository at this point in the history
Signed-off-by: Mamoru Sobue <[email protected]>
  • Loading branch information
soblin committed Jun 12, 2024
1 parent 3e0a039 commit 533965a
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -93,15 +93,19 @@ void Lanelet2MapLoaderNode::on_map_projector_info(
throw std::invalid_argument(
"allow_unsupported_version is false, so stop loading lanelet map");
}
} else if (const int map_major_ver = static_cast<int>(format_version[0] - '0');
map_major_ver > static_cast<int>(version)) {
RCLCPP_WARN(
get_logger(),
"format_version(%d) of the provided map(%s) is larger than the supported version(%d)",
map_major_ver, lanelet2_filename.c_str(), static_cast<int>(version));
if (!allow_unsupported_version) {
throw std::invalid_argument(
"allow_unsupported_version is false, so stop loading lanelet map");
} else if (const auto map_major_ver_opt = lanelet::io_handlers::parseMajorVersion(format_version);
map_major_ver_opt.has_value()) {
const auto map_major_ver = map_major_ver_opt.value();
if (map_major_ver > static_cast<uint64_t>(lanelet::autoware::version)) {
RCLCPP_WARN(
get_logger(),
"format_version(%ld) of the provided map(%s) is larger than the supported version(%ld)",
map_major_ver, lanelet2_filename.c_str(),
static_cast<uint64_t>(lanelet::autoware::version));
if (!allow_unsupported_version) {
throw std::invalid_argument(
"allow_unsupported_version is false, so stop loading lanelet map");
}
}
}
RCLCPP_INFO(get_logger(), "Loaded map format_version: %s", format_version.c_str());
Expand Down
11 changes: 11 additions & 0 deletions planning/autoware_route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "autoware_route_handler/route_handler.hpp"

#include <autoware_utils/math/normalization.hpp>
#include <lanelet2_extension/io/autoware_osm_parser.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/route_checker.hpp>
Expand Down Expand Up @@ -186,6 +187,16 @@ void RouteHandler::setMap(const LaneletMapBin & map_msg)
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
lanelet::utils::conversion::fromBinMsg(
map_msg, lanelet_map_ptr_, &traffic_rules_ptr_, &routing_graph_ptr_);
const auto map_major_version_opt =
lanelet::io_handlers::parseMajorVersion(map_msg.version_map_format);
if (!map_major_version_opt) {
RCLCPP_WARN(
logger_, "setMap() for invalid version map: %s", map_msg.version_map_format.c_str());
} else if (map_major_version_opt.value() > static_cast<uint64_t>(lanelet::autoware::version)) {
RCLCPP_WARN(
logger_, "setMap() for a map(version %s) newer than lanelet2_extension support version(%d)",
map_msg.version_map_format.c_str(), static_cast<int>(lanelet::autoware::version));
}

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

0 comments on commit 533965a

Please sign in to comment.