Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Mar 24, 2023
1 parent cd71fe6 commit 6f3b704
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,6 @@ PointCloudMapLoaderNode::PointCloudMapLoaderNode(const rclcpp::NodeOptions & opt
pcd_metadata_dict_ = loadPCDMetadata(pcd_metadata_path);
pcd_metadata_dict_ = replaceWithAbsolutePath(pcd_metadata_dict_, pcd_paths);
RCLCPP_INFO_STREAM(get_logger(), "Loaded PCD metadata: " << pcd_metadata_path);

}

if (enable_partial_load) {
Expand Down
7 changes: 4 additions & 3 deletions map/map_loader/src/pointcloud_map_loader/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,10 +45,11 @@ std::map<std::string, PCDFileMetadata> loadPCDMetadata(const std::string & pcd_m
}

std::map<std::string, PCDFileMetadata> replaceWithAbsolutePath(
const std::map<std::string, PCDFileMetadata> &pcd_metadata_path,
const std::vector<std::string> &pcd_paths) {
const std::map<std::string, PCDFileMetadata> & pcd_metadata_path,
const std::vector<std::string> & pcd_paths)
{
std::map<std::string, PCDFileMetadata> absolute_path_map;
for (const auto &path : pcd_paths) {
for (const auto & path : pcd_paths) {
std::string filename = path.substr(path.find_last_of("/\\") + 1);
auto it = pcd_metadata_path.find(filename);
if (it != pcd_metadata_path.end()) {
Expand Down
4 changes: 2 additions & 2 deletions map/map_loader/src/pointcloud_map_loader/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ struct PCDFileMetadata

std::map<std::string, PCDFileMetadata> loadPCDMetadata(const std::string & pcd_metadata_path);
std::map<std::string, PCDFileMetadata> replaceWithAbsolutePath(
const std::map<std::string, PCDFileMetadata> &pcd_metadata_path,
const std::vector<std::string> &pcd_paths);
const std::map<std::string, PCDFileMetadata> & pcd_metadata_path,
const std::vector<std::string> & pcd_paths);

bool sphereAndBoxOverlapExists(
const geometry_msgs::msg::Point position, const double radius, const pcl::PointXYZ position_min,
Expand Down

0 comments on commit 6f3b704

Please sign in to comment.