Skip to content

Commit a5c001f

Browse files
committed
Revert "refactor(autoware_map_msgs): modify pcd metadata msg (#7852)"
This reverts commit 8ea7de7. Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>
1 parent e46c927 commit a5c001f

File tree

17 files changed

+93
-97
lines changed

17 files changed

+93
-97
lines changed

localization/ndt_scan_matcher/src/map_update_module.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -265,7 +265,7 @@ bool MapUpdateModule::update_ndt(
265265
}
266266
diagnostics_ptr->add_key_value("is_succeed_call_pcd_loader", true);
267267

268-
auto & maps_to_add = result.get()->new_pointcloud_cells;
268+
auto & maps_to_add = result.get()->new_pointcloud_with_ids;
269269
auto & map_ids_to_remove = result.get()->ids_to_remove;
270270

271271
diagnostics_ptr->add_key_value("maps_to_add_size", maps_to_add.size());
@@ -283,7 +283,7 @@ bool MapUpdateModule::update_ndt(
283283
auto cloud = pcl::make_shared<pcl::PointCloud<PointTarget>>();
284284

285285
pcl::fromROSMsg(map.pointcloud, *cloud);
286-
ndt.addTarget(cloud, map.metadata.cell_id);
286+
ndt.addTarget(cloud, map.cell_id);
287287
}
288288

289289
// Remove pcd

localization/ndt_scan_matcher/test/stub_pcd_loader.hpp

+12-12
Original file line numberDiff line numberDiff line change
@@ -60,26 +60,26 @@ class StubPcdLoader : public rclcpp::Node
6060
return true;
6161
}
6262

63-
autoware_map_msgs::msg::PointCloudMapCellWithMetaData pcd_map_cell;
64-
pcd_map_cell.metadata.cell_id = "0";
63+
autoware_map_msgs::msg::PointCloudMapCellWithID pcd_map_cell_with_id;
64+
pcd_map_cell_with_id.cell_id = "0";
6565
pcl::PointCloud<pcl::PointXYZ> cloud = make_sample_half_cubic_pcd();
6666
for (auto & point : cloud.points) {
6767
point.x += offset_x;
6868
point.y += offset_y;
6969
}
70-
pcd_map_cell.metadata.min_x = std::numeric_limits<float>::max();
71-
pcd_map_cell.metadata.min_y = std::numeric_limits<float>::max();
72-
pcd_map_cell.metadata.max_x = std::numeric_limits<float>::lowest();
73-
pcd_map_cell.metadata.max_y = std::numeric_limits<float>::lowest();
70+
pcd_map_cell_with_id.metadata.min_x = std::numeric_limits<float>::max();
71+
pcd_map_cell_with_id.metadata.min_y = std::numeric_limits<float>::max();
72+
pcd_map_cell_with_id.metadata.max_x = std::numeric_limits<float>::lowest();
73+
pcd_map_cell_with_id.metadata.max_y = std::numeric_limits<float>::lowest();
7474
for (const auto & point : cloud.points) {
75-
pcd_map_cell.metadata.min_x = std::min(pcd_map_cell.metadata.min_x, point.x);
76-
pcd_map_cell.metadata.min_y = std::min(pcd_map_cell.metadata.min_y, point.y);
77-
pcd_map_cell.metadata.max_x = std::max(pcd_map_cell.metadata.max_x, point.x);
78-
pcd_map_cell.metadata.max_y = std::max(pcd_map_cell.metadata.max_y, point.y);
75+
pcd_map_cell_with_id.metadata.min_x = std::min(pcd_map_cell_with_id.metadata.min_x, point.x);
76+
pcd_map_cell_with_id.metadata.min_y = std::min(pcd_map_cell_with_id.metadata.min_y, point.y);
77+
pcd_map_cell_with_id.metadata.max_x = std::max(pcd_map_cell_with_id.metadata.max_x, point.x);
78+
pcd_map_cell_with_id.metadata.max_y = std::max(pcd_map_cell_with_id.metadata.max_y, point.y);
7979
}
8080
RCLCPP_INFO_STREAM(get_logger(), "cloud size: " << cloud.size());
81-
pcl::toROSMsg(cloud, pcd_map_cell.pointcloud);
82-
res->new_pointcloud_cells.push_back(pcd_map_cell);
81+
pcl::toROSMsg(cloud, pcd_map_cell_with_id.pointcloud);
82+
res->new_pointcloud_with_ids.push_back(pcd_map_cell_with_id);
8383
res->header.frame_id = "map";
8484
return true;
8585
}

