49
49
#include < lanelet2_io/Io.h>
50
50
#include < lanelet2_projection/UTM.h>
51
51
52
+ #include < stdexcept>
52
53
#include < string>
53
54
54
55
Lanelet2MapLoaderNode::Lanelet2MapLoaderNode (const rclcpp::NodeOptions & options)
@@ -61,13 +62,15 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
61
62
sub_map_projector_info_,
62
63
[this ](const MapProjectorInfo::Message::ConstSharedPtr msg) { on_map_projector_info (msg); });
63
64
65
+ declare_parameter<bool >(" allow_unsupported_version" );
64
66
declare_parameter<std::string>(" lanelet2_map_path" );
65
67
declare_parameter<double >(" center_line_resolution" );
66
68
}
67
69
68
70
void Lanelet2MapLoaderNode::on_map_projector_info (
69
71
const MapProjectorInfo::Message::ConstSharedPtr msg)
70
72
{
73
+ const auto allow_unsupported_version = get_parameter (" allow_unsupported_version" ).as_bool ();
71
74
const auto lanelet2_filename = get_parameter (" lanelet2_map_path" ).as_string ();
72
75
const auto center_line_resolution = get_parameter (" center_line_resolution" ).as_double ();
73
76
@@ -78,6 +81,31 @@ void Lanelet2MapLoaderNode::on_map_projector_info(
78
81
return ;
79
82
}
80
83
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
+
81
109
// overwrite centerline
82
110
lanelet::utils::overwriteLaneletsCenterline (map, center_line_resolution, false );
83
111
0 commit comments