36 #ifndef __JSK_PCL_COLORIZE_SEGMENTED_RF__ 37 #define __JSK_PCL_COLORIZE_SEGMENTED_RF__ 42 #include <jsk_recognition_msgs/PointsArray.h> 45 #include <pcl/point_types.h> 46 #include <pcl/ModelCoefficients.h> 47 #include <pcl/point_types.h> 48 #include <pcl/sample_consensus/method_types.h> 49 #include <pcl/sample_consensus/model_types.h> 50 #include <pcl/filters/passthrough.h> 51 #include <pcl/segmentation/sac_segmentation.h> 52 #include <pcl/common/centroid.h> 53 #include <pcl/common/impl/common.hpp> 54 #include <pcl/filters/extract_indices.h> 55 #include <pcl/features/normal_3d.h> 56 #include <pcl/kdtree/kdtree.h> 57 #include <pcl/segmentation/extract_clusters.h> 58 #include <pcl/features/fpfh_omp.h> 59 #include <ml_classifiers/ClassifyData.h> 60 #include <ml_classifiers/ClassDataPoint.h> 86 void extract(
const sensor_msgs::PointCloud2 cloud);
ros::Subscriber sub_input_
double max_depth_change_factor_
double mps_distance_threshold_
double angular_threshold_
void extract(const sensor_msgs::PointCloud2 cloud)
double refinement_threshold_
double normal_smoothingsize_