map/map_height_fitter/src/map_height_fitter.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -145,17 +145,17 @@ bool MapHeightFitter::Impl::get_partial_point_cloud_map(const Point & point)
145145
const auto res = future.get();
146146
RCLCPP_DEBUG(
147147
logger, "Loaded partial pcd map from map_loader (grid size: %lu)",
148-
res->new_pointcloud_cells.size());
148+
res->new_pointcloud_with_ids.size());
149149

150150
sensor_msgs::msg::PointCloud2 pcd_msg;
151-
for (const auto & pcd_cell : res->new_pointcloud_cells) {
151+
for (const auto & pcd_with_id : res->new_pointcloud_with_ids) {
152152
if (pcd_msg.width == 0) {
153-
pcd_msg = pcd_cell.pointcloud;
153+
pcd_msg = pcd_with_id.pointcloud;
154154
} else {
155-
pcd_msg.width += pcd_cell.pointcloud.width;
156-
pcd_msg.row_step += pcd_cell.pointcloud.row_step;
155+
pcd_msg.width += pcd_with_id.pointcloud.width;
156+
pcd_msg.row_step += pcd_with_id.pointcloud.row_step;
157157
pcd_msg.data.insert(
158-
pcd_msg.data.end(), pcd_cell.pointcloud.data.begin(), pcd_cell.pointcloud.data.end());
158+
pcd_msg.data.end(), pcd_with_id.pointcloud.data.begin(), pcd_with_id.pointcloud.data.end());
159159
}
160160
}
161161
map_frame_ = res->header.frame_id;

map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp

+13-13
Original file line numberDiff line numberDiff line change
@@ -48,13 +48,13 @@ void DifferentialMapLoaderModule::differential_area_load(
4848
int index = static_cast<int>(id_in_cached_list - cached_ids.begin());
4949
should_remove[index] = false;
5050
} else {
51-
autoware_map_msgs::msg::PointCloudMapCellWithMetaData pointcloud_map_cell =
52-
load_point_cloud_map_cell_with_metadata(path, map_id);
53-
pointcloud_map_cell.metadata.min_x = metadata.min.x;
54-
pointcloud_map_cell.metadata.min_y = metadata.min.y;
55-
pointcloud_map_cell.metadata.max_x = metadata.max.x;
56-
pointcloud_map_cell.metadata.max_y = metadata.max.y;
57-
response->new_pointcloud_cells.push_back(pointcloud_map_cell);
51+
autoware_map_msgs::msg::PointCloudMapCellWithID pointcloud_map_cell_with_id =
52+
load_point_cloud_map_cell_with_id(path, map_id);
53+
pointcloud_map_cell_with_id.metadata.min_x = metadata.min.x;
54+
pointcloud_map_cell_with_id.metadata.min_y = metadata.min.y;
55+
pointcloud_map_cell_with_id.metadata.max_x = metadata.max.x;
56+
pointcloud_map_cell_with_id.metadata.max_y = metadata.max.y;
57+
response->new_pointcloud_with_ids.push_back(pointcloud_map_cell_with_id);
5858
}
5959
}
6060

@@ -76,16 +76,16 @@ bool DifferentialMapLoaderModule::on_service_get_differential_point_cloud_map(
7676
return true;
7777
}
7878

