diff --git a/include/laser/capture/capture_laser_3d.h b/include/laser/capture/capture_laser_3d.h
index dc3b0457bb660b06214fa7e7238f27b6f56c587e..b7a0b1cef35a8cc5900cc3cdbc241f16136ac9b2 100644
--- a/include/laser/capture/capture_laser_3d.h
+++ b/include/laser/capture/capture_laser_3d.h
@@ -37,12 +37,12 @@ WOLF_PTR_TYPEDEFS(CaptureLaser3d);
 class CaptureLaser3d : public CaptureBase
 {
   public:
-    CaptureLaser3d(const TimeStamp& _timestamp, SensorBasePtr _sensor, pcl::PointCloud<pcl::PointXYZ>::Ptr _point_cloud_raw);//, bool _downsample, double _voxel_size);
+    CaptureLaser3d(const TimeStamp& _timestamp, SensorBasePtr _sensor, pcl::PointCloud<pcl::PointXYZ>::Ptr _point_cloud_raw);
     ~CaptureLaser3d();
-    pcl::PointCloud<pcl::PointXYZ>::Ptr getPointCloud();
-    pcl::PointCloud<pcl::PointXYZ>::ConstPtr getPointCloud() const;
-    pcl::PointCloud<pcl::PointXYZ>::Ptr getPointCloudRaw();
-    pcl::PointCloud<pcl::PointXYZ>::ConstPtr getPointCloudRaw() const;
+    pcl::PointCloud<pcl::PointXYZ>::Ptr getPCLDownsampled();
+    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_;
     
diff --git a/src/capture/capture_laser_3d.cpp b/src/capture/capture_laser_3d.cpp
index 42bcf015e60785fe980a30db8138140493991296..5c9ed0cc205b7d2aed801f364cae150556193a24 100644
--- a/src/capture/capture_laser_3d.cpp
+++ b/src/capture/capture_laser_3d.cpp
@@ -34,22 +34,22 @@ CaptureLaser3d::CaptureLaser3d(const TimeStamp&                    _timestamp,
 
 CaptureLaser3d::~CaptureLaser3d() {}
 
-pcl::PointCloud<pcl::PointXYZ>::Ptr CaptureLaser3d::getPointCloud()
+pcl::PointCloud<pcl::PointXYZ>::Ptr CaptureLaser3d::getPCLDownsampled()
 {
     return point_cloud_;
 }
 
-pcl::PointCloud<pcl::PointXYZ>::ConstPtr CaptureLaser3d::getPointCloud() const
+pcl::PointCloud<pcl::PointXYZ>::ConstPtr CaptureLaser3d::getPCLDownsampled() const
 {
     return point_cloud_;
 }
 
-pcl::PointCloud<pcl::PointXYZ>::Ptr CaptureLaser3d::getPointCloudRaw()
+pcl::PointCloud<pcl::PointXYZ>::Ptr CaptureLaser3d::getPCLRaw()
 {
     return point_cloud_raw_;
 }
 
-pcl::PointCloud<pcl::PointXYZ>::ConstPtr CaptureLaser3d::getPointCloudRaw() const
+pcl::PointCloud<pcl::PointXYZ>::ConstPtr CaptureLaser3d::getPCLRaw() const
 {
     return point_cloud_raw_;
 }
diff --git a/src/processor/processor_odom_icp_3d.cpp b/src/processor/processor_odom_icp_3d.cpp
index 6f6c4e7a025e8315f821e18d8952164c2aba8580..e3d606c9f039b38c54daeca9d0a6806c8a44f5f6 100644
--- a/src/processor/processor_odom_icp_3d.cpp
+++ b/src/processor/processor_odom_icp_3d.cpp
@@ -94,12 +94,12 @@ void ProcessorOdomIcp3d::preProcess()
         double pcl_voxel_size = params_odom_icp_->pcl_downsample_voxel_size;
         pcl::VoxelGrid<pcl::PointXYZ> grid; 
         grid.setLeafSize(pcl_voxel_size, pcl_voxel_size, pcl_voxel_size);
-        grid.setInputCloud(incoming_laser_->getPointCloudRaw());
+        grid.setInputCloud(incoming_laser_->getPCLRaw());
         grid.filter(* incoming_laser_->point_cloud_);    // public member of class, better with setter
     }
     else
     {
-        incoming_laser_->point_cloud_ = incoming_laser_->getPointCloudRaw();
+        incoming_laser_->point_cloud_ = incoming_laser_->getPCLRaw();
     }
 }
 
@@ -131,8 +131,8 @@ unsigned int ProcessorOdomIcp3d::processKnown()
     if (origin_ptr_ && (incoming_ptr_ != origin_ptr_))
     {
         origin_laser_ = std::static_pointer_cast<CaptureLaser3d>(origin_ptr_);
-        pairAlign(origin_laser_->getPointCloud(),
-                  incoming_laser_->getPointCloud(),
+        pairAlign(origin_laser_->getPCLDownsampled(),
+                  incoming_laser_->getPCLDownsampled(),
                   T_origin_last_,
                   T_origin_incoming_,
                   registration_solver_);
@@ -148,8 +148,8 @@ unsigned int ProcessorOdomIcp3d::processNew(const int& _max_features)
     if (last_ptr_)
     {
         last_laser_ = std::static_pointer_cast<CaptureLaser3d>(last_ptr_);
-        pairAlign(last_laser_->getPointCloud(),
-                  incoming_laser_->getPointCloud(),
+        pairAlign(last_laser_->getPCLDownsampled(),
+                  incoming_laser_->getPCLDownsampled(),
                   Eigen::Isometry3d::Identity(),
                   T_last_incoming_,
                   registration_solver_);