41 #include <pcl/filters/extract_indices.h> 43 #include <pcl/pcl_config.h> 44 #if PCL_VERSION_COMPARE (<, 1, 7, 2) 54 DiagnosticNodelet::onInit();
55 srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
56 dynamic_reconfigure::Server<Config>::CallbackType
f =
59 pub_histogram_ = advertise<jsk_recognition_msgs::ColorHistogramArray>(*
pnh_,
"output", 1);
83 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
96 const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
97 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices)
101 pcl::PointCloud<pcl::PointXYZRGB>::Ptr rgb_cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
104 pcl::PointCloud<pcl::PointXYZHSV>::Ptr hsv_cloud(
new pcl::PointCloud<pcl::PointXYZHSV>);
107 for (
size_t i = 0; i < rgb_cloud->points.size(); i++) {
108 hsv_cloud->points[i].x = rgb_cloud->points[i].x;
109 hsv_cloud->points[i].y = rgb_cloud->points[i].y;
110 hsv_cloud->points[i].z = rgb_cloud->points[i].z;
113 pcl::ExtractIndices<pcl::PointXYZHSV> extract;
114 extract.setInputCloud(hsv_cloud);
116 jsk_recognition_msgs::ColorHistogramArray histogram_array;
117 histogram_array.histograms.resize(input_indices->cluster_indices.size());
118 histogram_array.header = input_cloud->header;
119 for (
size_t i = 0; i < input_indices->cluster_indices.size(); ++i) {
120 pcl::IndicesPtr indices(
new std::vector<int>(input_indices->cluster_indices[i].indices));
121 extract.setIndices(indices);
122 pcl::PointCloud<pcl::PointXYZHSV> segmented_cloud;
123 extract.filter(segmented_cloud);
124 histogram_array.histograms[i].header = input_cloud->header;
127 histogram_array.histograms[i].histogram,
133 histogram_array.histograms[i].histogram,
virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
ColorHistogramConfig Config
void publish(const boost::shared_ptr< M > &message) const
void computeColorHistogram1d(const pcl::PointCloud< pcl::PointXYZHSV > &cloud, std::vector< float > &histogram, const int bin_size, const double white_threshold=0.1, const double black_threshold=0.1)
void computeColorHistogram2d(const pcl::PointCloud< pcl::PointXYZHSV > &cloud, std::vector< float > &histogram, const int bin_size_per_channel, const double white_threshold=0.1, const double black_threshold=0.1)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher pub_histogram_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ColorHistogram, nodelet::Nodelet)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
virtual void feature(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
jsk_recognition_utils::HistogramPolicy histogram_policy_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
#define NODELET_FATAL(...)
virtual void unsubscribe()
void PointCloudXYZRGBtoXYZHSV(PointCloud< PointXYZRGB > &in, PointCloud< PointXYZHSV > &out)
Convert a XYZRGB point cloud to a XYZHSV.