Skip to content

Commit 85354b2

Browse files
committed
fix: modify function names to snake_case
Signed-off-by: Ryohsuke Mitsudome <ryohsuke.mitsudome@tier4.jp>
1 parent 3544363 commit 85354b2

File tree

5 files changed

+23
-23
lines changed

5 files changed

+23
-23
lines changed

map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_utils.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -36,10 +36,10 @@ struct Lanelet2FileMetaData
3636

3737
namespace utils
3838
{
39-
std::map<std::string, Lanelet2FileMetaData> loadLanelet2Metadata(
39+
std::map<std::string, Lanelet2FileMetaData> load_lanelet2_metadata(
4040
const std::string & lanelet2_metadata_path, double & x_resolution, double & y_resolution);
4141

42-
std::map<std::string, Lanelet2FileMetaData> replaceWithAbsolutePath(
42+
std::map<std::string, Lanelet2FileMetaData> replace_with_absolute_path(
4343
const std::map<std::string, Lanelet2FileMetaData> & lanelet2_metadata_path,
4444
const std::vector<std::string> & lanelet2_paths);
4545

map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -40,11 +40,11 @@ Lanelet2DifferentialLoaderModule::Lanelet2DifferentialLoaderModule(
4040
get_differential_lanelet2_maps_service_ = node->create_service<GetDifferentialLanelet2Map>(
4141
"service/get_differential_lanelet_map",
4242
std::bind(
43-
&Lanelet2DifferentialLoaderModule::onServiceGetDifferentialLanelet2Map, this,
43+
&Lanelet2DifferentialLoaderModule::on_service_get_differential_lanelet2_map, this,
4444
std::placeholders::_1, std::placeholders::_2));
4545
}
4646

47-
bool Lanelet2DifferentialLoaderModule::onServiceGetDifferentialLanelet2Map(
47+
bool Lanelet2DifferentialLoaderModule::on_service_get_differential_lanelet2_map(
4848
GetDifferentialLanelet2Map::Request::SharedPtr req,
4949
GetDifferentialLanelet2Map::Response::SharedPtr res)
5050
{
@@ -107,24 +107,24 @@ bool Lanelet2DifferentialLoaderModule::onServiceGetDifferentialLanelet2Map(
107107
return true;
108108
}
109109

110-
void Lanelet2DifferentialLoaderModule::setLaneletMapMetadata(
110+
void Lanelet2DifferentialLoaderModule::set_lanelet2_map_metadata(
111111
const std::map<std::string, Lanelet2FileMetaData> & lanelet2_metadata_dict, const double x_res,
112112
const double y_res)
113113
{
114114
lanelet2_file_metadata_dict_ = lanelet2_metadata_dict;
115115

116-
const auto msg = getLaneletMapMetaDataMsg(x_res, y_res);
116+
const auto msg = get_lanelet_map_metadata_msg(x_res, y_res);
117117
pub_lanelet_map_meta_data_->publish(msg);
118118
}
119119

120-
void Lanelet2DifferentialLoaderModule::setProjectionInfo(
120+
void Lanelet2DifferentialLoaderModule::set_projection_info(
121121
const autoware_map_msgs::msg::MapProjectorInfo & projector_info)
122122
{
123123
projector_info_ = projector_info;
124124
}
125125

126126
autoware_map_msgs::msg::LaneletMapMetaData
127-
Lanelet2DifferentialLoaderModule::getLaneletMapMetaDataMsg(
127+
Lanelet2DifferentialLoaderModule::get_lanelet_map_metadata_msg(
128128
const double & x_res, const double & y_res) const
129129
{
130130
autoware_map_msgs::msg::LaneletMapMetaData metadata;

map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -52,11 +52,11 @@ class Lanelet2DifferentialLoaderModule
5252
explicit Lanelet2DifferentialLoaderModule(
5353
rclcpp::Node * node, const double & center_line_resolution, const bool & use_waypoints);
5454

55-
void setLaneletMapMetadata(
55+
void set_lanelet2_map_metadata(
5656
const std::map<std::string, Lanelet2FileMetaData> & lanelet2_metadata_dict, const double x_res,
5757
const double y_res);
5858

59-
void setProjectionInfo(const autoware_map_msgs::msg::MapProjectorInfo & projector_info);
59+
void set_projection_info(const autoware_map_msgs::msg::MapProjectorInfo & projector_info);
6060

6161
private:
6262
rclcpp::Logger logger_;
@@ -74,11 +74,11 @@ class Lanelet2DifferentialLoaderModule
7474

7575
double center_line_resolution_;
7676
bool use_waypoints_;
77-
bool onServiceGetDifferentialLanelet2Map(
77+
bool on_service_get_differential_lanelet2_map(
7878
GetDifferentialLanelet2Map::Request::SharedPtr req,
7979
GetDifferentialLanelet2Map::Response::SharedPtr res);
8080

81-
autoware_map_msgs::msg::LaneletMapMetaData getLaneletMapMetaDataMsg(
81+
autoware_map_msgs::msg::LaneletMapMetaData get_lanelet_map_metadata_msg(
8282
const double & x_res, const double & y_res) const;
8383
};
8484

map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp

+9-9
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ void Lanelet2MapLoaderNode::on_map_projector_info(
130130
}
131131

132132
// load lanelet2 map
133-
// We have to keep all loaded maps until publishing the map bin msg
133+
// Note that we cannot destroy loaded maps even after merging them
134134
// because the loaded lanelets will be expired when map is destructed
135135
std::vector<lanelet::LaneletMapPtr> maps;
136136
for (const auto & path : lanelet2_paths) {
@@ -143,9 +143,9 @@ void Lanelet2MapLoaderNode::on_map_projector_info(
143143
}
144144

145145
// merge all maps
146-
lanelet::LaneletMapPtr map = std::make_shared<lanelet::LaneletMap>();
147-
for (const auto & map_i : maps) {
148-
utils::merge_lanelet2_maps(*map, *map_i);
146+
lanelet::LaneletMapPtr map = maps.front();
147+
for (size_t i = 1; i < maps.size(); ++i) {
148+
utils::merge_lanelet2_maps(*map, *maps.at(i));
149149
}
150150

151151
// setup differential map loader module
@@ -169,12 +169,11 @@ void Lanelet2MapLoaderNode::on_map_projector_info(
169169
}
170170

171171
// set metadata and projection info to differential loader module
172-
differential_loader_module_->setLaneletMapMetadata(
172+
differential_loader_module_->set_lanelet2_map_metadata(
173173
lanelet2_metadata_dict, x_resolution, y_resolution);
174-
differential_loader_module_->setProjectionInfo(*msg);
174+
differential_loader_module_->set_projection_info(*msg);
175175
}
176176

177-
178177
// we use first lanelet2 path to get format_version and map_version
179178
std::string format_version{"null"}, map_version{""};
180179
lanelet::io_handlers::AutowareOsmParser::parseVersions(
@@ -262,8 +261,9 @@ std::map<std::string, Lanelet2FileMetaData> Lanelet2MapLoaderNode::get_lanelet2_
262261
{
263262
std::map<std::string, Lanelet2FileMetaData> lanelet2_metadata_dict;
264263
lanelet2_metadata_dict =
265-
utils::loadLanelet2Metadata(lanelet2_metadata_path, x_resolution, y_resolution);
266-
lanelet2_metadata_dict = utils::replaceWithAbsolutePath(lanelet2_metadata_dict, lanelet2_paths);
264+
utils::load_lanelet2_metadata(lanelet2_metadata_path, x_resolution, y_resolution);
265+
lanelet2_metadata_dict =
266+
utils::replace_with_absolute_path(lanelet2_metadata_dict, lanelet2_paths);
267267
RCLCPP_INFO_STREAM(get_logger(), "Loaded Lanelet2 metadata: " << lanelet2_metadata_path);
268268

269269
return lanelet2_metadata_dict;

map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_utils.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@
3838
namespace autoware::map_loader::utils
3939
{
4040

41-
std::map<std::string, Lanelet2FileMetaData> loadLanelet2Metadata(
41+
std::map<std::string, Lanelet2FileMetaData> load_lanelet2_metadata(
4242
const std::string & lanelet2_metadata_path, double & x_resolution, double & y_resolution)
4343
{
4444
YAML::Node config = YAML::LoadFile(lanelet2_metadata_path);
@@ -70,7 +70,7 @@ std::map<std::string, Lanelet2FileMetaData> loadLanelet2Metadata(
7070
return lanelet2_metadata;
7171
}
7272

73-
std::map<std::string, Lanelet2FileMetaData> replaceWithAbsolutePath(
73+
std::map<std::string, Lanelet2FileMetaData> replace_with_absolute_path(
7474
const std::map<std::string, Lanelet2FileMetaData> & lanelet2_metadata_path,
7575
const std::vector<std::string> & lanelet2_paths)
7676
{

0 commit comments

Comments
 (0)