79-
autoware_map_msgs::msg::PointCloudMapCellWithMetaData
80-
DifferentialMapLoaderModule::load_point_cloud_map_cell_with_metadata(
79+
autoware_map_msgs::msg::PointCloudMapCellWithID
80+
DifferentialMapLoaderModule::load_point_cloud_map_cell_with_id(
8181
const std::string & path, const std::string & map_id) const
8282
{
8383
sensor_msgs::msg::PointCloud2 pcd;
8484
if (pcl::io::loadPCDFile(path, pcd) == -1) {
8585
RCLCPP_ERROR_STREAM(logger_, "PCD load failed: " << path);
8686
}
87-
autoware_map_msgs::msg::PointCloudMapCellWithMetaData pointcloud_map_cell;
88-
pointcloud_map_cell.pointcloud = pcd;
89-
pointcloud_map_cell.metadata.cell_id = map_id;
90-
return pointcloud_map_cell;
87+
autoware_map_msgs::msg::PointCloudMapCellWithID pointcloud_map_cell_with_id;
88+
pointcloud_map_cell_with_id.pointcloud = pcd;
89+
pointcloud_map_cell_with_id.cell_id = map_id;
90+
return pointcloud_map_cell_with_id;
9191
}

map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -52,8 +52,7 @@ class DifferentialMapLoaderModule
5252
void differential_area_load(
5353
const autoware_map_msgs::msg::AreaInfo & area_info, const std::vector<std::string> & cached_ids,
5454
const GetDifferentialPointCloudMap::Response::SharedPtr & response) const;
55-
[[nodiscard]] autoware_map_msgs::msg::PointCloudMapCellWithMetaData
56-
load_point_cloud_map_cell_with_metadata(
55+
[[nodiscard]] autoware_map_msgs::msg::PointCloudMapCellWithID load_point_cloud_map_cell_with_id(
5756
const std::string & path, const std::string & map_id) const;
5857
};
5958

map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp

+13-13
Original file line numberDiff line numberDiff line change
@@ -42,14 +42,14 @@ void PartialMapLoaderModule::partial_area_load(
4242
// skip if the pcd file is not within the queried area
4343
if (!is_grid_within_queried_area(area, metadata)) continue;
4444

45-
autoware_map_msgs::msg::PointCloudMapCellWithMetaData pointcloud_map_cell =
46-
load_point_cloud_map_cell_with_metadata(path, map_id);
47-
pointcloud_map_cell.metadata.min_x = metadata.min.x;
48-
pointcloud_map_cell.metadata.min_y = metadata.min.y;
49-
pointcloud_map_cell.metadata.max_x = metadata.max.x;
50-
pointcloud_map_cell.metadata.max_y = metadata.max.y;
45+
autoware_map_msgs::msg::PointCloudMapCellWithID pointcloud_map_cell_with_id =
46+
load_point_cloud_map_cell_with_id(path, map_id);
47+
pointcloud_map_cell_with_id.metadata.min_x = metadata.min.x;
48+
pointcloud_map_cell_with_id.metadata.min_y = metadata.min.y;
49+
pointcloud_map_cell_with_id.metadata.max_x = metadata.max.x;
50+
pointcloud_map_cell_with_id.metadata.max_y = metadata.max.y;
5151

52-
response->new_pointcloud_cells.push_back(pointcloud_map_cell);
52+
response->new_pointcloud_with_ids.push_back(pointcloud_map_cell_with_id);
5353
}
5454
}
5555

@@ -63,16 +63,16 @@ bool PartialMapLoaderModule::on_service_get_partial_point_cloud_map(
6363
return true;
6464
}
6565

