38 #include <pcl/filters/extract_indices.h> 39 #include <pcl/common/centroid.h> 40 #include <geometry_msgs/PoseStamped.h> 42 #include <pcl/pcl_config.h> 43 #if PCL_VERSION_COMPARE (<, 1, 7, 2) 53 ConnectionBasedNodelet::onInit();
54 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
55 dynamic_reconfigure::Server<Config>::CallbackType
f =
57 srv_->setCallback (f);
63 = advertise<jsk_recognition_msgs::ColorHistogramArray>(
64 *
pnh_,
"output_histograms", 1);
66 = advertise<geometry_msgs::PoseStamped>(*
pnh_,
"best_match", 1);
68 = advertise<jsk_recognition_msgs::ColorHistogram>(*
pnh_,
"output_reference", 1);
70 = advertise<jsk_recognition_msgs::ClusterPointIndices>(*
pnh_,
"output", 1);
72 = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"coefficient_points", 1);
87 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
112 if (config.histogram_method == 0) {
115 else if (config.histogram_method == 1) {
118 else if (config.histogram_method == 2) {
121 else if (config.histogram_method == 3) {
125 ROS_WARN(
"unknown histogram method");
128 if (new_histogram !=
policy_) {
131 ROS_WARN(
"histogram method is reset, please specify histogram again");
137 const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
138 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices)
142 NODELET_WARN(
"reference histogram is not available yet");
145 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pcl_cloud (
new pcl::PointCloud<pcl::PointXYZRGB>);
147 pcl::PointCloud<pcl::PointXYZHSV>::Ptr hsv_cloud (
new pcl::PointCloud<pcl::PointXYZHSV>);
149 for (
size_t i = 0; i < pcl_cloud->points.size(); i++) {
150 hsv_cloud->points[i].x = pcl_cloud->points[i].x;
151 hsv_cloud->points[i].y = pcl_cloud->points[i].y;
152 hsv_cloud->points[i].z = pcl_cloud->points[i].z;
155 std::vector<std::vector<float> > histograms;
156 histograms.resize(input_indices->cluster_indices.size());
157 unsigned long point_all_size=0;
158 pcl::ExtractIndices<pcl::PointXYZHSV> extract;
159 extract.setInputCloud(hsv_cloud);
161 jsk_recognition_msgs::ColorHistogramArray histogram_array;
162 histogram_array.header = input_cloud->header;
163 std::vector<pcl::PointCloud<pcl::PointXYZHSV>::Ptr > segmented_clouds;
164 for (
size_t i = 0; i < input_indices->cluster_indices.size(); i++) {
165 pcl::IndicesPtr indices (
new std::vector<int>(input_indices->cluster_indices[i].indices));
166 point_all_size+=indices->size();
167 extract.setIndices(indices);
168 pcl::PointCloud<pcl::PointXYZHSV> segmented_cloud;
169 extract.filter(segmented_cloud);
170 segmented_clouds.push_back(segmented_cloud.makeShared());
171 std::vector<float> histogram;
173 histograms[i] = histogram;
174 jsk_recognition_msgs::ColorHistogram ros_histogram;
175 ros_histogram.header = input_cloud->header;
176 ros_histogram.histogram = histogram;
177 histogram_array.histograms.push_back(ros_histogram);
182 jsk_recognition_msgs::ClusterPointIndices
result;
183 result.header = input_indices->header;
184 double best_coefficient = - DBL_MAX;
186 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output_cloud (
new pcl::PointCloud<pcl::PointXYZRGB>);
188 output_cloud->width=point_all_size;
189 output_cloud->height=1;
190 output_cloud->resize(point_all_size);
192 unsigned long count_points=0;
193 for (
size_t i = 0; i < input_indices->cluster_indices.size(); i++) {
197 int tmp_point_size = input_indices->cluster_indices[i].indices.size();
198 double color_standard;
206 double color_standard_powered = 1;
207 for (
int k=0; k<
power_; k++){
208 color_standard_powered *= color_standard;
210 unsigned char color_r, color_g, color_b;
213 color_r=(int)(255*color_standard_powered);
215 color_b=(int)(255*(1-color_standard_powered));
219 int color_index = (int)(color_standard_powered*1280);
220 switch(color_index/256){
222 color_r=0; color_g=0; color_b=color_index;
225 color_r=color_index-256; color_g=0; color_b=255;
228 color_r=255; color_g=0; color_b=255-(color_index-256*2);
231 color_r=255; color_g=color_index-256*3; color_b=0;
234 color_r=255; color_g=255; color_b=color_index-256*4;
237 color_r=255; color_g=255; color_b=255;
242 for(
int j=0; j<tmp_point_size; j++){
243 output_cloud->points[j+count_points].x=segmented_clouds[i]->points[j].x;
244 output_cloud->points[j+count_points].y=segmented_clouds[i]->points[j].y;
245 output_cloud->points[j+count_points].z=segmented_clouds[i]->points[j].z;
246 output_cloud->points[j+count_points].r=color_r;
247 output_cloud->points[j+count_points].g=color_g;
248 output_cloud->points[j+count_points].b=color_b;
250 count_points+=tmp_point_size;
253 result.cluster_indices.push_back(input_indices->cluster_indices[i]);
254 if (best_coefficient < coefficient) {
255 best_coefficient = coefficient;
260 NODELET_DEBUG(
"best coefficients: %f, %d", best_coefficient, best_index);
262 sensor_msgs::PointCloud2 p_msg;
265 p_msg.header=input_cloud->header;
269 if (best_index != -1) {
270 pcl::PointCloud<pcl::PointXYZHSV>::Ptr best_cloud
271 = segmented_clouds[best_index];
273 best_cloud->is_dense =
false;
274 Eigen::Vector4f center;
275 pcl::compute3DCentroid(*best_cloud, center);
276 geometry_msgs::PoseStamped best_pose;
277 best_pose.header = input_cloud->header;
278 best_pose.pose.position.x = center[0];
279 best_pose.pose.position.y = center[1];
280 best_pose.pose.position.z = center[2];
281 best_pose.pose.orientation.w = 1.0;
288 if (a.size() != b.size()) {
293 for (
size_t i = 0; i < a.size(); i++) {
294 sum +=
sqrt(a[i] * b[i]);
300 const pcl::PointCloud<pcl::PointXYZHSV>& cloud,
301 std::vector<float>& output,
305 std::vector<float> hue, saturation;
309 output.resize(hue.size() + saturation.size());
310 for (
size_t i = 0; i < hue.size(); i++) {
313 for (
size_t j = hue.size(); j < hue.size() + saturation.size(); j++) {
314 output[j] = saturation[j - hue.size()];
318 double val_max, val_min;
328 for (
size_t i = 0; i < cloud.points.size(); i++) {
333 val = output_point.h;
336 val = output_point.s;
339 val = output_point.v;
341 int index = int((val - val_min) / (val_max - val_min) *
bin_size_);
342 if (index >= bin_size_) {
343 index = bin_size_ - 1;
345 output[index] += 1.0;
350 for (
size_t i = 0; i < output.size(); i++) {
353 for (
size_t i = 0; i < output.size(); i++) {
364 const sensor_msgs::PointCloud2::ConstPtr& input_cloud)
367 std::vector<float> hist;
368 pcl::PointCloud<pcl::PointXYZRGB> pcl_cloud;
370 pcl::PointCloud<pcl::PointXYZHSV> hsv_cloud;
376 jsk_recognition_msgs::ColorHistogram ros_histogram;
377 ros_histogram.header = input_cloud->header;
383 const jsk_recognition_msgs::ColorHistogram::ConstPtr& input_histogram)
virtual void feature(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices)
ros::Publisher all_histogram_pub_
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
double color_min_coefficient_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void reference(const sensor_msgs::PointCloud2::ConstPtr &input_cloud)
ros::Publisher reference_histogram_pub_
ros::Publisher coefficient_points_pub_
ros::Publisher result_pub_
ColorHistogramMatcherConfig Config
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual double bhattacharyyaCoefficient(const std::vector< float > &a, const std::vector< float > &b)
double color_max_coefficient_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
ros::Subscriber reference_histogram_sub_
bool publish_colored_cloud_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
#define NODELET_DEBUG_STREAM(...)
virtual void unsubscribe()
#define NODELET_INFO(...)
virtual void configCallback(Config &config, uint32_t level)
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)
virtual void referenceHistogram(const jsk_recognition_msgs::ColorHistogram::ConstPtr &input_histogram)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ColorHistogramMatcher, nodelet::Nodelet)
std::vector< float > reference_histogram_
virtual void computeHistogram(const pcl::PointCloud< pcl::PointXYZHSV > &cloud, std::vector< float > &output, const ComparePolicy policy)
ros::Subscriber reference_sub_
#define NODELET_DEBUG(...)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void PointCloudXYZRGBtoXYZHSV(PointCloud< PointXYZRGB > &in, PointCloud< PointXYZHSV > &out)
Convert a XYZRGB point cloud to a XYZHSV.
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_