Skip to content

Commit db00897

Browse files
takayuki5168h-ohta
authored andcommitted
feat(map_loader): make some functions static (autowarefoundation#2014)
* feat(map_loader): make some functions static Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * make publisher alive after constructor Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 80e4a46 commit db00897

File tree

2 files changed

+17
-14
lines changed

2 files changed

+17
-14
lines changed

map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp

+7-5
Original file line numberDiff line numberDiff line change
@@ -31,13 +31,15 @@ class Lanelet2MapLoaderNode : public rclcpp::Node
3131
public:
3232
explicit Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options);
3333

34+
static lanelet::LaneletMapPtr load_map(
35+
rclcpp::Node & node, const std::string & lanelet2_filename,
36+
const std::string & lanelet2_map_projector_type);
37+
static HADMapBin create_map_bin_msg(
38+
const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename,
39+
const rclcpp::Time & now);
40+
3441
private:
3542
rclcpp::Publisher<HADMapBin>::SharedPtr pub_map_bin_;
36-
37-
lanelet::LaneletMapPtr load_map(
38-
const std::string & lanelet2_filename, const std::string & lanelet2_map_projector_type);
39-
HADMapBin create_map_bin_msg(
40-
const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename);
4143
};
4244

4345
#endif // MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_

map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp

+10-9
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
5454
const auto center_line_resolution = declare_parameter("center_line_resolution", 5.0);
5555

5656
// 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);
5858
if (!map) {
5959
return;
6060
}
@@ -63,7 +63,7 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
6363
lanelet::utils::overwriteLaneletsCenterline(map, center_line_resolution, false);
6464

6565
// 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());
6767

6868
// create publisher and publish
6969
pub_map_bin_ =
@@ -72,7 +72,8 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
7272
}
7373

7474
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)
7677
{
7778
lanelet::ErrorMessages errors{};
7879
if (lanelet2_map_projector_type == "MGRS") {
@@ -82,8 +83,8 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map(
8283
return map;
8384
}
8485
} 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);
8788
lanelet::GPSPoint position{map_origin_lat, map_origin_lon};
8889
lanelet::Origin origin{position};
8990
lanelet::projection::UtmProjector projector{origin};
@@ -93,25 +94,25 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map(
9394
return map;
9495
}
9596
} 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");
9798
return nullptr;
9899
}
99100

100101
for (const auto & error : errors) {
101-
RCLCPP_ERROR_STREAM(get_logger(), error);
102+
RCLCPP_ERROR_STREAM(rclcpp::get_logger("map_loader"), error);
102103
}
103104
return nullptr;
104105
}
105106

106107
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)
108109
{
109110
std::string format_version{}, map_version{};
110111
lanelet::io_handlers::AutowareOsmParser::parseVersions(
111112
lanelet2_filename, &format_version, &map_version);
112113

113114
HADMapBin map_bin_msg;
114-
map_bin_msg.header.stamp = now();
115+
map_bin_msg.header.stamp = now;
115116
map_bin_msg.header.frame_id = "map";
116117
map_bin_msg.format_version = format_version;
117118
map_bin_msg.map_version = map_version;

0 commit comments

Comments
 (0)