Skip to content

Commit 0a9746b

Browse files
committed
feat(map_loader): add format_version validation
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 173aae4 commit 0a9746b

File tree

4 files changed

+38
-0
lines changed

4 files changed

+38
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
/**:
22
ros__parameters:
3+
allow_unsupported_version: false # flag to load unsupported format_version anyway. If true, just prints warning.
34
center_line_resolution: 5.0 # [m]
45
lanelet2_map_path: $(var lanelet2_map_path) # The lanelet2 map path

map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include <component_interface_specs/map.hpp>
1919
#include <component_interface_utils/rclcpp.hpp>
20+
#include <lanelet2_extension/version.hpp>
2021
#include <rclcpp/rclcpp.hpp>
2122

2223
#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
@@ -32,6 +33,9 @@ using tier4_map_msgs::msg::MapProjectorInfo;
3233

3334
class Lanelet2MapLoaderNode : public rclcpp::Node
3435
{
36+
public:
37+
static constexpr lanelet::autoware::Version version = lanelet::autoware::version;
38+
3539
public:
3640
explicit Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options);
3741

map/map_loader/schema/lanelet2_map_loader.schema.json

+5
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,11 @@
66
"lanelet2_map_loader": {
77
"type": "object",
88
"properties": {
9+
"allow_unsupported_version": {
10+
"type": "boolean",
11+
"description": "Flag to load unsupported format_version anyway. If true, just prints warning.",
12+
"default": "true"
13+
},
914
"center_line_resolution": {
1015
"type": "number",
1116
"description": "Resolution of the Lanelet center line [m]",

map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp

+28
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@
4949
#include <lanelet2_io/Io.h>
5050
#include <lanelet2_projection/UTM.h>
5151

52+
#include <stdexcept>
5253
#include <string>
5354

5455
Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options)
@@ -61,13 +62,15 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
6162
sub_map_projector_info_,
6263
[this](const MapProjectorInfo::Message::ConstSharedPtr msg) { on_map_projector_info(msg); });
6364

65+
declare_parameter<bool>("allow_unsupported_version");
6466
declare_parameter<std::string>("lanelet2_map_path");
6567
declare_parameter<double>("center_line_resolution");
6668
}
6769

6870
void Lanelet2MapLoaderNode::on_map_projector_info(
6971
const MapProjectorInfo::Message::ConstSharedPtr msg)
7072
{
73+
const auto allow_unsupported_version = get_parameter("allow_unsupported_version").as_bool();
7174
const auto lanelet2_filename = get_parameter("lanelet2_map_path").as_string();
7275
const auto center_line_resolution = get_parameter("center_line_resolution").as_double();
7376

@@ -78,6 +81,31 @@ void Lanelet2MapLoaderNode::on_map_projector_info(
7881
return;
7982
}
8083

84+
std::string format_version{"null"}, map_version{""};
85+
lanelet::io_handlers::AutowareOsmParser::parseVersions(
86+
lanelet2_filename, &format_version, &map_version);
87+
if (format_version == "null" || format_version.empty() || !isdigit(format_version[0])) {
88+
RCLCPP_WARN(
89+
get_logger(),
90+
"%s has no format_version(null) or non semver-style format_version(%s) information",
91+
lanelet2_filename.c_str(), format_version.c_str());
92+
if (!allow_unsupported_version) {
93+
throw std::invalid_argument(
94+
"allow_unsupported_version is false, so stop loading lanelet map");
95+
}
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");
105+
}
106+
}
107+
RCLCPP_INFO(get_logger(), "Loaded map format_version: %s", format_version.c_str());
108+
81109
// overwrite centerline
82110
lanelet::utils::overwriteLaneletsCenterline(map, center_line_resolution, false);
83111

0 commit comments

Comments
 (0)