Skip to content

Commit 61a1e0b

Browse files
committed
Tested
Signed-off-by: anhnv3991 <anh.nguyen.2@tier4.jp>
1 parent 52dbe75 commit 61a1e0b

File tree

1 file changed

+8
-11
lines changed

1 file changed

+8
-11
lines changed

localization/ndt_scan_matcher/src/map_update_module.cpp

+8-11
Original file line numberDiff line numberDiff line change
@@ -152,20 +152,17 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt
152152
}
153153

154154
const auto exe_start_time = std::chrono::system_clock::now();
155-
const size_t add_size = maps_to_add.size();
156155
// Perform heavy processing outside of the lock scope
157-
std::vector<pcl::shared_ptr<pcl::PointCloud<PointTarget>>> points_pcl(add_size);
158-
159-
for (size_t i = 0; i < add_size; i++) {
160-
points_pcl[i] = pcl::make_shared<pcl::PointCloud<PointTarget>>();
161-
pcl::fromROSMsg(maps_to_add[i].pointcloud, *points_pcl[i]);
162-
}
163-
156+
164157
// Add pcd
165-
for (size_t i = 0; i < add_size; i++) {
166-
ndt.addTarget(points_pcl[i], maps_to_add[i].cell_id);
158+
for (auto& map : maps_to_add)
159+
{
160+
auto cloud = pcl::make_shared<pcl::PointCloud<PointTarget>>();
161+
162+
pcl::fromROSMsg(map.pointcloud, *cloud);
163+
ndt.addTarget(cloud, map.cell_id);
167164
}
168-
165+
169166
// Remove pcd
170167
for (const std::string & map_id_to_remove : map_ids_to_remove) {
171168
ndt.removeTarget(map_id_to_remove);

0 commit comments

Comments
 (0)