From 9c3718b8af6a7061223452383be653029cf71228 Mon Sep 17 00:00:00 2001 From: vsainz <vsainz@iri.upc.edu> Date: Wed, 10 Aug 2022 18:09:43 +0200 Subject: [PATCH] created setPCLDownsampled(pcl_ptr) --- include/laser/capture/capture_laser_3d.h | 4 ++-- src/capture/capture_laser_3d.cpp | 7 ++++++- src/processor/processor_odom_icp_3d.cpp | 7 +++++-- 3 files changed, 13 insertions(+), 5 deletions(-) diff --git a/include/laser/capture/capture_laser_3d.h b/include/laser/capture/capture_laser_3d.h index b7a0b1cef..e6fae887f 100644 --- a/include/laser/capture/capture_laser_3d.h +++ b/include/laser/capture/capture_laser_3d.h @@ -43,11 +43,11 @@ class CaptureLaser3d : public CaptureBase pcl::PointCloud<pcl::PointXYZ>::ConstPtr getPCLDownsampled() const; pcl::PointCloud<pcl::PointXYZ>::Ptr getPCLRaw(); pcl::PointCloud<pcl::PointXYZ>::ConstPtr getPCLRaw() const; - - pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud_; + void setPCLDownsampled(pcl::PointCloud<pcl::PointXYZ>::Ptr _pcl_ptr); private: pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud_raw_; + pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud_; }; } // namespace wolf diff --git a/src/capture/capture_laser_3d.cpp b/src/capture/capture_laser_3d.cpp index 5c9ed0cc2..234713ba6 100644 --- a/src/capture/capture_laser_3d.cpp +++ b/src/capture/capture_laser_3d.cpp @@ -29,11 +29,16 @@ CaptureLaser3d::CaptureLaser3d(const TimeStamp& _timestamp, pcl::PointCloud<pcl::PointXYZ>::Ptr _point_cloud_raw) : CaptureBase("CaptureLaser3d", _timestamp, _sensor), point_cloud_raw_(_point_cloud_raw) { - + point_cloud_ = nullptr; } CaptureLaser3d::~CaptureLaser3d() {} +void CaptureLaser3d::setPCLDownsampled(pcl::PointCloud<pcl::PointXYZ>::Ptr _pcl_ptr) +{ + point_cloud_ = _pcl_ptr; +} + pcl::PointCloud<pcl::PointXYZ>::Ptr CaptureLaser3d::getPCLDownsampled() { return point_cloud_; diff --git a/src/processor/processor_odom_icp_3d.cpp b/src/processor/processor_odom_icp_3d.cpp index e3d606c9f..bae57adfa 100644 --- a/src/processor/processor_odom_icp_3d.cpp +++ b/src/processor/processor_odom_icp_3d.cpp @@ -95,11 +95,14 @@ void ProcessorOdomIcp3d::preProcess() pcl::VoxelGrid<pcl::PointXYZ> grid; grid.setLeafSize(pcl_voxel_size, pcl_voxel_size, pcl_voxel_size); grid.setInputCloud(incoming_laser_->getPCLRaw()); - grid.filter(* incoming_laser_->point_cloud_); // public member of class, better with setter + + pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_ptr = pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>(); + grid.filter(*pcl_ptr); + incoming_laser_->setPCLDownsampled(pcl_ptr); } else { - incoming_laser_->point_cloud_ = incoming_laser_->getPCLRaw(); + incoming_laser_->setPCLDownsampled(incoming_laser_->getPCLRaw()); } } -- GitLab