66-
autoware_map_msgs::msg::PointCloudMapCellWithMetaData
67-
PartialMapLoaderModule::load_point_cloud_map_cell_with_metadata(
66+
autoware_map_msgs::msg::PointCloudMapCellWithID
67+
PartialMapLoaderModule::load_point_cloud_map_cell_with_id(
6868
const std::string & path, const std::string & map_id) const
6969
{
7070
sensor_msgs::msg::PointCloud2 pcd;
7171
if (pcl::io::loadPCDFile(path, pcd) == -1) {
7272
RCLCPP_ERROR_STREAM(logger_, "PCD load failed: " << path);
7373
}
74-
autoware_map_msgs::msg::PointCloudMapCellWithMetaData pointcloud_map_cell;
75-
pointcloud_map_cell.pointcloud = pcd;
76-
pointcloud_map_cell.metadata.cell_id = map_id;
77-
return pointcloud_map_cell;
74+
autoware_map_msgs::msg::PointCloudMapCellWithID pointcloud_map_cell_with_id;
75+
pointcloud_map_cell_with_id.pointcloud = pcd;
76+
pointcloud_map_cell_with_id.cell_id = map_id;
77+
return pointcloud_map_cell_with_id;
7878
}

map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -52,8 +52,7 @@ class PartialMapLoaderModule
5252
void partial_area_load(
5353
const autoware_map_msgs::msg::AreaInfo & area,
5454
const GetPartialPointCloudMap::Response::SharedPtr & response) const;
55-
[[nodiscard]] autoware_map_msgs::msg::PointCloudMapCellWithMetaData
56-
load_point_cloud_map_cell_with_metadata(
55+
[[nodiscard]] autoware_map_msgs::msg::PointCloudMapCellWithID load_point_cloud_map_cell_with_id(
5756
const std::string & path, const std::string & map_id) const;
5857
};
5958

map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp

+20-20
Original file line numberDiff line numberDiff line change
@@ -30,14 +30,14 @@ autoware_map_msgs::msg::PointCloudMapMetaData create_metadata(
3030
// assume that the map ID = map path (for now)
3131
const std::string & map_id = ele.first;
3232

33-
autoware_map_msgs::msg::PointCloudMapCellMetaData cell_metadata;
34-
cell_metadata.cell_id = map_id;
35-
cell_metadata.min_x = metadata.min.x;
36-
cell_metadata.min_y = metadata.min.y;
37-
cell_metadata.max_x = metadata.max.x;
38-
cell_metadata.max_y = metadata.max.y;
33+
autoware_map_msgs::msg::PointCloudMapCellMetaDataWithID cell_metadata_with_id;
34+
cell_metadata_with_id.cell_id = map_id;
35+
cell_metadata_with_id.metadata.min_x = metadata.min.x;
36+
cell_metadata_with_id.metadata.min_y = metadata.min.y;
37+
cell_metadata_with_id.metadata.max_x = metadata.max.x;
38+
cell_metadata_with_id.metadata.max_y = metadata.max.y;
3939

40-
metadata_msg.metadata_list.push_back(cell_metadata);
40+
metadata_msg.metadata_list.push_back(cell_metadata_with_id);
4141
}
4242

4343
return metadata_msg;
@@ -81,29 +81,29 @@ bool SelectedMapLoaderModule::on_service_get_selected_point_cloud_map(
8181
const std::string & map_id = path;
8282
PCDFileMetadata metadata = requested_selected_map_iterator->second;
8383

84-
autoware_map_msgs::msg::PointCloudMapCellWithMetaData pointcloud_map_cell =
85-
load_point_cloud_map_cell_with_metadata(path, map_id);
86-
pointcloud_map_cell.metadata.min_x = metadata.min.x;
87-
pointcloud_map_cell.metadata.min_y = metadata.min.y;
88-
pointcloud_map_cell.metadata.max_x = metadata.max.x;
89-
pointcloud_map_cell.metadata.max_y = metadata.max.y;
84+
autoware_map_msgs::msg::PointCloudMapCellWithID pointcloud_map_cell_with_id =
85+
load_point_cloud_map_cell_with_id(path, map_id);
86+
pointcloud_map_cell_with_id.metadata.min_x = metadata.min.x;
87+
pointcloud_map_cell_with_id.metadata.min_y = metadata.min.y;
88+
pointcloud_map_cell_with_id.metadata.max_x = metadata.max.x;
89+
pointcloud_map_cell_with_id.metadata.max_y = metadata.max.y;
9090

91-
res->new_pointcloud_cells.push_back(pointcloud_map_cell);
91+
res->new_pointcloud_with_ids.push_back(pointcloud_map_cell_with_id);
9292
}
9393
res->header.frame_id = "map";
9494
return true;
9595
}
9696

