Skip to content

Commit 611731b

Browse files
style(pre-commit): autofix
1 parent 5604e9f commit 611731b

6 files changed

+32
-30
lines changed

map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.cpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,6 @@
1616

1717
#include "lanelet2_local_projector.hpp"
1818
#include "lanelet2_map_loader_node.hpp"
19-
2019
#include "utils.hpp"
2120

2221
namespace autoware::map_loader
@@ -66,15 +65,15 @@ bool Lanelet2DifferentialLoaderModule::onServiceGetDifferentialLanelet2Map(
6665
for (const auto & path : lanelet2_paths) {
6766
auto map_tmp = utils::load_map(path, projector_info_.value());
6867
if (!map_tmp) {
69-
RCLCPP_ERROR(rclcpp::get_logger("map_loader"), "Failed to load lanelet2_map %s", path.c_str());
68+
RCLCPP_ERROR(
69+
rclcpp::get_logger("map_loader"), "Failed to load lanelet2_map %s", path.c_str());
7070
return false;
7171
}
7272
utils::merge_lanelet2_maps(*map, *map_tmp);
7373
}
7474

7575
// create the map bin message
76-
const auto map_bin_msg =
77-
utils::create_map_bin_msg(map, lanelet2_paths[0], rclcpp::Clock().now());
76+
const auto map_bin_msg = utils::create_map_bin_msg(map, lanelet2_paths[0], rclcpp::Clock().now());
7877

7978
res->lanelet2_cells = map_bin_msg;
8079
res->header.frame_id = "map";

map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.hpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef MAP_LOADER__LANELET2_DIFFERENTIAL_LOADER_MODULE_HPP_
16-
#define MAP_LOADER__LANELET2_DIFFERENTIAL_LOADER_MODULE_HPP_
15+
#ifndef LANELET2_MAP_LOADER__LANELET2_DIFFERENTIAL_LOADER_MODULE_HPP_
16+
#define LANELET2_MAP_LOADER__LANELET2_DIFFERENTIAL_LOADER_MODULE_HPP_
1717

1818
#include "utils.hpp"
1919

@@ -26,10 +26,10 @@
2626
#include <pugixml.hpp>
2727
#include <rclcpp/rclcpp.hpp>
2828

29-
#include <autoware_map_msgs/srv/get_selected_lanelet2_map.hpp>
3029
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
3130
#include <autoware_map_msgs/msg/lanelet_map_meta_data.hpp>
3231
#include <autoware_map_msgs/msg/map_projector_info.hpp>
32+
#include <autoware_map_msgs/srv/get_selected_lanelet2_map.hpp>
3333

3434
#include <lanelet2_core/LaneletMap.h>
3535
#include <lanelet2_core/geometry/LineString.h>
@@ -41,7 +41,6 @@
4141
#include <string>
4242
#include <vector>
4343

44-
4544
namespace autoware::map_loader
4645
{
4746

@@ -68,7 +67,8 @@ class Lanelet2DifferentialLoaderModule
6867

6968
rclcpp::Service<GetDifferentialLanelet2Map>::SharedPtr get_differential_lanelet2_maps_service_;
7069

71-
autoware::component_interface_utils::Publisher<autoware::component_interface_specs_universe::map::LaneletMapMetaData>::SharedPtr
70+
autoware::component_interface_utils::Publisher<
71+
autoware::component_interface_specs_universe::map::LaneletMapMetaData>::SharedPtr
7272
pub_lanelet_map_meta_data_;
7373

7474
std::optional<autoware_map_msgs::msg::MapProjectorInfo> projector_info_;
@@ -84,4 +84,4 @@ class Lanelet2DifferentialLoaderModule
8484
};
8585

8686
} // namespace autoware::map_loader
87-
#endif // MAP_LOADER__LANELET2_DIFFERENTIAL_LOADER_MODULE_HPP_
87+
#endif // LANELET2_MAP_LOADER__LANELET2_DIFFERENTIAL_LOADER_MODULE_HPP_

map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp

