@@ -51,47 +51,73 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
51
51
{
52
52
const auto lanelet2_filename = declare_parameter (" lanelet2_map_path" , " " );
53
53
const auto lanelet2_map_projector_type = declare_parameter (" lanelet2_map_projector_type" , " MGRS" );
54
+ const auto center_line_resolution = declare_parameter (" center_line_resolution" , 5.0 );
55
+
56
+ // load map from file
57
+ const auto map = load_map (lanelet2_filename, lanelet2_map_projector_type);
58
+ if (!map) {
59
+ return ;
60
+ }
61
+
62
+ // overwrite centerline
63
+ lanelet::utils::overwriteLaneletsCenterline (map, center_line_resolution, false );
64
+
65
+ // create map bin msg
66
+ const auto map_bin_msg = create_map_bin_msg (map, lanelet2_filename);
67
+
68
+ // create publisher and publish
69
+ pub_map_bin_ =
70
+ create_publisher<HADMapBin>(" output/lanelet2_map" , rclcpp::QoS{1 }.transient_local ());
71
+ pub_map_bin_->publish (map_bin_msg);
72
+ }
73
+
74
+ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map (
75
+ const std::string & lanelet2_filename, const std::string & lanelet2_map_projector_type)
76
+ {
54
77
lanelet::ErrorMessages errors{};
55
- lanelet::LaneletMapPtr map;
56
78
if (lanelet2_map_projector_type == " MGRS" ) {
57
79
lanelet::projection::MGRSProjector projector{};
58
- map = lanelet::load (lanelet2_filename, projector, &errors);
80
+ const lanelet::LaneletMapPtr map = lanelet::load (lanelet2_filename, projector, &errors);
81
+ if (errors.empty ()) {
82
+ return map;
83
+ }
59
84
} else if (lanelet2_map_projector_type == " UTM" ) {
60
- double map_origin_lat = this -> declare_parameter (" latitude" , 0.0 );
61
- double map_origin_lon = this -> declare_parameter (" longitude" , 0.0 );
85
+ const double map_origin_lat = declare_parameter (" latitude" , 0.0 );
86
+ const double map_origin_lon = declare_parameter (" longitude" , 0.0 );
62
87
lanelet::GPSPoint position{map_origin_lat, map_origin_lon};
63
88
lanelet::Origin origin{position};
64
89
lanelet::projection::UtmProjector projector{origin};
65
- map = lanelet::load (lanelet2_filename, projector, &errors);
90
+
91
+ const lanelet::LaneletMapPtr map = lanelet::load (lanelet2_filename, projector, &errors);
92
+ if (errors.empty ()) {
93
+ return map;
94
+ }
66
95
} else {
67
- RCLCPP_ERROR (this ->get_logger (), " lanelet2_map_projector_type is not supported" );
96
+ RCLCPP_ERROR (get_logger (), " lanelet2_map_projector_type is not supported" );
97
+ return nullptr ;
68
98
}
69
99
70
100
for (const auto & error : errors) {
71
- RCLCPP_ERROR_STREAM (this -> get_logger (), error);
101
+ RCLCPP_ERROR_STREAM (get_logger (), error);
72
102
}
73
- if (!errors.empty ()) {
74
- return ;
75
- }
76
-
77
- const auto center_line_resolution = this ->declare_parameter (" center_line_resolution" , 5.0 );
78
- lanelet::utils::overwriteLaneletsCenterline (map, center_line_resolution, false );
103
+ return nullptr ;
104
+ }
79
105
106
+ HADMapBin Lanelet2MapLoaderNode::create_map_bin_msg (
107
+ const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename)
108
+ {
80
109
std::string format_version{}, map_version{};
81
110
lanelet::io_handlers::AutowareOsmParser::parseVersions (
82
111
lanelet2_filename, &format_version, &map_version);
83
112
84
- pub_map_bin_ = this ->create_publisher <autoware_auto_mapping_msgs::msg::HADMapBin>(
85
- " output/lanelet2_map" , rclcpp::QoS{1 }.transient_local ());
86
-
87
- autoware_auto_mapping_msgs::msg::HADMapBin map_bin_msg;
88
- map_bin_msg.header .stamp = this ->now ();
113
+ HADMapBin map_bin_msg;
114
+ map_bin_msg.header .stamp = now ();
89
115
map_bin_msg.header .frame_id = " map" ;
90
116
map_bin_msg.format_version = format_version;
91
117
map_bin_msg.map_version = map_version;
92
118
lanelet::utils::conversion::toBinMsg (map, &map_bin_msg);
93
119
94
- pub_map_bin_-> publish ( map_bin_msg) ;
120
+ return map_bin_msg;
95
121
}
96
122
97
123
#include < rclcpp_components/register_node_macro.hpp>
0 commit comments