97-
autoware_map_msgs::msg::PointCloudMapCellWithMetaData
98-
SelectedMapLoaderModule::load_point_cloud_map_cell_with_metadata(
97+
autoware_map_msgs::msg::PointCloudMapCellWithID
98+
SelectedMapLoaderModule::load_point_cloud_map_cell_with_id(
9999
const std::string & path, const std::string & map_id) const
100100
{
101101
sensor_msgs::msg::PointCloud2 pcd;
102102
if (pcl::io::loadPCDFile(path, pcd) == -1) {
103103
RCLCPP_ERROR_STREAM(logger_, "PCD load failed: " << path);
104104
}
105-
autoware_map_msgs::msg::PointCloudMapCellWithMetaData pointcloud_map_cell;
106-
pointcloud_map_cell.pointcloud = pcd;
107-
pointcloud_map_cell.metadata.cell_id = map_id;
108-
return pointcloud_map_cell;
105+
autoware_map_msgs::msg::PointCloudMapCellWithID pointcloud_map_cell_with_id;
106+
pointcloud_map_cell_with_id.pointcloud = pcd;
107+
pointcloud_map_cell_with_id.cell_id = map_id;
108+
return pointcloud_map_cell_with_id;
109109
}

map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -52,8 +52,7 @@ class SelectedMapLoaderModule
5252
[[nodiscard]] bool on_service_get_selected_point_cloud_map(
5353
GetSelectedPointCloudMap::Request::SharedPtr req,
5454
GetSelectedPointCloudMap::Response::SharedPtr res) const;
55-
[[nodiscard]] autoware_map_msgs::msg::PointCloudMapCellWithMetaData
56-
load_point_cloud_map_cell_with_metadata(
55+
[[nodiscard]] autoware_map_msgs::msg::PointCloudMapCellWithID load_point_cloud_map_cell_with_id(
5756
const std::string & path, const std::string & map_id) const;
5857
};
5958

map/map_loader/test/test_differential_map_loader_module.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -85,8 +85,8 @@ TEST_F(TestDifferentialMapLoaderModule, LoadDifferentialPCDFiles)
8585

8686
// Check the result
8787
auto result = result_future.get();
88-
ASSERT_EQ(static_cast<int>(result->new_pointcloud_cells.size()), 1);
89-
EXPECT_EQ(result->new_pointcloud_cells[0].metadata.cell_id, "/tmp/dummy.pcd");
88+
ASSERT_EQ(static_cast<int>(result->new_pointcloud_with_ids.size()), 1);
89+
EXPECT_EQ(result->new_pointcloud_with_ids[0].cell_id, "/tmp/dummy.pcd");
9090
EXPECT_EQ(static_cast<int>(result->ids_to_remove.size()), 0);
9191
}
9292

map/map_loader/test/test_partial_map_loader_module.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -82,8 +82,8 @@ TEST_F(TestPartialMapLoaderModule, LoadPartialPCDFiles)
8282

8383
// Check the result
8484
auto result = result_future.get();
85-
ASSERT_EQ(static_cast<int>(result->new_pointcloud_cells.size()), 1);
86-
EXPECT_EQ(result->new_pointcloud_cells[0].metadata.cell_id, "/tmp/dummy.pcd");
85+
ASSERT_EQ(static_cast<int>(result->new_pointcloud_with_ids.size()), 1);
86+
EXPECT_EQ(result->new_pointcloud_with_ids[0].cell_id, "/tmp/dummy.pcd");
8787
}
8888

8989
int main(int argc, char ** argv)

perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,7 @@ class DistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader
6464
bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold) override;
6565

6666
inline void addMapCellAndFilter(
67-
const autoware_map_msgs::msg::PointCloudMapCellWithMetaData & map_cell_to_add) override
67+
const autoware_map_msgs::msg::PointCloudMapCellWithID & map_cell_to_add) override
6868
{
6969
map_grid_size_x_ = map_cell_to_add.metadata.max_x - map_cell_to_add.metadata.min_x;
7070
map_grid_size_y_ = map_cell_to_add.metadata.max_y - map_cell_to_add.metadata.min_y;
@@ -95,8 +95,7 @@ class DistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader
9595

9696
// add
9797
(*mutex_ptr_).lock();
98-
current_voxel_grid_dict_.insert(
99-
{map_cell_to_add.metadata.cell_id, current_voxel_grid_list_item});
98+
current_voxel_grid_dict_.insert({map_cell_to_add.cell_id, current_voxel_grid_list_item});
10099
(*mutex_ptr_).unlock();
101100
}
102101
};

perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ class VoxelDistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader
7171
bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold) override;
7272