+10-6
Original file line numberDiff line numberDiff line change
@@ -120,7 +120,8 @@ void Lanelet2MapLoaderNode::on_map_projector_info(
120120
// get lanelet2 paths
121121
const std::vector<std::string> lanelet2_paths = get_lanelet2_paths(lanelet2_paths_or_directory);
122122
if (lanelet2_paths.empty()) {
123-
RCLCPP_ERROR(get_logger(), "No lanelet2 map files found from %s", lanelet2_paths_or_directory[0].c_str());
123+
RCLCPP_ERROR(
124+
get_logger(), "No lanelet2 map files found from %s", lanelet2_paths_or_directory[0].c_str());
124125
return;
125126
}
126127

@@ -129,12 +130,13 @@ void Lanelet2MapLoaderNode::on_map_projector_info(
129130
RCLCPP_INFO(get_logger(), "Differential lanelet2 map loading is enabled.");
130131

131132
// generate metadata
132-
const auto lanelet2_metadata_path = declare_parameter<std::string>("lanelet2_map_metadata_path");
133+
const auto lanelet2_metadata_path =
134+
declare_parameter<std::string>("lanelet2_map_metadata_path");
133135
double x_resolution, y_resolution;
134136
std::map<std::string, Lanelet2FileMetaData> lanelet2_metadata_dict;
135137
if (std::filesystem::exists(lanelet2_metadata_path)) {
136-
lanelet2_metadata_dict = get_lanelet2_metadata(
137-
lanelet2_metadata_path, lanelet2_paths, x_resolution, y_resolution);
138+
lanelet2_metadata_dict =
139+
get_lanelet2_metadata(lanelet2_metadata_path, lanelet2_paths, x_resolution, y_resolution);
138140
} else {
139141
throw std::runtime_error("Lanelet2 metadata file not found: " + lanelet2_metadata_path);
140142
}
@@ -205,7 +207,8 @@ void Lanelet2MapLoaderNode::on_map_projector_info(
205207

206208
/**
207209
* @brief Get list of lanelet2 map file paths from input paths/directories
208-
* @param lanelet2_paths_or_directory Vector of paths that can be either lanelet2 map files or directories containing them
210+
* @param lanelet2_paths_or_directory Vector of paths that can be either lanelet2 map files or
211+
* directories containing them
209212
* @return Vector of absolute paths to lanelet2 map files
210213
*/
211214
std::vector<std::string> Lanelet2MapLoaderNode::get_lanelet2_paths(
@@ -241,7 +244,8 @@ std::map<std::string, Lanelet2FileMetaData> Lanelet2MapLoaderNode::get_lanelet2_
241244
double & x_resolution, double & y_resolution) const
242245
{
243246
std::map<std::string, Lanelet2FileMetaData> lanelet2_metadata_dict;
244-
lanelet2_metadata_dict = utils::loadLanelet2Metadata(lanelet2_metadata_path, x_resolution, y_resolution);
247+
lanelet2_metadata_dict =
248+
utils::loadLanelet2Metadata(lanelet2_metadata_path, x_resolution, y_resolution);
245249
lanelet2_metadata_dict = utils::replaceWithAbsolutePath(lanelet2_metadata_dict, lanelet2_paths);
246250
RCLCPP_INFO_STREAM(get_logger(), "Loaded Lanelet2 metadata: " << lanelet2_metadata_path);
247251

map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.hpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_
16-
#define AUTOWARE__MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_
15+
#ifndef LANELET2_MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_
16+
#define LANELET2_MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_
1717

1818
#include "lanelet2_differential_loader_module.hpp"
1919
#include "utils.hpp"
@@ -59,8 +59,7 @@ class Lanelet2MapLoaderNode : public rclcpp::Node
5959
std::map<std::string, Lanelet2FileMetaData> get_lanelet2_metadata(
6060
const std::string & lanelet2_metadata_path, const std::vector<std::string> & lanelet2_paths,
6161
double & x_resolution, double & y_resolution) const;
62-
6362
};
6463
} // namespace autoware::map_loader
6564

66-
#endif // AUTOWARE__MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_
65+
#endif // LANELET2_MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_

map/autoware_map_loader/src/lanelet2_map_loader/utils.cpp

+2-4
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,6 @@
1414

1515
#include "utils.hpp"
1616

17-
#include <yaml-cpp/yaml.h>
18-
1917
#include "lanelet2_local_projector.hpp"
2018

2119
#include <autoware/geography_utils/lanelet2_projector.hpp>
@@ -24,13 +22,13 @@
2422
#include <autoware_lanelet2_extension/projection/transverse_mercator_projector.hpp>
2523
#include <autoware_lanelet2_extension/utility/message_conversion.hpp>
2624
#include <autoware_lanelet2_extension/utility/utilities.hpp>
25+
#include <rclcpp/rclcpp.hpp>
2726

2827
#include <lanelet2_core/LaneletMap.h>
2928
#include <lanelet2_core/geometry/LineString.h>
3029
#include <lanelet2_io/Io.h>
3130
#include <lanelet2_projection/UTM.h>
32-
33-
#include <rclcpp/rclcpp.hpp>
31+
#include <yaml-cpp/yaml.h>
3432

3533
namespace autoware::map_loader::utils
3634
{

map/autoware_map_loader/src/lanelet2_map_loader/utils.hpp

+8-6
Original file line numberDiff line numberDiff line change
@@ -12,16 +12,16 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef MAP_LOADER__UTILS_HPP_
16-
#define MAP_LOADER__UTILS_HPP_
15+
#ifndef LANELET2_MAP_LOADER__UTILS_HPP_
16+
#define LANELET2_MAP_LOADER__UTILS_HPP_
17+
18+
#include <rclcpp/time.hpp>
1719

1820
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
1921
#include <autoware_map_msgs/msg/map_projector_info.hpp>
2022

2123
#include <lanelet2_core/LaneletMap.h>
2224

23-
#include <rclcpp/time.hpp>
24-
2525
#include <map>
2626
#include <string>
2727
#include <vector>
@@ -45,7 +45,9 @@ std::map<std::string, Lanelet2FileMetaData> replaceWithAbsolutePath(
4545

4646
void merge_lanelet2_maps(lanelet::LaneletMap & merge_target, lanelet::LaneletMap & merge_source);
4747

48-
lanelet::LaneletMapPtr load_map( const std::string & lanelet2_filename, const autoware_map_msgs::msg::MapProjectorInfo & projector_info);
48+
lanelet::LaneletMapPtr load_map(
49+
const std::string & lanelet2_filename,
50+
const autoware_map_msgs::msg::MapProjectorInfo & projector_info);
4951

5052
autoware_map_msgs::msg::LaneletMapBin create_map_bin_msg(
5153
const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename,
@@ -55,4 +57,4 @@ autoware_map_msgs::msg::LaneletMapBin create_map_bin_msg(
5557

5658
} // namespace autoware::map_loader
5759

58-
#endif // MAP_LOADER__UTILS_HPP_
60+
#endif // LANELET2_MAP_LOADER__UTILS_HPP_

0 commit comments

Comments
 (0)