From c3317b63547472675d09e7c0d27597d8b7665749 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Wed, 18 Oct 2023 11:15:46 +0900 Subject: [PATCH] chore: refactor Signed-off-by: badai-nguyen --- .../obstacle_pointcloud_based_validator/debugger.hpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp b/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp index 7b6cf91997682..6597475ae297e 100644 --- a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp +++ b/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp @@ -71,15 +71,16 @@ class Debugger void addNeighborPointcloud(const pcl::PointCloud::Ptr & input) { pcl::PointCloud::Ptr input_xyz = toXYZ(input); - for (const auto & point : *input_xyz) { - neighbor_pointcloud_->push_back(point); - } + addNeighborPointcloud(input_xyz); } void addNeighborPointcloud(const pcl::PointCloud::Ptr & input) { - for (const auto & point : *input) { - neighbor_pointcloud_->push_back(point); + if (!input->empty()) { + neighbor_pointcloud_->reserve(neighbor_pointcloud_->size() + input->size()); + for (const auto & point : *input) { + neighbor_pointcloud_->push_back(point); + } } } void addPointcloudWithinPolygon(const pcl::PointCloud::Ptr & input)