7373
inline void addMapCellAndFilter(
74-
const autoware_map_msgs::msg::PointCloudMapCellWithMetaData & map_cell_to_add) override
74+
const autoware_map_msgs::msg::PointCloudMapCellWithID & map_cell_to_add) override
7575
{
7676
map_grid_size_x_ = map_cell_to_add.metadata.max_x - map_cell_to_add.metadata.min_x;
7777
map_grid_size_y_ = map_cell_to_add.metadata.max_y - map_cell_to_add.metadata.min_y;
@@ -118,8 +118,7 @@ class VoxelDistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader
118118

119119
// add
120120
(*mutex_ptr_).lock();
121-
current_voxel_grid_dict_.insert(
122-
{map_cell_to_add.metadata.cell_id, current_voxel_grid_list_item});
121+
current_voxel_grid_dict_.insert({map_cell_to_add.cell_id, current_voxel_grid_list_item});
123122
(*mutex_ptr_).unlock();
124123
}
125124
};

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -453,10 +453,12 @@ void VoxelGridDynamicMapLoader::request_update_map(const geometry_msgs::msg::Poi
453453
}
454454
//
455455
if (status == std::future_status::ready) {
456-
if (result.get()->new_pointcloud_cells.size() == 0 && result.get()->ids_to_remove.size() == 0) {
456+
if (
457+
result.get()->new_pointcloud_with_ids.size() == 0 &&
458+
result.get()->ids_to_remove.size() == 0) {
457459
return;
458460
}
459-
updateDifferentialMapCells(result.get()->new_pointcloud_cells, result.get()->ids_to_remove);
461+
updateDifferentialMapCells(result.get()->new_pointcloud_with_ids, result.get()->ids_to_remove);
460462
if (debug_) {
461463
publish_downsampled_map(getCurrentDownsampledMapPc());
462464
}

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -223,7 +223,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
223223
return current_map_ids;
224224
}
225225
inline void updateDifferentialMapCells(
226-
const std::vector<autoware_map_msgs::msg::PointCloudMapCellWithMetaData> & map_cells_to_add,
226+
const std::vector<autoware_map_msgs::msg::PointCloudMapCellWithID> & map_cells_to_add,
227227
std::vector<std::string> map_cell_ids_to_remove)
228228
{
229229
for (const auto & map_cell_to_add : map_cells_to_add) {
@@ -279,7 +279,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
279279
}
280280

281281
virtual inline void addMapCellAndFilter(
282-
const autoware_map_msgs::msg::PointCloudMapCellWithMetaData & map_cell_to_add)
282+
const autoware_map_msgs::msg::PointCloudMapCellWithID & map_cell_to_add)
283283
{
284284
map_grid_size_x_ = map_cell_to_add.metadata.max_x - map_cell_to_add.metadata.min_x;
285285
map_grid_size_y_ = map_cell_to_add.metadata.max_y - map_cell_to_add.metadata.min_y;
@@ -316,8 +316,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
316316
current_voxel_grid_list_item.map_cell_pc_ptr = std::move(map_cell_downsampled_pc_ptr_tmp);
317317
// add
318318
(*mutex_ptr_).lock();
319-
current_voxel_grid_dict_.insert(
320-
{map_cell_to_add.metadata.cell_id, current_voxel_grid_list_item});
319+
current_voxel_grid_dict_.insert({map_cell_to_add.cell_id, current_voxel_grid_list_item});
321320
(*mutex_ptr_).unlock();
322321
}
323322
};

perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,7 @@ class ElevationMapLoaderNode : public rclcpp::Node
8282
void receiveMap();
8383
void concatenatePointCloudMaps(
8484
sensor_msgs::msg::PointCloud2 & pointcloud_map,
85-
const std::vector<autoware_map_msgs::msg::PointCloudMapCellWithMetaData> & new_pointcloud_cells)
85+
const std::vector<autoware_map_msgs::msg::PointCloudMapCellWithID> & new_pointcloud_with_ids)
8686
const;
8787
std::vector<std::string> getRequestIDs(const unsigned int map_id_counter) const;
8888
void publish();

0 commit comments

Comments
 (0)