36 #ifndef JSK_PCL_ROS_EUCLIDEAN_CLUSTER_EXTRACTION_NODELET_H_ 37 #define JSK_PCL_ROS_EUCLIDEAN_CLUSTER_EXTRACTION_NODELET_H_ 42 #include <std_msgs/ColorRGBA.h> 44 #include <dynamic_reconfigure/server.h> 48 #include <pcl/point_types.h> 49 #include <pcl/impl/point_types.hpp> 50 #include <pcl/kdtree/kdtree_flann.h> 51 #include <pcl/segmentation/sac_segmentation.h> 52 #include <pcl/segmentation/extract_clusters.h> 53 #include <pcl/filters/extract_indices.h> 54 #include <pcl/filters/voxel_grid.h> 55 #include <pcl/common/centroid.h> 57 #include "jsk_recognition_msgs/ClusterPointIndices.h" 58 #include "jsk_recognition_msgs/EuclideanSegment.h" 59 #include "jsk_recognition_msgs/Int32Stamped.h" 61 #include "jsk_pcl_ros/EuclideanClusteringConfig.h" 62 #include <Eigen/StdVector> 75 jsk_recognition_msgs::ClusterPointIndices,
79 jsk_recognition_msgs::ClusterPointIndices,
82 typedef jsk_pcl_ros::EuclideanClusteringConfig
Config;
83 typedef std::vector<Eigen::Vector4f,
84 Eigen::aligned_allocator<Eigen::Vector4f> >
126 virtual void extract(
const sensor_msgs::PointCloud2ConstPtr &input);
127 virtual void multi_extract(
const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_indices,
128 const sensor_msgs::PointCloud2::ConstPtr& input);
130 std::vector<pcl::PointIndices::Ptr> &cluster_indices,
131 std::vector<pcl::PointIndices> &clustered_indices);
133 jsk_recognition_msgs::EuclideanSegment::Response &
res);
136 std::vector<int>& pivot_table,
137 std::vector<pcl::PointIndices>& cluster_indices);
143 double label_tracking_tolerance);
152 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
153 std::vector<pcl::PointIndices> cluster_indices);
157 const pcl::PointCloud<pcl::PointXYZ>::Ptr& original_cloud,
158 pcl::PointCloud<pcl::PointXYZ>::Ptr& sampled_cloud,
159 std::vector<std::vector<int> >& sampled_to_original_indices,
160 std::vector<int>& original_to_sampled_indices,
ros::Publisher result_pub_
ros::Subscriber sub_input_
void downsample_cloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &original_cloud, pcl::PointCloud< pcl::PointXYZ >::Ptr &sampled_cloud, std::vector< std::vector< int > > &sampled_to_original_indices, std::vector< int > &original_to_sampled_indices, double leaf_size)
virtual void computeCentroidsOfClusters(Vector4fVector &ret, pcl::PointCloud< pcl::PointXYZ >::Ptr cloud, std::vector< pcl::PointIndices > cluster_indices)
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
virtual void unsubscribe()
jsk_topic_tools::TimeAccumulator segmentation_acc_
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
std::vector< std::vector< int > > downsample_to_original_indices_
virtual void computeDistanceMatrix(double *D, Vector4fVector &old_cogs, Vector4fVector &new_cogs)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_cluster_indices_
virtual std::vector< pcl::PointIndices > pivotClusterIndices(std::vector< int > &pivot_table, std::vector< pcl::PointIndices > &cluster_indices)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void configCallback(Config &config, uint32_t level)
jsk_recognition_utils::Counter cluster_counter_
jsk_topic_tools::TimeAccumulator kdtree_acc_
virtual std::vector< int > buildLabelTrackingPivotTable(double *D, Vector4fVector cogs, Vector4fVector new_cogs, double label_tracking_tolerance)
message_filters::sync_policies::ApproximateTime< jsk_recognition_msgs::ClusterPointIndices, sensor_msgs::PointCloud2 > ApproximateSyncPolicy
virtual void clusteringClusterIndices(pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, std::vector< pcl::PointIndices::Ptr > &cluster_indices, std::vector< pcl::PointIndices > &clustered_indices)
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::ClusterPointIndices, sensor_msgs::PointCloud2 > SyncPolicy
std::vector< int > original_to_downsample_indices_
ros::Publisher cluster_num_pub_
double label_tracking_tolerance
boost::mutex mutex
global mutex.
jsk_pcl_ros::EuclideanClusteringConfig Config
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_point_cloud_
ros::ServiceServer service_
virtual void multi_extract(const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &cluster_indices, const sensor_msgs::PointCloud2::ConstPtr &input)
virtual void extract(const sensor_msgs::PointCloud2ConstPtr &input)
virtual void removeDuplicatedIndices(pcl::PointIndices::Ptr indices)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
bool serviceCallback(jsk_recognition_msgs::EuclideanSegment::Request &req, jsk_recognition_msgs::EuclideanSegment::Response &res)
std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > Vector4fVector