EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense.  
 More...
#include <extract_clusters.h>
|  | 
| void | config_callback (EuclideanClusterExtractionConfig &config, uint32_t level) | 
|  | Dynamic reconfigure callback.  More... 
 | 
|  | 
| void | input_indices_callback (const PointCloudConstPtr &cloud, const PointIndicesConstPtr &indices) | 
|  | Input point cloud callback.  More... 
 | 
|  | 
| void | onInit () | 
|  | Nodelet initialization routine.  More... 
 | 
|  | 
| void | subscribe () | 
|  | LazyNodelet connection routine.  More... 
 | 
|  | 
| void | unsubscribe () | 
|  | 
| bool | isValid (const ModelCoefficientsConstPtr &, const std::string &="model") | 
|  | Test whether a given ModelCoefficients message is "valid" (i.e., has values).  More... 
 | 
|  | 
| bool | isValid (const PointCloud2::ConstPtr &cloud, const std::string &topic_name="input") | 
|  | Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero).  More... 
 | 
|  | 
| bool | isValid (const PointCloudConstPtr &cloud, const std::string &topic_name="input") | 
|  | Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero).  More... 
 | 
|  | 
| bool | isValid (const PointIndicesConstPtr &, const std::string &="indices") | 
|  | Test whether a given PointIndices message is "valid" (i.e., has values).  More... 
 | 
|  | 
| ros::Publisher | advertise (ros::NodeHandle &nh, std::string topic, int queue_size, bool latch=false) | 
|  | 
| virtual void | connectionCallback (const ros::SingleSubscriberPublisher &pub) | 
|  | 
| virtual void | onInitPostProcess () | 
|  | 
| virtual void | warnNeverSubscribedCallback (const ros::WallTimerEvent &event) | 
|  | 
| ros::CallbackQueueInterface & | getMTCallbackQueue () const | 
|  | 
| ros::NodeHandle & | getMTNodeHandle () const | 
|  | 
| ros::NodeHandle & | getMTPrivateNodeHandle () const | 
|  | 
| const V_string & | getMyArgv () const | 
|  | 
| const std::string & | getName () const | 
|  | 
| ros::NodeHandle & | getNodeHandle () const | 
|  | 
| ros::NodeHandle & | getPrivateNodeHandle () const | 
|  | 
| const M_string & | getRemappingArgs () const | 
|  | 
| ros::CallbackQueueInterface & | getSTCallbackQueue () const | 
|  | 
| std::string | getSuffixedName (const std::string &suffix) const | 
|  | 
EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense. 
- Author
- Radu Bogdan Rusu 
Definition at line 57 of file extract_clusters.h.
◆ EuclideanClusterExtraction()
  
  | 
        
          | pcl_ros::EuclideanClusterExtraction::EuclideanClusterExtraction | ( |  | ) |  |  | inline | 
 
 
◆ config_callback()
  
  | 
        
          | void pcl_ros::EuclideanClusterExtraction::config_callback | ( | EuclideanClusterExtractionConfig & | config, |  
          |  |  | uint32_t | level |  
          |  | ) |  |  |  | protected | 
 
Dynamic reconfigure callback. 
- Parameters
- 
  
    | config | the config object |  | level | the dynamic reconfigure level |  
 
Definition at line 140 of file extract_clusters.cpp.
 
 
◆ input_indices_callback()
Input point cloud callback. 
- Parameters
- 
  
    | cloud | the pointer to the input point cloud |  | indices | the pointer to the input point cloud indices |  
 
DEBUG
Definition at line 166 of file extract_clusters.cpp.
 
 
◆ onInit()
  
  | 
        
          | void pcl_ros::EuclideanClusterExtraction::onInit | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ subscribe()
  
  | 
        
          | void pcl_ros::EuclideanClusterExtraction::subscribe | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ unsubscribe()
  
  | 
        
          | void pcl_ros::EuclideanClusterExtraction::unsubscribe | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ impl_
◆ max_clusters_
  
  | 
        
          | int pcl_ros::EuclideanClusterExtraction::max_clusters_ |  | protected | 
 
 
◆ publish_indices_
  
  | 
        
          | bool pcl_ros::EuclideanClusterExtraction::publish_indices_ |  | protected | 
 
Publish indices or convert to PointCloud clusters. Default: false. 
Definition at line 61 of file extract_clusters.h.
 
 
◆ srv_
  
  | 
        
          | boost::shared_ptr<dynamic_reconfigure::Server<EuclideanClusterExtractionConfig> > pcl_ros::EuclideanClusterExtraction::srv_ |  | protected | 
 
 
◆ sub_input_
◆ sync_input_indices_a_
◆ sync_input_indices_e_
The documentation for this class was generated from the following files: