#include <cylinder.h>
|  | 
|  | Cylinder (Eigen::Vector3f point, Eigen::Vector3f direction, double radius) | 
|  | 
| virtual void | estimateCenterAndHeight (const pcl::PointCloud< pcl::PointXYZ > &cloud, const pcl::PointIndices &indices, Eigen::Vector3f ¢er, double &height) | 
|  | 
| virtual void | filterPointCloud (const pcl::PointCloud< pcl::PointXYZ > &cloud, const double threshold, pcl::PointIndices &output) | 
|  | 
| virtual Eigen::Vector3f | getDirection () | 
|  | 
| virtual double | getRadius () | 
|  | 
| virtual void | toMarker (visualization_msgs::Marker &marker, const Eigen::Vector3f ¢er, const Eigen::Vector3f &uz, const double height) | 
|  | 
Definition at line 79 of file cylinder.h.
 
◆ Ptr
◆ Cylinder()
      
        
          | jsk_recognition_utils::Cylinder::Cylinder | ( | Eigen::Vector3f | point, | 
        
          |  |  | Eigen::Vector3f | direction, | 
        
          |  |  | double | radius | 
        
          |  | ) |  |  | 
      
 
 
◆ estimateCenterAndHeight()
  
  | 
        
          | void jsk_recognition_utils::Cylinder::estimateCenterAndHeight | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud, |  
          |  |  | const pcl::PointIndices & | indices, |  
          |  |  | Eigen::Vector3f & | center, |  
          |  |  | double & | height |  
          |  | ) |  |  |  | virtual | 
 
 
◆ filterPointCloud()
  
  | 
        
          | void jsk_recognition_utils::Cylinder::filterPointCloud | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud, |  
          |  |  | const double | threshold, |  
          |  |  | pcl::PointIndices & | output |  
          |  | ) |  |  |  | virtual | 
 
 
◆ getDirection()
  
  | 
        
          | Eigen::Vector3f jsk_recognition_utils::Cylinder::getDirection | ( |  | ) |  |  | virtual | 
 
 
◆ getRadius()
  
  | 
        
          | virtual double jsk_recognition_utils::Cylinder::getRadius | ( |  | ) |  |  | inlinevirtual | 
 
 
◆ toMarker()
  
  | 
        
          | void jsk_recognition_utils::Cylinder::toMarker | ( | visualization_msgs::Marker & | marker, |  
          |  |  | const Eigen::Vector3f & | center, |  
          |  |  | const Eigen::Vector3f & | uz, |  
          |  |  | const double | height |  
          |  | ) |  |  |  | virtual | 
 
 
◆ direction_
  
  | 
        
          | Eigen::Vector3f jsk_recognition_utils::Cylinder::direction_ |  | protected | 
 
 
◆ point_
  
  | 
        
          | Eigen::Vector3f jsk_recognition_utils::Cylinder::point_ |  | protected | 
 
 
◆ radius_
  
  | 
        
          | double jsk_recognition_utils::Cylinder::radius_ |  | protected | 
 
 
The documentation for this class was generated from the following files: