#include <organized_edge_detector.h>
|  | 
| typedef jsk_pcl_ros::OrganizedEdgeDetectorConfig | Config | 
|  | 
| typedef pcl::PointXYZRGB | PointT | 
|  | 
|  | 
| virtual void | configCallback (Config &config, uint32_t level) | 
|  | 
| virtual void | estimate (const sensor_msgs::PointCloud2::ConstPtr &msg) | 
|  | 
| virtual void | estimateEdge (const pcl::PointCloud< PointT >::Ptr &input, const pcl::PointCloud< pcl::Normal >::Ptr &normal, pcl::PointCloud< pcl::Label >::Ptr &output, std::vector< pcl::PointIndices > &label_indices) | 
|  | 
| virtual void | estimateNormal (const pcl::PointCloud< PointT >::Ptr &input, pcl::PointCloud< pcl::Normal >::Ptr output, const std_msgs::Header &header) | 
|  | 
| virtual void | estimateStraightEdges (const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, const std_msgs::Header &header, std::vector< std::vector< int > > &output_indices) | 
|  | 
| virtual void | onInit () | 
|  | 
| virtual void | publishIndices (ros::Publisher &pub, ros::Publisher &pub_indices, const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, const std_msgs::Header &header) | 
|  | 
| virtual void | publishStraightEdges (const pcl::PointCloud< PointT >::Ptr &cloud, const std_msgs::Header &header, const std::vector< std::vector< int > > indices) | 
|  | 
| virtual void | subscribe () | 
|  | 
| virtual void | unsubscribe () | 
|  | 
Definition at line 81 of file organized_edge_detector.h.
 
◆ Config
◆ PointT
◆ configCallback()
  
  | 
        
          | void jsk_pcl_ros::OrganizedEdgeDetector::configCallback | ( | Config & | config, |  
          |  |  | uint32_t | level |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ estimate()
  
  | 
        
          | void jsk_pcl_ros::OrganizedEdgeDetector::estimate | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) |  |  | protectedvirtual | 
 
 
◆ estimateEdge()
◆ estimateNormal()
◆ estimateStraightEdges()
◆ onInit()
  
  | 
        
          | void jsk_pcl_ros::OrganizedEdgeDetector::onInit | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ publishIndices()
◆ publishStraightEdges()
◆ subscribe()
  
  | 
        
          | void jsk_pcl_ros::OrganizedEdgeDetector::subscribe | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ unsubscribe()
  
  | 
        
          | void jsk_pcl_ros::OrganizedEdgeDetector::unsubscribe | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ border_policy_ignore_
  
  | 
        
          | bool jsk_pcl_ros::OrganizedEdgeDetector::border_policy_ignore_ |  | protected | 
 
 
◆ depth_dependent_smoothing_
  
  | 
        
          | bool jsk_pcl_ros::OrganizedEdgeDetector::depth_dependent_smoothing_ |  | protected | 
 
 
◆ depth_discontinuation_threshold_
  
  | 
        
          | double jsk_pcl_ros::OrganizedEdgeDetector::depth_discontinuation_threshold_ |  | protected | 
 
 
◆ estimation_method_
  
  | 
        
          | int jsk_pcl_ros::OrganizedEdgeDetector::estimation_method_ |  | protected | 
 
 
◆ max_depth_change_factor_
  
  | 
        
          | double jsk_pcl_ros::OrganizedEdgeDetector::max_depth_change_factor_ |  | protected | 
 
 
◆ max_line_gap_
  
  | 
        
          | double jsk_pcl_ros::OrganizedEdgeDetector::max_line_gap_ |  | protected | 
 
 
◆ max_search_neighbors_
  
  | 
        
          | int jsk_pcl_ros::OrganizedEdgeDetector::max_search_neighbors_ |  | protected | 
 
 
◆ min_line_length_
  
  | 
        
          | double jsk_pcl_ros::OrganizedEdgeDetector::min_line_length_ |  | protected | 
 
 
◆ mutex_
◆ normal_smoothing_size_
  
  | 
        
          | double jsk_pcl_ros::OrganizedEdgeDetector::normal_smoothing_size_ |  | protected | 
 
 
◆ pub_all_edges_
◆ pub_all_edges_indices_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::OrganizedEdgeDetector::pub_all_edges_indices_ |  | protected | 
 
 
◆ pub_curvature_edges_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::OrganizedEdgeDetector::pub_curvature_edges_ |  | protected | 
 
 
◆ pub_curvature_edges_indices_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::OrganizedEdgeDetector::pub_curvature_edges_indices_ |  | protected | 
 
 
◆ pub_edge_image_
◆ pub_hough_image_
◆ pub_nan_boundary_edges_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::OrganizedEdgeDetector::pub_nan_boundary_edges_ |  | protected | 
 
 
◆ pub_nan_boundary_edges_indices_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::OrganizedEdgeDetector::pub_nan_boundary_edges_indices_ |  | protected | 
 
 
◆ pub_normal_
◆ pub_occluded_edges_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::OrganizedEdgeDetector::pub_occluded_edges_ |  | protected | 
 
 
◆ pub_occluded_edges_indices_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::OrganizedEdgeDetector::pub_occluded_edges_indices_ |  | protected | 
 
 
◆ pub_occluding_edges_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::OrganizedEdgeDetector::pub_occluding_edges_ |  | protected | 
 
 
◆ pub_occluding_edges_indices_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::OrganizedEdgeDetector::pub_occluding_edges_indices_ |  | protected | 
 
 
◆ pub_rgb_edges_
◆ pub_rgb_edges_indices_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::OrganizedEdgeDetector::pub_rgb_edges_indices_ |  | protected | 
 
 
◆ pub_straight_edges_indices_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::OrganizedEdgeDetector::pub_straight_edges_indices_ |  | protected | 
 
 
◆ publish_debug_image_
  
  | 
        
          | bool jsk_pcl_ros::OrganizedEdgeDetector::publish_debug_image_ |  | protected | 
 
 
◆ publish_normal_
  
  | 
        
          | bool jsk_pcl_ros::OrganizedEdgeDetector::publish_normal_ |  | protected | 
 
 
◆ rho_
  
  | 
        
          | double jsk_pcl_ros::OrganizedEdgeDetector::rho_ |  | protected | 
 
 
◆ srv_
◆ straightline_threshold_
  
  | 
        
          | int jsk_pcl_ros::OrganizedEdgeDetector::straightline_threshold_ |  | protected | 
 
 
◆ sub_
◆ theta_
  
  | 
        
          | double jsk_pcl_ros::OrganizedEdgeDetector::theta_ |  | protected | 
 
 
◆ use_curvature_
  
  | 
        
          | bool jsk_pcl_ros::OrganizedEdgeDetector::use_curvature_ |  | protected | 
 
 
◆ use_nan_boundary_
  
  | 
        
          | bool jsk_pcl_ros::OrganizedEdgeDetector::use_nan_boundary_ |  | protected | 
 
 
◆ use_occluded_
  
  | 
        
          | bool jsk_pcl_ros::OrganizedEdgeDetector::use_occluded_ |  | protected | 
 
 
◆ use_occluding_
  
  | 
        
          | bool jsk_pcl_ros::OrganizedEdgeDetector::use_occluding_ |  | protected | 
 
 
◆ use_rgb_
  
  | 
        
          | bool jsk_pcl_ros::OrganizedEdgeDetector::use_rgb_ |  | protected | 
 
 
◆ use_straightline_detection_
  
  | 
        
          | bool jsk_pcl_ros::OrganizedEdgeDetector::use_straightline_detection_ |  | protected | 
 
 
The documentation for this class was generated from the following files: