@@ -54,7 +54,7 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
54
54
const auto center_line_resolution = declare_parameter (" center_line_resolution" , 5.0 );
55
55
56
56
// load map from file
57
- const auto map = load_map (lanelet2_filename, lanelet2_map_projector_type);
57
+ const auto map = load_map (* this , lanelet2_filename, lanelet2_map_projector_type);
58
58
if (!map) {
59
59
return ;
60
60
}
@@ -63,7 +63,7 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
63
63
lanelet::utils::overwriteLaneletsCenterline (map, center_line_resolution, false );
64
64
65
65
// create map bin msg
66
- const auto map_bin_msg = create_map_bin_msg (map, lanelet2_filename);
66
+ const auto map_bin_msg = create_map_bin_msg (map, lanelet2_filename, now () );
67
67
68
68
// create publisher and publish
69
69
pub_map_bin_ =
@@ -72,7 +72,8 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
72
72
}
73
73
74
74
lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map (
75
- const std::string & lanelet2_filename, const std::string & lanelet2_map_projector_type)
75
+ rclcpp::Node & node, const std::string & lanelet2_filename,
76
+ const std::string & lanelet2_map_projector_type)
76
77
{
77
78
lanelet::ErrorMessages errors{};
78
79
if (lanelet2_map_projector_type == " MGRS" ) {
@@ -82,8 +83,8 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map(
82
83
return map;
83
84
}
84
85
} else if (lanelet2_map_projector_type == " UTM" ) {
85
- const double map_origin_lat = declare_parameter (" latitude" , 0.0 );
86
- const double map_origin_lon = declare_parameter (" longitude" , 0.0 );
86
+ const double map_origin_lat = node. declare_parameter (" latitude" , 0.0 );
87
+ const double map_origin_lon = node. declare_parameter (" longitude" , 0.0 );
87
88
lanelet::GPSPoint position{map_origin_lat, map_origin_lon};
88
89
lanelet::Origin origin{position};
89
90
lanelet::projection::UtmProjector projector{origin};
@@ -93,25 +94,25 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map(
93
94
return map;
94
95
}
95
96
} else {
96
- RCLCPP_ERROR (get_logger (), " lanelet2_map_projector_type is not supported" );
97
+ RCLCPP_ERROR (rclcpp:: get_logger (" map_loader " ), " lanelet2_map_projector_type is not supported" );
97
98
return nullptr ;
98
99
}
99
100
100
101
for (const auto & error : errors) {
101
- RCLCPP_ERROR_STREAM (get_logger (), error);
102
+ RCLCPP_ERROR_STREAM (rclcpp:: get_logger (" map_loader " ), error);
102
103
}
103
104
return nullptr ;
104
105
}
105
106
106
107
HADMapBin Lanelet2MapLoaderNode::create_map_bin_msg (
107
- const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename)
108
+ const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now )
108
109
{
109
110
std::string format_version{}, map_version{};
110
111
lanelet::io_handlers::AutowareOsmParser::parseVersions (
111
112
lanelet2_filename, &format_version, &map_version);
112
113
113
114
HADMapBin map_bin_msg;
114
- map_bin_msg.header .stamp = now () ;
115
+ map_bin_msg.header .stamp = now;
115
116
map_bin_msg.header .frame_id = " map" ;
116
117
map_bin_msg.format_version = format_version;
117
118
map_bin_msg.map_version = map_version;
0 commit comments