forked from autowarefoundation/autoware.universe
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
feat(map_loader): add differential map loading interface (autowarefou…
…ndation#2417) * first commit Signed-off-by: kminoda <koji.minoda@tier4.jp> * ci(pre-commit): autofix * added module load in _node.cpp Signed-off-by: kminoda <koji.minoda@tier4.jp> * ci(pre-commit): autofix * create pcd metadata dict when either of the flag is true Signed-off-by: kminoda <koji.minoda@tier4.jp> * ci(pre-commit): autofix * fix readme * ci(pre-commit): autofix Signed-off-by: kminoda <koji.minoda@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
- Loading branch information
1 parent
9a3613b
commit c48b9cf
Showing
8 changed files
with
169 additions
and
1 deletion.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
85 changes: 85 additions & 0 deletions
85
map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,85 @@ | ||
// Copyright 2022 The Autoware Contributors | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#include "differential_map_loader_module.hpp" | ||
|
||
DifferentialMapLoaderModule::DifferentialMapLoaderModule( | ||
rclcpp::Node * node, const std::map<std::string, PCDFileMetadata> & pcd_file_metadata_dict) | ||
: logger_(node->get_logger()), all_pcd_file_metadata_dict_(pcd_file_metadata_dict) | ||
{ | ||
get_differential_pcd_maps_service_ = node->create_service<GetDifferentialPointCloudMap>( | ||
"service/get_differential_pcd_map", | ||
std::bind( | ||
&DifferentialMapLoaderModule::onServiceGetDifferentialPointCloudMap, this, | ||
std::placeholders::_1, std::placeholders::_2)); | ||
} | ||
|
||
void DifferentialMapLoaderModule::differentialAreaLoad( | ||
const autoware_map_msgs::msg::AreaInfo area, const std::vector<std::string> & cached_ids, | ||
GetDifferentialPointCloudMap::Response::SharedPtr & response) const | ||
{ | ||
// iterate over all the available pcd map grids | ||
std::vector<bool> should_remove(static_cast<int>(cached_ids.size()), true); | ||
for (const auto & ele : all_pcd_file_metadata_dict_) { | ||
std::string path = ele.first; | ||
PCDFileMetadata metadata = ele.second; | ||
|
||
// assume that the map ID = map path (for now) | ||
std::string map_id = path; | ||
|
||
// skip if the pcd file is not within the queried area | ||
if (!isGridWithinQueriedArea(area, metadata)) continue; | ||
|
||
auto id_in_cached_list = std::find(cached_ids.begin(), cached_ids.end(), map_id); | ||
if (id_in_cached_list != cached_ids.end()) { | ||
int index = id_in_cached_list - cached_ids.begin(); | ||
should_remove[index] = false; | ||
} else { | ||
autoware_map_msgs::msg::PointCloudMapCellWithID pointcloud_map_cell_with_id = | ||
loadPointCloudMapCellWithID(path, map_id); | ||
response->new_pointcloud_with_ids.push_back(pointcloud_map_cell_with_id); | ||
} | ||
} | ||
|
||
for (int i = 0; i < static_cast<int>(cached_ids.size()); ++i) { | ||
if (should_remove[i]) { | ||
response->ids_to_remove.push_back(cached_ids[i]); | ||
} | ||
} | ||
} | ||
|
||
bool DifferentialMapLoaderModule::onServiceGetDifferentialPointCloudMap( | ||
GetDifferentialPointCloudMap::Request::SharedPtr req, | ||
GetDifferentialPointCloudMap::Response::SharedPtr res) | ||
{ | ||
auto area = req->area; | ||
std::vector<std::string> cached_ids = req->cached_ids; | ||
differentialAreaLoad(area, cached_ids, res); | ||
res->header.frame_id = "map"; | ||
return true; | ||
} | ||
|
||
autoware_map_msgs::msg::PointCloudMapCellWithID | ||
DifferentialMapLoaderModule::loadPointCloudMapCellWithID( | ||
const std::string path, const std::string map_id) const | ||
{ | ||
sensor_msgs::msg::PointCloud2 pcd; | ||
if (pcl::io::loadPCDFile(path, pcd) == -1) { | ||
RCLCPP_ERROR_STREAM(logger_, "PCD load failed: " << path); | ||
} | ||
autoware_map_msgs::msg::PointCloudMapCellWithID pointcloud_map_cell_with_id; | ||
pointcloud_map_cell_with_id.pointcloud = pcd; | ||
pointcloud_map_cell_with_id.cell_id = map_id; | ||
return pointcloud_map_cell_with_id; | ||
} |
59 changes: 59 additions & 0 deletions
59
map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,59 @@ | ||
// Copyright 2022 The Autoware Contributors | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#ifndef POINTCLOUD_MAP_LOADER__DIFFERENTIAL_MAP_LOADER_MODULE_HPP_ | ||
#define POINTCLOUD_MAP_LOADER__DIFFERENTIAL_MAP_LOADER_MODULE_HPP_ | ||
|
||
#include "utils.hpp" | ||
|
||
#include <rclcpp/rclcpp.hpp> | ||
|
||
#include "autoware_map_msgs/srv/get_differential_point_cloud_map.hpp" | ||
|
||
#include <pcl/common/common.h> | ||
#include <pcl/filters/voxel_grid.h> | ||
#include <pcl/io/pcd_io.h> | ||
#include <pcl/point_cloud.h> | ||
#include <pcl/point_types.h> | ||
#include <pcl_conversions/pcl_conversions.h> | ||
|
||
#include <map> | ||
#include <string> | ||
#include <vector> | ||
|
||
class DifferentialMapLoaderModule | ||
{ | ||
using GetDifferentialPointCloudMap = autoware_map_msgs::srv::GetDifferentialPointCloudMap; | ||
|
||
public: | ||
explicit DifferentialMapLoaderModule( | ||
rclcpp::Node * node, const std::map<std::string, PCDFileMetadata> & pcd_file_metadata_dict); | ||
|
||
private: | ||
rclcpp::Logger logger_; | ||
|
||
std::map<std::string, PCDFileMetadata> all_pcd_file_metadata_dict_; | ||
rclcpp::Service<GetDifferentialPointCloudMap>::SharedPtr get_differential_pcd_maps_service_; | ||
|
||
bool onServiceGetDifferentialPointCloudMap( | ||
GetDifferentialPointCloudMap::Request::SharedPtr req, | ||
GetDifferentialPointCloudMap::Response::SharedPtr res); | ||
void differentialAreaLoad( | ||
const autoware_map_msgs::msg::AreaInfo area_info, const std::vector<std::string> & cached_ids, | ||
GetDifferentialPointCloudMap::Response::SharedPtr & response) const; | ||
autoware_map_msgs::msg::PointCloudMapCellWithID loadPointCloudMapCellWithID( | ||
const std::string path, const std::string map_id) const; | ||
}; | ||
|
||
#endif // POINTCLOUD_MAP_LOADER__DIFFERENTIAL_MAP_LOADER_MODULE_HPP_ |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters