#include <incremental_model_registration.h>
◆ Ptr
◆ CapturedSamplePointCloud() [1/2]
      
        
          | jsk_pcl_ros::CapturedSamplePointCloud::CapturedSamplePointCloud | ( |  | ) |  | 
      
 
 
◆ CapturedSamplePointCloud() [2/2]
      
        
          | jsk_pcl_ros::CapturedSamplePointCloud::CapturedSamplePointCloud | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr | cloud, | 
        
          |  |  | const Eigen::Affine3f & | original_pose | 
        
          |  | ) |  |  | 
      
 
 
◆ getOriginalPointCloud()
  
  | 
        
          | pcl::PointCloud< pcl::PointXYZRGB >::Ptr jsk_pcl_ros::CapturedSamplePointCloud::getOriginalPointCloud | ( |  | ) |  |  | virtual | 
 
 
◆ getOriginalPose()
  
  | 
        
          | Eigen::Affine3f jsk_pcl_ros::CapturedSamplePointCloud::getOriginalPose | ( |  | ) |  |  | virtual | 
 
 
◆ getRefinedPointCloud()
  
  | 
        
          | pcl::PointCloud< pcl::PointXYZRGB >::Ptr jsk_pcl_ros::CapturedSamplePointCloud::getRefinedPointCloud | ( |  | ) |  |  | virtual | 
 
 
◆ getRefinedPose()
  
  | 
        
          | Eigen::Affine3f jsk_pcl_ros::CapturedSamplePointCloud::getRefinedPose | ( |  | ) |  |  | virtual | 
 
 
◆ setRefinedPointCloud()
  
  | 
        
          | void jsk_pcl_ros::CapturedSamplePointCloud::setRefinedPointCloud | ( | pcl::PointCloud< pcl::PointXYZRGB > | cloud | ) |  |  | virtual | 
 
 
◆ setRefinedPose()
  
  | 
        
          | void jsk_pcl_ros::CapturedSamplePointCloud::setRefinedPose | ( | Eigen::Affine3f | pose | ) |  |  | virtual | 
 
 
◆ original_cloud_
  
  | 
        
          | pcl::PointCloud<pcl::PointXYZRGB>::Ptr jsk_pcl_ros::CapturedSamplePointCloud::original_cloud_ |  | protected | 
 
 
◆ original_pose_
  
  | 
        
          | Eigen::Affine3f jsk_pcl_ros::CapturedSamplePointCloud::original_pose_ |  | protected | 
 
 
◆ refined_cloud_
  
  | 
        
          | pcl::PointCloud<pcl::PointXYZRGB>::Ptr jsk_pcl_ros::CapturedSamplePointCloud::refined_cloud_ |  | protected | 
 
 
◆ refined_pose_
  
  | 
        
          | Eigen::Affine3f jsk_pcl_ros::CapturedSamplePointCloud::refined_pose_ |  | protected | 
 
 
The documentation for this class was generated from the following files: