target_adaptive_tracking_nodelet.cpp
Go to the documentation of this file.
1 // Copyright (C) 2015 by Krishneel Chaudhary, JSK Lab,
2 // The University of Tokyo, Japan
3 
5 #include <map>
6 #include <string>
7 
8 namespace jsk_pcl_ros
9 {
11  DiagnosticNodelet("target_adaptive_tracking"),
12  init_counter_(0),
13  update_counter_(0),
14  growth_rate_(1.15)
15  {
16  this->object_reference_ = ModelsPtr(new Models);
18  this->previous_template_ = pcl::PointCloud<PointT>::Ptr(
19  new pcl::PointCloud<PointT>);
20  }
21 
23  {
24  DiagnosticNodelet::onInit();
25 
26  pnh_->param("use_tf", use_tf_, false);
27  pnh_->param("parent_frame_id", parent_frame_id_, std::string("/track_result"));
28  pnh_->param("child_frame_id", child_frame_id_, std::string("/camera_rgb_optical_frame"));
29 
30  srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
31  dynamic_reconfigure::Server<Config>::CallbackType f =
32  boost::bind(&TargetAdaptiveTracking::configCallback, this, _1, _2);
33  srv_->setCallback(f);
34 
35  this->pub_cloud_ = advertise<sensor_msgs::PointCloud2>(
36  *pnh_, "/target_adaptive_tracking/output/cloud", 1);
37 
38  // this->pub_templ_ = advertise<sensor_msgs::PointCloud2>(
39  // *pnh_, "/target_adaptive_tracking/output/template", 1);
40 
41  this->pub_templ_ = advertise<sensor_msgs::PointCloud2>(
42  *pnh_, "/selected_pointcloud", 1);
43 
44  this->pub_sindices_ = advertise<
45  jsk_recognition_msgs::ClusterPointIndices>(
46  *pnh_, "/target_adaptive_tracking/supervoxel/indices", 1);
47 
48  this->pub_scloud_ = advertise<sensor_msgs::PointCloud2>(
49  *pnh_, "/target_adaptive_tracking/supervoxel/cloud", 1);
50 
51  this->pub_normal_ = advertise<sensor_msgs::PointCloud2>(
52  *pnh_, "/target_adaptive_tracking/output/normal", 1);
53 
54  this->pub_tdp_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
55  *pnh_, "/target_adaptive_tracking/supervoxel/tdp_indices", 1);
56 
57  this->pub_inliers_ = advertise<sensor_msgs::PointCloud2>(
58  *pnh_, "/target_adaptive_tracking/output/inliers", 1);
59 
60  this->pub_centroids_ = advertise<sensor_msgs::PointCloud2>(
61  *pnh_, "/target_adaptive_tracking/output/centroids", 1);
62 
63  this->pub_pose_ = advertise<geometry_msgs::PoseStamped>(
64  *pnh_, "/target_adaptive_tracking/output/object_pose", 1);
65 
66  this->pub_prob_ = advertise<sensor_msgs::PointCloud2>(
67  *pnh_, "/target_adaptive_tracking/output/probability_map", 1);
68 
70  }
71 
73  {
74  this->sub_obj_cloud_.subscribe(*pnh_, "input_obj_cloud", 1);
75  this->sub_bkgd_cloud_.subscribe(*pnh_, "input_bkgd_cloud", 1);
76  this->sub_obj_pose_.subscribe(*pnh_, "input_obj_pose", 1);
77  this->obj_sync_ = boost::make_shared<message_filters::Synchronizer<
78  ObjectSyncPolicy> >(100);
79  this->obj_sync_->connectInput(
81  this->obj_sync_->registerCallback(
83  this, _1, _2, _3));
84  this->sub_cloud_.subscribe(*pnh_, "input_cloud", 1);
85  this->sub_pose_.subscribe(*pnh_, "input_pose", 1);
86  this->sync_ = boost::make_shared<message_filters::Synchronizer<
87  SyncPolicy> >(100);
88  this->sync_->connectInput(sub_cloud_, sub_pose_);
89  this->sync_->registerCallback(
91  this, _1, _2));
92  }
93 
95  {
96  this->sub_cloud_.unsubscribe();
97  this->sub_pose_.unsubscribe();
99  this->sub_obj_pose_.unsubscribe();
100  }
101 
103  const sensor_msgs::PointCloud2::ConstPtr &cloud_msg,
104  const sensor_msgs::PointCloud2::ConstPtr &bkgd_msg,
105  const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
106  {
107  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
108  pcl::fromROSMsg(*cloud_msg, *cloud);
109  pcl::PointCloud<PointT>::Ptr bkgd_cloud (new pcl::PointCloud<PointT>);
110  pcl::fromROSMsg(*bkgd_msg, *bkgd_cloud);
111  if (this->init_counter_++ > 0) {
112  ROS_WARN("Object is re-initalized! stopping & reseting...");
113  }
114  if (!cloud->empty() && !bkgd_cloud->empty()) {
115  this->motion_history_.clear();
116  PointXYZRPY motion_displacement;
117  this->estimatedPFPose(pose_msg, motion_displacement);
118  this->previous_pose_ = this->current_pose_;
119  this->object_reference_ = ModelsPtr(new Models);
120  this->processInitCloud(cloud, this->object_reference_);
122  this->processInitCloud(bkgd_cloud, this->background_reference_);
124  this->previous_template_->clear();
125  pcl::copyPointCloud<PointT, PointT>(*cloud, *previous_template_);
127 
128  sensor_msgs::PointCloud2 ros_templ;
129  pcl::toROSMsg(*cloud, ros_templ);
130  ros_templ.header = cloud_msg->header;
131  this->pub_templ_.publish(ros_templ);
132  }
133  }
134 
136  const pcl::PointCloud<PointT>::Ptr cloud,
137  ModelsPtr object_reference)
138  {
139  if (cloud->empty()) {
140  ROS_ERROR("OBJECT INIT CLOUD IS EMPTY");
141  return;
142  }
143  float seed_resolution = static_cast<float>(this->seed_resolution_) / 2.0f;
144  float seed_factor = seed_resolution;
145  for (int i = 0; i < 3; i++) {
146  std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> supervoxel_clusters;
147  std::multimap<uint32_t, uint32_t> supervoxel_adjacency;
149  cloud, supervoxel_clusters, supervoxel_adjacency, seed_resolution);
150  ModelsPtr obj_ref(new Models);
151  std::vector<AdjacentInfo> supervoxel_list;
153  cloud, supervoxel_clusters, supervoxel_adjacency,
154  supervoxel_list, obj_ref, true, true, true, true);
155  for (int j = 0; j < obj_ref->size(); j++) {
156  object_reference->push_back(obj_ref->operator[](j));
157  }
158  seed_resolution += seed_factor;
159  }
160  }
161 
163  const sensor_msgs::PointCloud2::ConstPtr &cloud_msg,
164  const geometry_msgs::PoseStamped::ConstPtr &pose_msg) {
165  if (this->object_reference_->empty())
166  {
167  ROS_WARN("No Model To Track Selected");
168  return;
169  }
170  ROS_INFO("\n\n\033[34m------------RUNNING CALLBACK-------------\033[0m");
172  PointXYZRPY motion_displacement;
173  this->estimatedPFPose(pose_msg, motion_displacement);
174  std::cout << "Motion Displacement: " << motion_displacement << std::endl;
175 
176  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
177  pcl::fromROSMsg(*cloud_msg, *cloud);
178  tf::TransformListener tf_listener;
179  tf::StampedTransform transform;
180  ros::Time now = ros::Time(0);
181  Eigen::Affine3f transform_model = Eigen::Affine3f::Identity();
182  tf::Transform update_transform;
183  if (use_tf_) {
184  bool wft_ok = tf_listener.waitForTransform(
186  if (!wft_ok) {
187  ROS_ERROR("CANNOT TRANSFORM SOURCE AND TARGET FRAMES");
188  return;
189  }
190  tf_listener.lookupTransform(
191  child_frame_id_, parent_frame_id_, now, transform);
192  tf::Quaternion tf_quaternion = transform.getRotation();
193  transform_model = Eigen::Affine3f::Identity();
194  transform_model.translation() <<
195  transform.getOrigin().getX(),
196  transform.getOrigin().getY(),
197  transform.getOrigin().getZ();
198  Eigen::Quaternion<float> quaternion = Eigen::Quaternion<float>(
199  tf_quaternion.w(), tf_quaternion.x(),
200  tf_quaternion.y(), tf_quaternion.z());
201  transform_model.rotate(quaternion);
202  tf::Vector3 origin = tf::Vector3(transform.getOrigin().getX(),
203  transform.getOrigin().getY(),
204  transform.getOrigin().getZ());
205  update_transform.setOrigin(origin);
206  tf::Quaternion update_quaternion = tf_quaternion;
207  update_transform.setRotation(update_quaternion +
209 
210  } else {
211  transform_model = Eigen::Affine3f::Identity();
212  transform_model.translation() << pose_msg->pose.position.x,
213  pose_msg->pose.position.y, pose_msg->pose.position.z;
214  Eigen::Quaternion<float> pf_quat = Eigen::Quaternion<float>(
215  pose_msg->pose.orientation.w, pose_msg->pose.orientation.x,
216  pose_msg->pose.orientation.y, pose_msg->pose.orientation.z);
217  transform_model.rotate(pf_quat);
218  tf::Vector3 origin = tf::Vector3(
219  pose_msg->pose.position.x,
220  pose_msg->pose.position.y,
221  pose_msg->pose.position.z);
222  update_transform.setOrigin(origin);
223  tf::Quaternion update_quaternion = tf::Quaternion(
224  pose_msg->pose.orientation.x, pose_msg->pose.orientation.y,
225  pose_msg->pose.orientation.z, pose_msg->pose.orientation.w);
226  update_transform.setRotation(update_quaternion *
228  }
229 
230  Eigen::Affine3f transform_reference = Eigen::Affine3f::Identity();
231  const int motion_hist_index = static_cast<int>(
232  this->motion_history_.size()) - 1;
233  transform_reference.translation() <<
234  motion_history_[motion_hist_index].x,
235  motion_history_[motion_hist_index].y,
236  motion_history_[motion_hist_index].z;
237  Eigen::Affine3f transformation_matrix = transform_model *
238  transform_reference.inverse();
239  bool is_cloud_exist = this->filterPointCloud(
240  cloud, this->current_pose_, this->object_reference_, 1.5f);
241  if (is_cloud_exist && this->update_filter_template_) {
243  cloud, transformation_matrix, motion_displacement,
244  cloud_msg->header);
245  }
247  std::cout << "Processing Time: " << end - begin << std::endl;
248 
251  update_transform, cloud_msg->header.stamp,
252  cloud_msg->header.frame_id, "object_pose"));
253  this->previous_transform_ = update_transform;
254 
255  geometry_msgs::PoseStamped update_pose;
256  tf::poseTFToMsg(update_transform, update_pose.pose);
257  update_pose.header.stamp = cloud_msg->header.stamp;
258  update_pose.header.frame_id = child_frame_id_;
259  this->pub_pose_.publish(update_pose);
260 
261  sensor_msgs::PointCloud2 ros_cloud;
262  pcl::toROSMsg(*cloud, ros_cloud);
263  ros_cloud.header.stamp = cloud_msg->header.stamp;
264  ros_cloud.header.frame_id = child_frame_id_;
265  this->pub_cloud_.publish(ros_cloud);
266  }
267 
269  const pcl::PointCloud<PointT>::Ptr cloud,
270  const std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> &
271  supervoxel_clusters,
272  const std::multimap<uint32_t, uint32_t> &supervoxel_adjacency,
273  std::vector<AdjacentInfo> &supervoxel_list,
275  bool norm_flag, bool feat_flag, bool cent_flag, bool neigh_pfh)
276  {
277  if (cloud->empty() || supervoxel_clusters.empty()) {
278  return;
279  }
280  models = ModelsPtr(new Models);
281  int icounter = 0;
282  for (std::multimap<uint32_t, pcl::Supervoxel<PointT>::Ptr>::const_iterator
283  label_itr = supervoxel_clusters.begin(); label_itr !=
284  supervoxel_clusters.end(); label_itr++) {
285  ReferenceModel ref_model;
286  ref_model.flag = true;
287  ref_model.supervoxel_index = label_itr->first;
288  uint32_t supervoxel_label = label_itr->first;
289  pcl::Supervoxel<PointT>::Ptr supervoxel =
290  supervoxel_clusters.at(supervoxel_label);
291  if (supervoxel->voxels_->size() > min_cluster_size_) {
292  std::vector<uint32_t> adjacent_voxels;
293  for (std::multimap<uint32_t, uint32_t>::const_iterator
294  adjacent_itr = supervoxel_adjacency.equal_range(
295  supervoxel_label).first; adjacent_itr !=
296  supervoxel_adjacency.equal_range(
297  supervoxel_label).second; ++adjacent_itr) {
298  pcl::Supervoxel<PointT>::Ptr neighbor_supervoxel =
299  supervoxel_clusters.at(adjacent_itr->second);
300  if (neighbor_supervoxel->voxels_->size() >
302  adjacent_voxels.push_back(adjacent_itr->second);
303  }
304  icounter++;
305  }
306  AdjacentInfo a_info;
307  a_info.adjacent_voxel_indices[supervoxel_label] = adjacent_voxels;
308  supervoxel_list.push_back(a_info);
309  a_info.voxel_index = supervoxel_label;
310  ref_model.cluster_neigbors = a_info;
311  ref_model.cluster_cloud = pcl::PointCloud<PointT>::Ptr(
312  new pcl::PointCloud<PointT>);
313  ref_model.cluster_cloud = supervoxel->voxels_;
314  if (norm_flag) {
315  ref_model.cluster_normals = pcl::PointCloud<pcl::Normal>::Ptr(
316  new pcl::PointCloud<pcl::Normal>);
317  ref_model.cluster_normals = supervoxel->normals_;
318  }
319  if (feat_flag) {
321  ref_model.cluster_cloud,
322  ref_model.cluster_normals,
323  ref_model.cluster_vfh_hist);
324  this->computeColorHistogram(
325  ref_model.cluster_cloud,
326  ref_model.cluster_color_hist);
327  }
328  if (cent_flag) {
329  ref_model.cluster_centroid = Eigen::Vector4f();
330  ref_model.cluster_centroid =
331  supervoxel->centroid_.getVector4fMap();
332  }
333  ref_model.flag = false;
334  ref_model.match_counter = 0;
335  models->push_back(ref_model);
336  }
337  }
338  std::cout << "Cloud Voxel size: " << models->size() << std::endl;
339 
340  // compute the local pfh
341  if (neigh_pfh) {
342  for (int i = 0; i < models->size(); i++) {
344  supervoxel_clusters,
345  models->operator[](i).cluster_neigbors.adjacent_voxel_indices,
346  models->operator[](i).neigbour_pfh);
347  }
348  }
349  }
350 
352  pcl::PointCloud<PointT>::Ptr cloud,
353  const Eigen::Affine3f &transformation_matrix,
354  const TargetAdaptiveTracking::PointXYZRPY &motion_disp,
355  const std_msgs::Header header)
356  {
357  if (cloud->empty()) {
358  ROS_ERROR("ERROR: Global Layer Input Empty");
359  return;
360  }
361  pcl::PointCloud<PointT>::Ptr n_cloud(new pcl::PointCloud<PointT>);
362  Models obj_ref = *object_reference_;
363  std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> supervoxel_clusters;
364  std::multimap<uint32_t, uint32_t> supervoxel_adjacency;
365  this->supervoxelSegmentation(cloud,
366  supervoxel_clusters,
367  supervoxel_adjacency);
368  Eigen::Matrix<float, 3, 3> rotation_matrix;
369  rotation_matrix = transformation_matrix.rotation();
370 
371  std::vector<AdjacentInfo> supervoxel_list;
372  ModelsPtr t_voxels = ModelsPtr(new Models);
374  cloud, supervoxel_clusters, supervoxel_adjacency,
375  supervoxel_list, t_voxels, true, false, true);
376  Models target_voxels = *t_voxels;
377 
378  ROS_INFO("\033[35m MODEL TRANSITION FOR MATCHING \033[0m");
379  std::map<int, int> matching_indices;
380  pcl::PointCloud<PointT>::Ptr template_cloud(new pcl::PointCloud<PointT>);
381  for (int j = 0; j < obj_ref.size(); j++) {
382  if (!obj_ref[j].flag) {
383  float distance = FLT_MAX;
384  int nearest_index = -1;
385  Eigen::Vector4f obj_centroid;
386  obj_centroid = transformation_matrix * obj_ref[j].cluster_centroid;
387  for (int i = 0; i < target_voxels.size(); i++) {
388  if (!target_voxels[i].flag) {
389  Eigen::Vector4f t_centroid =
390  target_voxels[i].cluster_centroid;
391  t_centroid(3) = 1.0f;
392  float dist = static_cast<float>(
393  pcl::distances::l2(obj_centroid, t_centroid));
394  if (dist < distance) {
395  distance = dist;
396  nearest_index = i;
397  }
398  }
399  }
400  if (nearest_index != -1) {
401  matching_indices[j] = nearest_index;
402  }
403  const int motion_hist_index = this->motion_history_.size() - 1;
404  obj_ref[j].centroid_distance(0) = obj_ref[j].cluster_centroid(0) -
405  this->motion_history_[motion_hist_index].x;
406  obj_ref[j].centroid_distance(1) = obj_ref[j].cluster_centroid(1) -
407  this->motion_history_[motion_hist_index].y;
408  obj_ref[j].centroid_distance(2) = obj_ref[j].cluster_centroid(2) -
409  this->motion_history_[motion_hist_index].z;
410  }
411  }
412  ROS_INFO("\033[35m MATCHING THROUGH NIEGBOUR SEARCH \033[0m");
413  int counter = 0;
414  float connectivity_lenght = 2.0f;
415  pcl::PointCloud<PointT>::Ptr est_centroid_cloud(
416  new pcl::PointCloud<PointT>);
417  std::multimap<uint32_t, Eigen::Vector3f> estimated_centroids;
418  std::multimap<uint32_t, float> estimated_match_prob;
419  std::multimap<uint32_t, ReferenceModel*> estimated_match_info;
420  std::vector<uint32_t> best_match_index;
421  std::multimap<uint32_t, float> all_probabilites;
422  for (std::map<int, int>::iterator itr = matching_indices.begin();
423  itr != matching_indices.end(); itr++) {
424  if (!target_voxels[itr->second].flag) {
425  std::map<uint32_t, std::vector<uint32_t> > neigb =
426  target_voxels[itr->second].cluster_neigbors.adjacent_voxel_indices;
427  uint32_t v_ind = target_voxels[
428  itr->second].cluster_neigbors.voxel_index;
429  uint32_t bm_index = v_ind;
430  float probability = 0.0f;
431  ReferenceModel *voxel_model = new ReferenceModel;
432  probability = this->targetCandidateToReferenceLikelihood<float>(
433  obj_ref[itr->first], target_voxels[itr->second].cluster_cloud,
434  target_voxels[itr->second].cluster_normals,
435  target_voxels[itr->second].cluster_centroid, voxel_model);
436  voxel_model->query_index = itr->first;
437 
438  // TODO(.) collect the neigbours here instead of next for
439  // loop
440 
441  bool is_voxel_adjacency_info = true;
442  float local_weight = 0.0f;
443  if (is_voxel_adjacency_info) {
444  cv::Mat histogram_phf;
446  supervoxel_clusters, neigb, histogram_phf);
447  voxel_model->cluster_neigbors.adjacent_voxel_indices = neigb;
448  voxel_model->neigbour_pfh = histogram_phf.clone();
449  float dist_phf = static_cast<float>(
450  cv::compareHist(obj_ref[itr->first].neigbour_pfh,
451  histogram_phf, CV_COMP_BHATTACHARYYA));
452  local_weight = std::exp(-this->structure_scaling_ * dist_phf);
453  probability *= local_weight;
454  }
455  for (std::vector<uint32_t>::iterator it =
456  neigb.find(v_ind)->second.begin();
457  it != neigb.find(v_ind)->second.end(); it++) {
458  ReferenceModel *voxel_mod = new ReferenceModel;
459  float prob = this->targetCandidateToReferenceLikelihood<float>(
460  obj_ref[itr->first], supervoxel_clusters.at(*it)->voxels_,
461  supervoxel_clusters.at(*it)->normals_,
462  supervoxel_clusters.at(*it)->centroid_.getVector4fMap(),
463  voxel_mod);
464  voxel_mod->query_index = itr->first;
465  if (is_voxel_adjacency_info) {
466  std::map<uint32_t, std::vector<uint32_t> > local_adjacency;
467  std::vector<uint32_t> list_adj;
468  for (std::multimap<uint32_t, uint32_t>::const_iterator
469  adjacent_itr = supervoxel_adjacency.equal_range(
470  *it).first; adjacent_itr !=
471  supervoxel_adjacency.equal_range(*it).second;
472  ++adjacent_itr) {
473  list_adj.push_back(adjacent_itr->second);
474  }
475  local_adjacency[*it] = list_adj;
476  cv::Mat local_phf;
478  supervoxel_clusters, local_adjacency, local_phf);
479  voxel_mod->neigbour_pfh = local_phf.clone();
481  local_adjacency;
482  float dist_phf = static_cast<float>(
483  cv::compareHist(obj_ref[itr->first].neigbour_pfh,
484  local_phf, CV_COMP_BHATTACHARYYA));
485  float phf_prob = std::exp(-this->structure_scaling_ * dist_phf);
486  local_weight = phf_prob;
487  prob *= phf_prob;
488  }
489 
490  float matching_dist = static_cast<float>(pcl::distances::l2(
491  supervoxel_clusters.at(v_ind)->centroid_.getVector4fMap(),
492  supervoxel_clusters.at(*it)->centroid_.getVector4fMap()));
493  if (matching_dist > this->seed_resolution_ / connectivity_lenght) {
494  prob *= 0.0f;
495  }
496  if (prob > probability) {
497  probability = prob;
498  bm_index = *it;
499  voxel_model = voxel_mod;
500  }
501  }
502  all_probabilites.insert(
503  std::pair<uint32_t, float>(bm_index, probability));
504  if (probability > threshold_) {
505  Eigen::Vector3f estimated_position = supervoxel_clusters.at(
506  bm_index)->centroid_.getVector3fMap() - rotation_matrix *
507  obj_ref[itr->first].centroid_distance /* local_weight*/;
508  Eigen::Vector4f estimated_pos = Eigen::Vector4f(
509  estimated_position(0), estimated_position(1),
510  estimated_position(2), 0.0f);
511  float match_dist = static_cast<float>(
512  pcl::distances::l2(estimated_pos, current_pose_));
513 
514  if (match_dist < this->seed_resolution_ / connectivity_lenght) {
515  best_match_index.push_back(bm_index);
516  estimated_centroids.insert(
517  std::pair<uint32_t, Eigen::Vector3f>(
518  bm_index, estimated_position));
519  estimated_match_prob.insert(
520  std::pair<uint32_t, float>(bm_index, probability));
521  estimated_match_info.insert(
522  std::pair<uint32_t, ReferenceModel*>(
523  bm_index, voxel_model));
524  obj_ref[itr->first].history_window.push_back(1);
525  PointT pt;
526  pt.x = estimated_position(0);
527  pt.y = estimated_position(1);
528  pt.z = estimated_position(2);
529  pt.r = 255;
530  est_centroid_cloud->push_back(pt);
531  counter++;
532  } else {
533  ROS_WARN("-- Outlier not added...");
534  }
535  } else {
536  obj_ref[itr->first].history_window.push_back(0);
537  }
538  }
539  }
540  pcl::PointCloud<PointT>::Ptr prob_cloud(new pcl::PointCloud<PointT>);
541  for (std::multimap<uint32_t, float>::iterator it = all_probabilites.begin();
542  it != all_probabilites.end(); it++) {
543  if (it->second > eps_distance_) {
544  for (int i = 0; i < supervoxel_clusters.at(
545  it->first)->voxels_->size(); i++) {
546  PointT pt = supervoxel_clusters.at(it->first)->voxels_->points[i];
547  pt.r = 255 * it->second;
548  pt.g = 255 * it->second;
549  pt.b = 255 * it->second;
550  prob_cloud->push_back(pt);
551  }
552  }
553  }
554  sensor_msgs::PointCloud2 ros_prob;
555  pcl::toROSMsg(*prob_cloud, ros_prob);
556  ros_prob.header = header;
557  this->pub_prob_.publish(ros_prob);
558 
559  pcl::PointCloud<PointT>::Ptr inliers(new pcl::PointCloud<PointT>);
560  std::vector<uint32_t> outlier_index;
561 
562  ROS_INFO("\033[35m OUTLIER FILTERING VIA BACKPROJECTION \033[0m");
563  Eigen::Matrix<float, 3, 3> inv_rotation_matrix = rotation_matrix.inverse();
564  PointT ptt;
565  ptt.x = previous_pose_(0);
566  ptt.y = previous_pose_(1);
567  ptt.z = previous_pose_(2);
568  ptt.b = 255;
569  inliers->push_back(ptt);
570  std::vector<uint32_t> matching_indx = best_match_index;
571  best_match_index.clear();
572  for (std::vector<uint32_t>::iterator it = matching_indx.begin();
573  it != matching_indx.end(); it++) {
574  Eigen::Vector4f cur_pt = supervoxel_clusters.at(
575  *it)->centroid_.getVector4fMap();
576  Eigen::Vector3f demean_pts = Eigen::Vector3f();
577  demean_pts(0) = cur_pt(0) - this->current_pose_(0);
578  demean_pts(1) = cur_pt(1) - this->current_pose_(1);
579  demean_pts(2) = cur_pt(2) - this->current_pose_(2);
580  int query_idx = estimated_match_info.find(*it)->second->query_index;
581  Eigen::Vector3f abs_position = -(inv_rotation_matrix * demean_pts) +
582  obj_ref[query_idx].cluster_centroid.head<3>();
583  Eigen::Vector4f prev_vote = Eigen::Vector4f(
584  abs_position(0), abs_position(1), abs_position(2), 0.0f);
585  float matching_dist = static_cast<float>(
586  pcl::distances::l2(prev_vote, this->previous_pose_));
587 
588  PointT pt;
589  pt.x = abs_position(0);
590  pt.y = abs_position(1);
591  pt.z = abs_position(2);
592  if (matching_dist < this->seed_resolution_ / connectivity_lenght) {
593  best_match_index.push_back(*it);
594  pt.r = 255;
595  pt.b = 255;
596  } else {
597  pt.g = 255;
598  pt.b = 255;
599  }
600  inliers->push_back(pt);
601  }
602  /*
603  std::cout << "TOTAL POINTS: " << estimated_centroids.size() << std::endl;
604  std::cout << "Cloud Size: " << est_centroid_cloud->size() << "\t"
605  << inliers->size() << "\t" << counter << "\t Best Match: "
606  << best_match_index.size() << "\t Query-Test"
607  << matching_indices.size() << std::endl;
608  */
609 
610  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr centroid_normal(
611  new pcl::PointCloud<pcl::PointXYZRGBNormal>);
612 
613  // visualization of removed normal
614  for (std::vector<uint32_t>::iterator it = outlier_index.begin();
615  it != outlier_index.end(); it++) {
616  Eigen::Vector4f c_centroid = supervoxel_clusters.at(
617  *it)->centroid_.getVector4fMap();
618  Eigen::Vector4f c_normal = this->cloudMeanNormal(
619  supervoxel_clusters.at(*it)->normals_);
620  centroid_normal->push_back(
622  c_centroid, c_normal, cv::Scalar(0, 0, 255)));
623  }
624 
625  ROS_INFO("\033[35m CONVEX VOXELS \033[0m");
626  pcl::PointCloud<PointT>::Ptr output(new pcl::PointCloud<PointT>);
627  std::vector<uint32_t> neigb_lookup;
628  neigb_lookup = best_match_index;
629  std::vector<uint32_t> convex_ok;
630  std::map<uint32_t, ReferenceModel*> convex_local_voxels;
631 
632  for (std::vector<uint32_t>::iterator it = best_match_index.begin();
633  it != best_match_index.end(); it++) {
634  std::pair<std::multimap<uint32_t, uint32_t>::iterator,
635  std::multimap<uint32_t, uint32_t>::iterator> ret;
636  ret = supervoxel_adjacency.equal_range(*it);
637  Eigen::Vector4f c_centroid = supervoxel_clusters.at(
638  *it)->centroid_.getVector4fMap();
639  Eigen::Vector4f c_normal = this->cloudMeanNormal(
640  supervoxel_clusters.at(*it)->normals_);
641 
642  centroid_normal->push_back(
644  c_centroid, c_normal, cv::Scalar(255, 0, 0)));
645 
646  for (std::multimap<uint32_t, uint32_t>::iterator itr = ret.first;
647  itr != ret.second; itr++) {
648  bool is_process_neigh = true;
649  for (std::vector<uint32_t>::iterator lup_it = neigb_lookup.begin();
650  lup_it != neigb_lookup.end(); lup_it++) {
651  if (*lup_it == itr->second) {
652  is_process_neigh = false;
653  break;
654  }
655  }
656  if (!supervoxel_clusters.at(itr->second)->voxels_->empty() &&
657  is_process_neigh) {
658  bool is_common_neigh = false;
659  if (!is_common_neigh) {
660  neigb_lookup.push_back(itr->second);
661  Eigen::Vector4f n_centroid = supervoxel_clusters.at(
662  itr->second)->centroid_.getVector4fMap();
663  Eigen::Vector4f n_normal = this->cloudMeanNormal(
664  supervoxel_clusters.at(itr->second)->normals_);
665  float convx_weight = this->localVoxelConvexityLikelihood<
666  float>(c_centroid, c_normal, n_centroid, n_normal);
667  if (convx_weight > 0.0f) {
668  *output = *output + *supervoxel_clusters.at(
669  itr->second)->voxels_;
670 
671  ReferenceModel *ref_model = new ReferenceModel;
673  supervoxel_clusters, supervoxel_adjacency,
674  itr->second, ref_model);
675  if (!ref_model->flag) {
676  Eigen::Vector4f convx_centroid = Eigen::Vector4f();
677  convx_centroid = transformation_matrix.inverse() *
678  ref_model->cluster_centroid;
679  for (int j = 0; j < this->object_reference_->size();
680  j++) {
681  float rev_match_dist = static_cast<float>(
682  pcl::distances::l2(convx_centroid,
683  this->object_reference_->operator[](
684  j).cluster_centroid));
685  if (rev_match_dist < this->seed_resolution_) {
686  float convx_dist = static_cast<float>(
687  cv::compareHist(ref_model->cluster_vfh_hist,
688  object_reference_->operator[](
689  j).cluster_vfh_hist,
690  CV_COMP_BHATTACHARYYA));
691  float convx_prob = std::exp(
692  -1 * this->vfh_scaling_ * convx_dist);
693  if (convx_prob > this->threshold_) {
694  ref_model->query_index = static_cast<int>(j);
695  estimated_match_info.insert(
696  std::pair<int32_t, ReferenceModel*>(
697  itr->second, ref_model));
698  convex_ok.push_back(itr->second);
699  estimated_match_prob.insert(
700  std::pair<uint32_t, float>(
701  itr->second, convx_prob));
702  centroid_normal->push_back(
704  n_centroid, n_normal,
705  cv::Scalar(0, 255, 0)));
706  ROS_INFO("\033[34m Added VOXEL \033[0m");
707  break;
708  }
709  } else {
710  // TODO(complete): here
711  // mark and test on object in next (t +
712  // 1)
713  convex_local_voxels[itr->second] = ref_model;
714  centroid_normal->push_back(
716  n_centroid, n_normal, cv::Scalar(0, 255, 0)));
717  }
718  }
719  }
720  }
721  } else {
722  std::pair<
723  std::multimap<uint32_t, uint32_t>::iterator,
724  std::multimap<uint32_t, uint32_t>::iterator> comm_neigb;
725  comm_neigb = supervoxel_adjacency.equal_range(itr->second);
726  uint32_t common_neigbour_index = 0;
727  for (std::multimap<uint32_t, uint32_t>::iterator c_itr =
728  comm_neigb.first; c_itr != comm_neigb.second;
729  c_itr++) {
730  if (!supervoxel_clusters.at(
731  c_itr->second)->voxels_->empty()) {
732  bool is_common_neigh = false;
733  for (std::map<uint32_t, uint32_t>::iterator itr_ret =
734  supervoxel_adjacency.equal_range(c_itr->first).
735  first; itr_ret !=supervoxel_adjacency.equal_range(
736  c_itr->first).second; itr_ret++) {
737  if (itr_ret->second == *it) {
738  is_common_neigh = true;
739  common_neigbour_index = c_itr->second;
740  break;
741  }
742  }
743  if (is_common_neigh) {
744  break;
745  }
746  }
747  }
748  if (common_neigbour_index > 0) {
749  Eigen::Vector4f n_centroid_b = supervoxel_clusters.at(
750  itr->second)->centroid_.getVector4fMap();
751  Eigen::Vector4f n_normal_b = this->cloudMeanNormal(
752  supervoxel_clusters.at(itr->second)->normals_);
753  Eigen::Vector4f n_centroid_c = supervoxel_clusters.at(
754  common_neigbour_index)->centroid_.getVector4fMap();
755  Eigen::Vector4f n_normal_c = this->cloudMeanNormal(
756  supervoxel_clusters.at(common_neigbour_index)->normals_);
757  float convx_weight_ab = this->localVoxelConvexityLikelihood<
758  float>(c_centroid, c_normal, n_centroid_b, n_normal_b);
759  float convx_weight_ac = this->localVoxelConvexityLikelihood<
760  float>(c_centroid, c_normal, n_centroid_c, n_normal_c);
761  float convx_weight_bc = this->localVoxelConvexityLikelihood<
762  float>(n_centroid_b, n_normal_b, n_centroid_c,
763  n_normal_c);
764  if (convx_weight_ab != 0.0f &&
765  convx_weight_ac != 0.0f &&
766  convx_weight_bc != 0.0f) {
767  *output = *output + *supervoxel_clusters.at(
768  itr->second)->voxels_;
769  centroid_normal->push_back(
771  n_centroid_b, n_normal_b, cv::Scalar(0, 255, 0)));
772  neigb_lookup.push_back(itr->second);
773  ReferenceModel *ref_model = new ReferenceModel;
775  supervoxel_clusters, supervoxel_adjacency,
776  itr->second, ref_model);
777  if (!ref_model->flag) {
778  Eigen::Vector4f convx_centroid = Eigen::Vector4f();
779  convx_centroid = transformation_matrix.inverse() *
780  ref_model->cluster_centroid;
781  for (int j = 0; j < this->object_reference_->size(); j++) {
782  float rev_match_dist = static_cast<float>(
783  pcl::distances::l2(convx_centroid,
784  this->object_reference_->operator[](
785  j).cluster_centroid));
786  if (rev_match_dist < this->seed_resolution_) {
787  float convx_dist = static_cast<float>(
788  cv::compareHist(ref_model->cluster_vfh_hist,
789  object_reference_->operator[](
790  j).cluster_vfh_hist, CV_COMP_BHATTACHARYYA));
791  float convx_prob = std::exp(
792  -1 * this->vfh_scaling_ * convx_dist);
793  if (convx_prob > this->threshold_) {
794  ref_model->query_index = static_cast<int>(j);
795  estimated_match_info.insert(
796  std::pair<int32_t, ReferenceModel*>(
797  itr->second, ref_model));
798  convex_ok.push_back(itr->second);
799  estimated_match_prob.insert(
800  std::pair<uint32_t, float>(
801  itr->second, convx_prob));
802  centroid_normal->push_back(
804  n_centroid_b, n_normal_b,
805  cv::Scalar(0, 255, 0)));
806  break;
807  }
808  } else {
809  convex_local_voxels[itr->second] = ref_model;
810  }
811  }
812  }
813  }
814  }
815  }
816  }
817  }
818  *output = *output + *supervoxel_clusters.at(*it)->voxels_;
819  }
820  for (int i = 0; i < convex_ok.size(); i++) {
821  best_match_index.push_back(convex_ok[i]);
822  }
823 
824  ModelsPtr transform_model (new Models);
826  this->object_reference_, transform_model, transformation_matrix);
827  obj_ref.clear();
828  obj_ref = *transform_model;
829  if (best_match_index.size() > 2 && this->update_tracker_reference_) {
830  ROS_INFO("\n\033[32mUpdating Tracking Reference Model\033[0m \n");
831  std::map<int, ReferenceModel> matching_surfels;
832  for (std::vector<uint32_t>::iterator it = best_match_index.begin();
833  it != best_match_index.end(); it++) {
834  float adaptive_factor = estimated_match_prob.find(*it)->second;
835  std::pair<std::multimap<uint32_t, ReferenceModel*>::iterator,
836  std::multimap<uint32_t, ReferenceModel*>::iterator> ret;
837  ret = estimated_match_info.equal_range(*it);
838  for (std::multimap<uint32_t, ReferenceModel*>::iterator itr =
839  ret.first; itr != ret.second; ++itr) {
840  cv::Mat nvfh_hist = cv::Mat::zeros(
841  itr->second->cluster_vfh_hist.size(), CV_32F);
842  nvfh_hist = itr->second->cluster_vfh_hist * adaptive_factor +
843  obj_ref[itr->second->query_index].cluster_vfh_hist *
844  (1 - adaptive_factor);
845  cv::normalize(nvfh_hist, nvfh_hist, 0, 1,
846  cv::NORM_MINMAX, -1, cv::Mat());
847  cv::Mat ncolor_hist = cv::Mat::zeros(
848  itr->second->cluster_color_hist.size(),
849  itr->second->cluster_color_hist.type());
850  ncolor_hist = itr->second->cluster_color_hist * adaptive_factor +
851  obj_ref[itr->second->query_index].cluster_color_hist *
852  (1 - adaptive_factor);
853  cv::normalize(ncolor_hist, ncolor_hist, 0, 1,
854  cv::NORM_MINMAX, -1, cv::Mat());
855  cv::Mat local_phf = cv::Mat::zeros(
856  itr->second->neigbour_pfh.size(),
857  itr->second->neigbour_pfh.type());
858  local_phf = itr->second->neigbour_pfh * adaptive_factor +
859  obj_ref[itr->second->query_index].neigbour_pfh *
860  (1 - adaptive_factor);
861  cv::normalize(local_phf, local_phf, 0, 1,
862  cv::NORM_MINMAX, -1, cv::Mat());
863  int query_idx = estimated_match_info.find(
864  *it)->second->query_index;
865  obj_ref[query_idx].cluster_cloud = supervoxel_clusters.at(
866  *it)->voxels_;
867  obj_ref[query_idx].cluster_vfh_hist = nvfh_hist.clone();
868  obj_ref[query_idx].cluster_color_hist = ncolor_hist.clone();
869  obj_ref[query_idx].cluster_normals = supervoxel_clusters.at(
870  *it)->normals_;
871  obj_ref[query_idx].cluster_centroid = supervoxel_clusters.at(
872  *it)->centroid_.getVector4fMap();
873  obj_ref[query_idx].neigbour_pfh = local_phf.clone();
874  obj_ref[query_idx].flag = false;
875  matching_surfels[query_idx] = obj_ref[query_idx];
876  obj_ref[query_idx].match_counter++;
877  }
878  }
879  this->motion_history_.push_back(this->tracker_pose_);
880  this->previous_pose_ = this->current_pose_;
881  // std::cout << "Updating Ref Model: " << matching_surfels.size()
882  // << "\t Convex: " << convex_local_voxels.size()
883  // << std::endl;
884 
885  for (std::map<int, ReferenceModel>::iterator it =
886  matching_surfels.begin(); it != matching_surfels.end(); it++) {
887  this->object_reference_->operator[](it->first) = it->second;
888  }
889  for (std::map<uint32_t, ReferenceModel*>::iterator it =
890  convex_local_voxels.begin(); it != convex_local_voxels.begin();
891  it++) {
892  this->object_reference_->push_back(*(it->second));
893  }
894  ModelsPtr tmp_model(new Models);
895  if (this->update_counter_++ == this->history_window_size_) {
896  for (int i = 0; i < this->object_reference_->size(); i++) {
897  if (this->object_reference_->operator[](i).match_counter > 0) {
898  ReferenceModel renew_model;
899  renew_model = this->object_reference_->operator[](i);
900  tmp_model->push_back(renew_model);
901  } else {
902  std::cout << "\033[033m OUTDATED MODEL \033[0m" << std::endl;
903  }
904  }
905  this->update_counter_ = 0;
906  this->object_reference_->clear();
907  this->object_reference_ = tmp_model;
908  }
909 
910  } else {
911  ROS_WARN("TRACKING MODEL CURRENTLY SET TO STATIC\n");
912  }
913  template_cloud->clear();
914  int tmp_counter = 0;
915  float argmax_lenght = 0.0f;
916  for (int i = 0; i < this->object_reference_->size(); i++) {
917  Eigen::Vector4f surfel_centroid = Eigen::Vector4f();
918  surfel_centroid = this->object_reference_->operator[](
919  i).cluster_centroid;
920  surfel_centroid(3) = 0.0f;
921  float surfel_dist = static_cast<float>(
922  pcl::distances::l2(surfel_centroid, current_pose_));
923  if (surfel_dist > argmax_lenght) {
924  argmax_lenght = surfel_dist;
925  }
926  if (surfel_dist < (this->previous_distance_ * growth_rate_)) {
927  float probability = 0.0f;
928  for (int j = 0; j < this->background_reference_->size(); j++) {
929  ReferenceModel *r_mod = new ReferenceModel;
930  float prob = this->targetCandidateToReferenceLikelihood<float>(
931  this->object_reference_->operator[](i),
932  this->background_reference_->operator[](j).cluster_cloud,
933  this->background_reference_->operator[](j).cluster_normals,
934  this->background_reference_->operator[](j).cluster_centroid,
935  r_mod);
936  if (prob > probability) {
937  probability = prob;
938  }
939  }
940  if (probability < 0.60f) {
941  *template_cloud = *template_cloud + *(
942  this->object_reference_->operator[](i).cluster_cloud);
943  tmp_counter++;
944  } else {
945  ROS_INFO("\033[35m SURFEL REMOVED AS BACKGRND \033[0m");
946  }
947  } else {
948  ROS_INFO("\033[35m SURFEL REMOVED \033[0m]");
949  }
950  }
951  if (argmax_lenght > (growth_rate_ * previous_distance_)) {
952  argmax_lenght = previous_distance_ * growth_rate_;
953  } else if (argmax_lenght < ((1 - growth_rate_) * previous_distance_)) {
954  argmax_lenght = (1 - growth_rate_) * previous_distance_;
955  }
957  this->previous_distance_ = argmax_lenght;
958 
959  // std::cout << "\033[031m TEMPLATE SIZE: \033[0m" << template_cloud->size()
960  // << std::endl;
961 
962  if (tmp_counter < 1) {
963  template_cloud->clear();
964  pcl::copyPointCloud<PointT, PointT>(*previous_template_, *template_cloud);
965  } else {
966  ROS_INFO("\033[34m UPDATING INFO...\033[0m");
967  // previous_distance_ = this->templateCloudFilterLenght(template_cloud);
968  pcl::copyPointCloud<PointT, PointT>(*template_cloud, *previous_template_);
969  this->object_reference_ = ModelsPtr(new Models);
970  this->processInitCloud(template_cloud, this->object_reference_);
971  }
972  std::cout << "\033[038m REFERENCE INFO \033[0m"
973  << object_reference_->size() << std::endl;
974  cloud->clear();
975  pcl::copyPointCloud<PointT, PointT>(*output, *cloud);
976  pcl::PointIndices tdp_ind;
977  for (int i = 0; i < cloud->size(); i++) {
978  tdp_ind.indices.push_back(i);
979  }
980  if (this->update_filter_template_) {
981  sensor_msgs::PointCloud2 ros_templ;
982  pcl::toROSMsg(*template_cloud, ros_templ);
983  ros_templ.header = header;
984  this->pub_templ_.publish(ros_templ);
985  }
986  // visualization of target surfels
987  std::vector<pcl::PointIndices> all_indices;
988  all_indices.push_back(tdp_ind);
989  jsk_recognition_msgs::ClusterPointIndices tdp_indices;
990  tdp_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
991  all_indices, header);
992  tdp_indices.header = header;
993  this->pub_tdp_.publish(tdp_indices);
994 
995  // for visualization of supervoxel
996  sensor_msgs::PointCloud2 ros_svcloud;
997  jsk_recognition_msgs::ClusterPointIndices ros_svindices;
998  this->publishSupervoxel(
999  supervoxel_clusters, ros_svcloud, ros_svindices, header);
1000  pub_scloud_.publish(ros_svcloud);
1001  pub_sindices_.publish(ros_svindices);
1002 
1003  // for visualization of inliers
1004  sensor_msgs::PointCloud2 ros_inliers;
1005  pcl::toROSMsg(*inliers, ros_inliers);
1006  ros_inliers.header = header;
1007  this->pub_inliers_.publish(ros_inliers);
1008 
1009  // for visualization of initial centroids
1010  sensor_msgs::PointCloud2 ros_centroids;
1011  pcl::toROSMsg(*est_centroid_cloud, ros_centroids);
1012  ros_centroids.header = header;
1013  this->pub_centroids_.publish(ros_centroids);
1014 
1015  // for visualization of normal
1016  sensor_msgs::PointCloud2 rviz_normal;
1017  pcl::toROSMsg(*centroid_normal, rviz_normal);
1018  rviz_normal.header = header;
1019  this->pub_normal_.publish(rviz_normal);
1020  }
1021 
1023  const std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> supervoxel_clusters,
1024  const std::multimap<uint32_t, uint32_t> supervoxel_adjacency,
1025  const uint32_t match_index,
1027  {
1028  if (supervoxel_clusters.empty() || supervoxel_adjacency.empty()) {
1029  ROS_ERROR("ERROR: empty data for updating voxel ref model");
1030  return;
1031  }
1032  if (supervoxel_clusters.at(
1033  match_index)->voxels_->size() > this->min_cluster_size_) {
1034  ref_model->flag = false;
1035  ref_model->cluster_cloud = supervoxel_clusters.at(
1036  match_index)->voxels_;
1037  ref_model->cluster_normals = supervoxel_clusters.at(
1038  match_index)->normals_;
1039  ref_model->cluster_centroid = supervoxel_clusters.at(
1040  match_index)->centroid_.getVector4fMap();
1042  ref_model->cluster_cloud,
1043  ref_model->cluster_normals,
1044  ref_model->cluster_vfh_hist);
1045  this->computeColorHistogram(
1046  ref_model->cluster_cloud,
1047  ref_model->cluster_color_hist);
1048  std::vector<uint32_t> adjacent_voxels;
1049  for (std::multimap<uint32_t, uint32_t>::const_iterator adjacent_itr =
1050  supervoxel_adjacency.equal_range(match_index).first;
1051  adjacent_itr != supervoxel_adjacency.equal_range(
1052  match_index).second; ++adjacent_itr) {
1053  pcl::Supervoxel<PointT>::Ptr neighbor_supervoxel =
1054  supervoxel_clusters.at(adjacent_itr->second);
1055  if (neighbor_supervoxel->voxels_->size() >
1057  adjacent_voxels.push_back(adjacent_itr->second);
1058  }
1059  }
1060  AdjacentInfo a_info;
1061  a_info.adjacent_voxel_indices[match_index] = adjacent_voxels;
1062  a_info.voxel_index = match_index;
1063  ref_model->cluster_neigbors = a_info;
1064  std::map<uint32_t, std::vector<uint32_t> > local_adj;
1065  local_adj[match_index] = adjacent_voxels;
1067  supervoxel_clusters, local_adj, ref_model->neigbour_pfh);
1068  } else {
1069  ref_model->flag = true;
1070  }
1071  }
1072 
1073  template<class T>
1075  const TargetAdaptiveTracking::ReferenceModel &reference_model,
1076  const pcl::PointCloud<PointT>::Ptr cloud,
1077  const pcl::PointCloud<pcl::Normal>::Ptr normal,
1078  const Eigen::Vector4f &centroid,
1079  ReferenceModel *voxel_model)
1080  {
1081  if (cloud->empty() || normal->empty()) {
1082  return 0.0f;
1083  }
1084  cv::Mat vfh_hist;
1085  this->computeCloudClusterRPYHistogram(cloud, normal, vfh_hist);
1086  cv::Mat color_hist;
1087  this->computeColorHistogram(cloud, color_hist);
1088  T dist_vfh = static_cast<T>(
1089  cv::compareHist(vfh_hist,
1090  reference_model.cluster_vfh_hist,
1091  CV_COMP_BHATTACHARYYA));
1092  T dist_col = static_cast<T>(
1093  cv::compareHist(color_hist,
1094  reference_model.cluster_color_hist,
1095  CV_COMP_BHATTACHARYYA));
1096  T probability = std::exp(-1 * this->vfh_scaling_ * dist_vfh) *
1097  std::exp(-1 * this->color_scaling_ * dist_col);
1098  bool convex_weight = false;
1099  if (convex_weight) {
1100  Eigen::Vector4f n_normal = this->cloudMeanNormal(normal);
1101  Eigen::Vector4f n_centroid = centroid;
1102  Eigen::Vector4f c_normal = this->cloudMeanNormal(
1103  reference_model.cluster_normals);
1104  Eigen::Vector4f c_centroid = reference_model.cluster_centroid;
1105  float convx_prob = this->localVoxelConvexityLikelihood<float>(
1106  c_centroid, c_normal, n_centroid, n_normal);
1107  probability * convx_prob;
1108  }
1109  voxel_model->cluster_vfh_hist = vfh_hist.clone();
1110  voxel_model->cluster_color_hist = color_hist.clone();
1111  return probability;
1112  }
1113 
1114  template<class T>
1116  Eigen::Vector4f c_centroid,
1117  Eigen::Vector4f c_normal,
1118  Eigen::Vector4f n_centroid,
1119  Eigen::Vector4f n_normal) {
1120  c_centroid(3) = 0.0f;
1121  c_normal(3) = 0.0f;
1122  n_centroid(3) = 0.0f;
1123  n_normal(3) = 0.0f;
1124  T weight = 1.0f;
1125  if ((n_centroid - c_centroid).dot(n_normal) > 0) {
1126  weight = static_cast<T>(std::pow(1 - (c_normal.dot(n_normal)), 2));
1127  return 1.0f;
1128  } else {
1129  // weight = static_cast<T>(1 - (c_normal.dot(n_normal)));
1130  return 0.0f;
1131  }
1132  if (std::isnan(weight)) {
1133  return 0.0f;
1134  }
1135  T probability = std::exp(-1 * weight);
1136  return probability;
1137  }
1138 
1140  const ModelsPtr background_reference,
1141  const ModelsPtr target_voxels,
1142  std::map<uint32_t, float> max_prob)
1143  {
1144  if (background_reference->empty() || target_voxels->empty()) {
1145  ROS_ERROR("INPUT DATA IS EMPTY");
1146  }
1147  for (int j = 0; j < target_voxels->size(); j++) {
1148  float probability = 0.0f;
1149  for (int i = 0; i < background_reference->size(); i++) {
1150  ReferenceModel *mod = new ReferenceModel;
1151  float prob = this->targetCandidateToReferenceLikelihood<float>(
1152  background_reference->operator[](i),
1153  target_voxels->operator[](j).cluster_cloud,
1154  target_voxels->operator[](j).cluster_normals,
1155  target_voxels->operator[](j).cluster_centroid,
1156  mod);
1157  if (prob > probability) {
1158  probability = prob;
1159  }
1160  }
1161  max_prob[target_voxels->operator[](j).supervoxel_index] = probability;
1162  }
1163  }
1164 
1165  template<class T>
1167  const pcl::PointCloud<PointT>::Ptr cloud,
1168  pcl::PointCloud<pcl::Normal>::Ptr normals,
1169  const T k, bool use_knn) const {
1170  if (cloud->empty()) {
1171  ROS_ERROR("ERROR: The Input cloud is Empty.....");
1172  return;
1173  }
1174  pcl::NormalEstimationOMP<PointT, pcl::Normal> ne;
1175  ne.setInputCloud(cloud);
1176  ne.setNumberOfThreads(8);
1177  pcl::search::KdTree<PointT>::Ptr tree (new pcl::search::KdTree<PointT> ());
1178  ne.setSearchMethod(tree);
1179  if (use_knn) {
1180  ne.setKSearch(k);
1181  } else {
1182  ne.setRadiusSearch(k);
1183  } ne.compute(*normals);
1184  }
1185 
1187  const pcl::PointCloud<PointT>::Ptr cloud,
1188  const pcl::PointCloud<pcl::Normal>::Ptr normal,
1189  cv::Mat &histogram) const
1190  {
1191  if (cloud->empty() || normal->empty()){
1192  ROS_ERROR("ERROR: Empty Input");
1193  return;
1194  }
1195  bool is_gfpfh = false;
1196  bool is_vfh = true;
1197  bool is_cvfh = false;
1198  if (is_gfpfh) {
1199  pcl::PointCloud<pcl::PointXYZL>::Ptr object(
1200  new pcl::PointCloud<pcl::PointXYZL>);
1201  for (int i = 0; i < cloud->size(); i++) {
1202  pcl::PointXYZL pt;
1203  pt.x = cloud->points[i].x;
1204  pt.y = cloud->points[i].y;
1205  pt.z = cloud->points[i].z;
1206  pt.label = 1;
1207  object->push_back(pt);
1208  }
1209  pcl::GFPFHEstimation<
1210  pcl::PointXYZL, pcl::PointXYZL, pcl::GFPFHSignature16> gfpfh;
1211  gfpfh.setInputCloud(object);
1212  gfpfh.setInputLabels(object);
1213  gfpfh.setOctreeLeafSize(0.01);
1214  gfpfh.setNumberOfClasses(1);
1215  pcl::PointCloud<pcl::GFPFHSignature16>::Ptr descriptor(
1216  new pcl::PointCloud<pcl::GFPFHSignature16>);
1217  gfpfh.compute(*descriptor);
1218  histogram = cv::Mat(sizeof(char), 16, CV_32F);
1219  for (int i = 0; i < histogram.cols; i++) {
1220  histogram.at<float>(0, i) = descriptor->points[0].histogram[i];
1221 
1222  }
1223  }
1224  if (is_vfh) {
1225  pcl::VFHEstimation<PointT,
1226  pcl::Normal,
1227  pcl::VFHSignature308> vfh;
1228  vfh.setInputCloud(cloud);
1229  vfh.setInputNormals(normal);
1230  pcl::search::KdTree<PointT>::Ptr tree(
1231  new pcl::search::KdTree<PointT>);
1232  vfh.setSearchMethod(tree);
1233  pcl::PointCloud<pcl::VFHSignature308>::Ptr vfhs(
1234  new pcl::PointCloud<pcl::VFHSignature308>());
1235  vfh.compute(*vfhs);
1236  histogram = cv::Mat(sizeof(char), 308, CV_32F);
1237  for (int i = 0; i < histogram.cols; i++) {
1238  histogram.at<float>(0, i) = vfhs->points[0].histogram[i];
1239  }
1240  }
1241  if (is_cvfh) {
1242  pcl::CVFHEstimation<PointT,
1243  pcl::Normal,
1244  pcl::VFHSignature308> cvfh;
1245  cvfh.setInputCloud(cloud);
1246  cvfh.setInputNormals(normal);
1247  pcl::search::KdTree<PointT>::Ptr tree(
1248  new pcl::search::KdTree<PointT>);
1249  cvfh.setSearchMethod(tree);
1250  cvfh.setEPSAngleThreshold(5.0f / 180.0f * M_PI);
1251  cvfh.setCurvatureThreshold(1.0f);
1252  cvfh.setNormalizeBins(false);
1253  pcl::PointCloud<pcl::VFHSignature308>::Ptr cvfhs(
1254  new pcl::PointCloud<pcl::VFHSignature308>());
1255  cvfh.compute(*cvfhs);
1256  histogram = cv::Mat(sizeof(char), 308, CV_32F);
1257  for (int i = 0; i < histogram.cols; i++) {
1258  histogram.at<float>(0, i) = cvfhs->points[0].histogram[i];
1259  }
1260  }
1261  }
1262 
1264  const pcl::PointCloud<PointT>::Ptr cloud,
1265  cv::Mat &hist, const int hBin, const int sBin, bool is_norm) const
1266  {
1267  cv::Mat pixels = cv::Mat::zeros(
1268  sizeof(char), static_cast<int>(cloud->size()), CV_8UC3);
1269  for (int i = 0; i < cloud->size(); i++) {
1270  cv::Vec3b pix_val;
1271  pix_val[0] = cloud->points[i].b;
1272  pix_val[1] = cloud->points[i].g;
1273  pix_val[2] = cloud->points[i].r;
1274  pixels.at<cv::Vec3b>(0, i) = pix_val;
1275  }
1276  cv::Mat hsv;
1277  cv::cvtColor(pixels, hsv, CV_BGR2HSV);
1278  int histSize[] = {hBin, sBin};
1279  float h_ranges[] = {0, 180};
1280  float s_ranges[] = {0, 256};
1281  const float* ranges[] = {h_ranges, s_ranges};
1282  int channels[] = {0, 1};
1283  cv::calcHist(
1284  &hsv, 1, channels, cv::Mat(), hist, 2, histSize, ranges, true, false);
1285  if (is_norm) {
1286  cv::normalize(hist, hist, 0, 1, cv::NORM_MINMAX, -1, cv::Mat());
1287  }
1288  }
1289 
1291  const pcl::PointCloud<PointT>::Ptr cloud,
1292  const pcl::PointCloud<pcl::Normal>::Ptr normals,
1293  cv::Mat &histogram, bool holistic) const
1294  {
1295  if (cloud->empty() || normals->empty()) {
1296  ROS_ERROR("-- ERROR: cannot compute FPFH");
1297  return;
1298  }
1299  pcl::FPFHEstimationOMP<PointT, pcl::Normal, pcl::FPFHSignature33> fpfh;
1300  fpfh.setInputCloud(cloud);
1301  fpfh.setInputNormals(normals);
1302  pcl::search::KdTree<PointT>::Ptr tree (new pcl::search::KdTree<PointT>);
1303  fpfh.setSearchMethod(tree);
1304  pcl::PointCloud<pcl::FPFHSignature33>::Ptr fpfhs(
1305  new pcl::PointCloud<pcl::FPFHSignature33> ());
1306  fpfh.setRadiusSearch(0.05);
1307  fpfh.compute(*fpfhs);
1308  const int hist_dim = 33;
1309  if (holistic) {
1310  histogram = cv::Mat::zeros(1, hist_dim, CV_32F);
1311  for (int i = 0; i < fpfhs->size(); i++) {
1312  for (int j = 0; j < hist_dim; j++) {
1313  histogram.at<float>(0, j) += fpfhs->points[i].histogram[j];
1314  }
1315  }
1316  } else {
1317  histogram = cv::Mat::zeros(
1318  static_cast<int>(fpfhs->size()), hist_dim, CV_32F);
1319  for (int i = 0; i < fpfhs->size(); i++) {
1320  for (int j = 0; j < hist_dim; j++) {
1321  histogram.at<float>(i, j) = fpfhs->points[i].histogram[j];
1322  }
1323  }
1324  }
1325  cv::normalize(histogram, histogram, 0, 1, cv::NORM_MINMAX, -1, cv::Mat());
1326  }
1327 
1328  std::vector<pcl::PointIndices::Ptr>
1330  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_mgs)
1331  {
1332  std::vector<pcl::PointIndices::Ptr> ret;
1333  for (int i = 0; i < indices_mgs->cluster_indices.size(); i++) {
1334  std::vector<int> indices = indices_mgs->cluster_indices[i].indices;
1335  pcl::PointIndices::Ptr pcl_indices (new pcl::PointIndices);
1336  pcl_indices->indices = indices;
1337  ret.push_back(pcl_indices);
1338  }
1339  return ret;
1340  }
1341 
1343  const geometry_msgs::PoseStamped::ConstPtr &pose_msg,
1344  PointXYZRPY &motion_displacement)
1345  {
1346  PointXYZRPY current_pose;
1347  current_pose.x = pose_msg->pose.position.x;
1348  current_pose.y = pose_msg->pose.position.y;
1349  current_pose.z = pose_msg->pose.position.z;
1350  current_pose.roll = pose_msg->pose.orientation.x;
1351  current_pose.pitch = pose_msg->pose.orientation.y;
1352  current_pose.yaw = pose_msg->pose.orientation.z;
1353  current_pose.weight = pose_msg->pose.orientation.w;
1354  this->tracker_pose_ = current_pose;
1355  this->current_pose_(0) = current_pose.x;
1356  this->current_pose_(1) = current_pose.y;
1357  this->current_pose_(2) = current_pose.z;
1358  this->current_pose_(3) = 0.0f;
1359  if (!std::isnan(current_pose.x) && !std::isnan(current_pose.y) &&
1360  !std::isnan(current_pose.z)) {
1361  if (!this->motion_history_.empty()) {
1362  int last_index = static_cast<int>(
1363  this->motion_history_.size()) - 1;
1364  motion_displacement.x = current_pose.x -
1365  this->motion_history_[last_index].x;
1366  motion_displacement.y = current_pose.y -
1367  this->motion_history_[last_index].y;
1368  motion_displacement.z = current_pose.z -
1369  this->motion_history_[last_index].z;
1370  motion_displacement.roll = current_pose.roll -
1371  this->motion_history_[last_index].roll;
1372  motion_displacement.pitch = current_pose.pitch -
1373  this->motion_history_[last_index].pitch;
1374  motion_displacement.yaw = current_pose.yaw -
1375  this->motion_history_[last_index].yaw;
1376  } else {
1377  this->motion_history_.push_back(current_pose);
1378  }
1379  } else {
1380  // pertubate with history error weight
1381  }
1382  }
1383 
1385  const pcl::PointCloud<PointT>::Ptr cloud,
1386  Eigen::Vector4f &centre) const
1387  {
1388  if (cloud->empty()) {
1389  ROS_ERROR("ERROR: empty cloud for centroid");
1390  centre = Eigen::Vector4f(-1, -1, -1, -1);
1391  return;
1392  }
1393  Eigen::Vector4f centroid;
1394  pcl::compute3DCentroid<PointT, float>(*cloud, centroid);
1395  if (!std::isnan(centroid(0)) && !std::isnan(centroid(1)) && !std::isnan(centroid(2))) {
1396  centre = centroid;
1397  }
1398  }
1399 
1401  const pcl::PointCloud<pcl::Normal>::Ptr normal,
1402  bool isnorm)
1403  {
1404  if (normal->empty()) {
1405  return Eigen::Vector4f(0, 0, 0, 0);
1406  }
1407  float x = 0.0f;
1408  float y = 0.0f;
1409  float z = 0.0f;
1410  int icounter = 0;
1411  for (int i = 0; i < normal->size(); i++) {
1412  if ((!std::isnan(normal->points[i].normal_x)) &&
1413  (!std::isnan(normal->points[i].normal_y)) &&
1414  (!std::isnan(normal->points[i].normal_z))) {
1415  x += normal->points[i].normal_x;
1416  y += normal->points[i].normal_y;
1417  z += normal->points[i].normal_z;
1418  icounter++;
1419  }
1420  }
1421  Eigen::Vector4f n_mean = Eigen::Vector4f(
1422  x/static_cast<float>(icounter),
1423  y/static_cast<float>(icounter),
1424  z/static_cast<float>(icounter),
1425  0.0f);
1426  if (isnorm) {
1427  n_mean.normalize();
1428  }
1429  return n_mean;
1430  }
1431 
1433  const pcl::PointCloud<PointT>::Ptr cloud,
1434  const Eigen::Vector4f centroid)
1435  {
1436  if (cloud->empty()) {
1437  ROS_ERROR("Empty input for computing Scatter Matrix");
1438  return;
1439  }
1440  const int rows = 3;
1441  const int cols = 3;
1442  Eigen::MatrixXf scatter_matrix = Eigen::Matrix3f::Zero(cols, rows);
1443  for (int i = 0; i < cloud->size(); i++) {
1444  Eigen::Vector3f de_mean = Eigen::Vector3f();
1445  de_mean(0) = cloud->points[i].x - centroid(0);
1446  de_mean(1) = cloud->points[i].y - centroid(1);
1447  de_mean(2) = cloud->points[i].z - centroid(2);
1448  Eigen::Vector3f t_de_mean = de_mean.transpose();
1449  for (int y = 0; y < rows; y++) {
1450  for (int x = 0; x < cols; x++) {
1451  scatter_matrix(y, x) += de_mean(y) * t_de_mean(x);
1452  }
1453  }
1454  }
1455  Eigen::EigenSolver<Eigen::MatrixXf> eigen_solver(scatter_matrix, true);
1456  // Eigen::complex<float> eigen_values;
1457  }
1458 
1460  const float dist, const float weight) {
1461  if (std::isnan(dist)) {
1462  return 0.0f;
1463  }
1464  return static_cast<float>(1/(1 + (weight * std::pow(dist, 2))));
1465  }
1466 
1467  pcl::PointXYZRGBNormal
1469  const Eigen::Vector4f &centroid,
1470  const Eigen::Vector4f &normal,
1471  const cv::Scalar color) {
1472  pcl::PointXYZRGBNormal pt;
1473  pt.x = centroid(0);
1474  pt.y = centroid(1);
1475  pt.z = centroid(2);
1476  pt.r = color.val[2];
1477  pt.g = color.val[1];
1478  pt.b = color.val[0];
1479  pt.normal_x = normal(0);
1480  pt.normal_y = normal(1);
1481  pt.normal_z = normal(2);
1482  return pt;
1483  }
1484 
1485  template<typename T>
1487  const PointXYZRPY &motion_displacement,
1488  Eigen::Matrix<T, 3, 3> &rotation)
1489  {
1490  tf::Quaternion tf_quaternion;
1491  tf_quaternion.setEulerZYX(motion_displacement.yaw,
1492  motion_displacement.pitch,
1493  motion_displacement.roll);
1494  Eigen::Quaternion<float> quaternion = Eigen::Quaternion<float>(
1495  tf_quaternion.w(), tf_quaternion.x(),
1496  tf_quaternion.y(), tf_quaternion.z());
1497  rotation.template block<3, 3>(0, 0) =
1498  quaternion.normalized().toRotationMatrix();
1499  }
1500 
1502  const std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> &
1503  supervoxel_clusters, const std::map<uint32_t, std::vector<uint32_t> > &
1504  adjacency_list, cv::Mat &histogram, const int feature_count)
1505  {
1506  if (supervoxel_clusters.empty() || adjacency_list.empty()) {
1507  std::cout << supervoxel_clusters.size() << "\t"
1508  << adjacency_list.size() << std::endl;
1509  ROS_ERROR("ERROR: empty data returing no local feautures");
1510  return;
1511  }
1512  float d_pi = 1.0f / (2.0f * static_cast<float> (M_PI));
1513  histogram = cv::Mat::zeros(1, this->bin_size_ * feature_count, CV_32F);
1514  for (std::map<uint32_t, std::vector<uint32_t> >::const_iterator it =
1515  adjacency_list.begin(); it != adjacency_list.end(); it++) {
1516  pcl::Supervoxel<PointT>::Ptr supervoxel =
1517  supervoxel_clusters.at(it->first);
1518  Eigen::Vector4f c_normal = this->cloudMeanNormal(supervoxel->normals_);
1519  std::map<uint32_t, Eigen::Vector4f> cache_normals;
1520  int icounter = 0;
1521  for (std::vector<uint32_t>::const_iterator itr = it->second.begin();
1522  itr != it->second.end(); itr++) {
1523  pcl::Supervoxel<PointT>::Ptr neighbor_supervoxel =
1524  supervoxel_clusters.at(*itr);
1525  Eigen::Vector4f n_normal = this->cloudMeanNormal(
1526  neighbor_supervoxel->normals_);
1527  float alpha;
1528  float phi;
1529  float theta;
1530  float distance;
1531  pcl::computePairFeatures(
1532  supervoxel->centroid_.getVector4fMap(), c_normal,
1533  neighbor_supervoxel->centroid_.getVector4fMap(),
1534  n_normal, alpha, phi, theta, distance);
1535  int bin_index[feature_count];
1536  bin_index[0] = static_cast<int>(
1537  std::floor(this->bin_size_ * ((alpha + M_PI) * d_pi)));
1538  bin_index[1] = static_cast<int>(
1539  std::floor(this->bin_size_ * ((phi + 1.0f) * 0.5f)));
1540  bin_index[2] = static_cast<int>(
1541  std::floor(this->bin_size_ * ((theta + 1.0f) * 0.5f)));
1542  for (int i = 0; i < feature_count; i++) {
1543  if (bin_index[i] < 0) {
1544  bin_index[i] = 0;
1545  }
1546  if (bin_index[i] >= bin_size_) {
1547  bin_index[i] = bin_size_ - sizeof(char);
1548  }
1549  // h_index += h_p + bin_index[i];
1550  // h_p *= this->bin_size_;
1551  histogram.at<float>(
1552  0, bin_index[i] + (i * this->bin_size_)) += 1;
1553  }
1554  cache_normals[*itr] = n_normal;
1555  icounter++;
1556  }
1557  for (std::vector<uint32_t>::const_iterator itr = it->second.begin();
1558  itr != it->second.end(); itr++) {
1559  cache_normals.find(*itr)->second;
1560  for (std::vector<uint32_t>::const_iterator itr_in =
1561  it->second.begin(); itr_in != it->second.end(); itr_in++) {
1562  if (*itr != *itr_in) {
1563  float alpha;
1564  float phi;
1565  float theta;
1566  float distance;
1567  pcl::computePairFeatures(
1568  supervoxel_clusters.at(*itr)->centroid_.getVector4fMap(),
1569  cache_normals.find(*itr)->second, supervoxel_clusters.at(
1570  *itr_in)->centroid_.getVector4fMap(),
1571  cache_normals.find(*itr_in)->second,
1572  alpha, phi, theta, distance);
1573  int bin_index[feature_count];
1574  bin_index[0] = static_cast<int>(
1575  std::floor(this->bin_size_ * ((alpha + M_PI) * d_pi)));
1576  bin_index[1] = static_cast<int>(
1577  std::floor(this->bin_size_ * ((phi + 1.0f) * 0.5f)));
1578  bin_index[2] = static_cast<int>(
1579  std::floor(this->bin_size_ * ((theta + 1.0f) * 0.5f)));
1580  for (int i = 0; i < feature_count; i++) {
1581  if (bin_index[i] < 0) {
1582  bin_index[i] = 0;
1583  }
1584  if (bin_index[i] >= bin_size_) {
1585  bin_index[i] = bin_size_ - sizeof(char);
1586  }
1587  histogram.at<float>(
1588  0, bin_index[i] + (i * this->bin_size_)) += 1;
1589  }
1590  }
1591  }
1592  }
1593  cv::normalize(
1594  histogram, histogram, 0, 1, cv::NORM_MINMAX, -1, cv::Mat());
1595  }
1596  }
1597 
1598 
1600  const pcl::PointCloud<PointT>::Ptr cloud)
1601  {
1602  if (cloud->empty()) {
1603  ROS_ERROR("ERROR! Input Cloud is Empty");
1604  return -1.0f;
1605  }
1606  Eigen::Vector4f pivot_pt;
1607  pcl::compute3DCentroid<PointT, float>(*cloud, pivot_pt);
1608  Eigen::Vector4f max_pt;
1609  pcl::getMaxDistance<PointT>(*cloud, pivot_pt, max_pt);
1610  pivot_pt(3) = 0.0f;
1611  max_pt(3) = 0.0f;
1612  float dist = static_cast<float>(pcl::distances::l2(max_pt, pivot_pt));
1613  return (dist);
1614  }
1615 
1617  pcl::PointCloud<PointT>::Ptr cloud,
1618  const Eigen::Vector4f tracker_position,
1619  const ModelsPtr template_model,
1620  const float scaling_factor)
1621  {
1622  if (cloud->empty() || template_model->empty()) {
1623  ROS_ERROR("ERROR! Input data is empty is Empty");
1624  return false;
1625  }
1626  pcl::PointCloud<PointT>::Ptr template_cloud(new pcl::PointCloud<PointT>);
1627  for (int i = 0; i < template_model->size(); i++) {
1628  *template_cloud = *template_cloud + *(
1629  template_model->operator[](i).cluster_cloud);
1630  }
1631  float filter_distance = this->templateCloudFilterLenght(template_cloud);
1632  filter_distance *= scaling_factor;
1633  if (filter_distance < 0.05f) {
1634  return false;
1635  }
1636  pcl::PointCloud<PointT>::Ptr cloud_filter(new pcl::PointCloud<PointT>);
1637  pcl::PassThrough<PointT> pass;
1638  pass.setInputCloud(cloud);
1639  pass.setFilterFieldName("x");
1640  float min_x = tracker_position(0) - filter_distance;
1641  float max_x = tracker_position(0) + filter_distance;
1642  pass.setFilterLimits(min_x, max_x);
1643  pass.filter(*cloud_filter);
1644  pass.setInputCloud(cloud_filter);
1645  pass.setFilterFieldName("y");
1646  float min_y = tracker_position(1) - filter_distance;
1647  float max_y = tracker_position(1) + filter_distance;
1648  pass.setFilterLimits(min_y, max_y);
1649  pass.filter(*cloud_filter);
1650  pass.setInputCloud(cloud_filter);
1651  pass.setFilterFieldName("z");
1652  float min_z = tracker_position(2) - filter_distance;
1653  float max_z = tracker_position(2) + filter_distance;
1654  pass.setFilterLimits(min_z, max_z);
1655  pass.filter(*cloud_filter);
1656  if (cloud_filter->empty()) {
1657  return false;
1658  }
1659  cloud->empty();
1660  pcl::copyPointCloud<PointT, PointT>(*cloud_filter, *cloud);
1661  return true;
1662  }
1663 
1665  const ModelsPtr &obj_ref,
1666  ModelsPtr trans_models,
1667  const Eigen::Affine3f &transform_model)
1668  {
1669  if (obj_ref->empty()) {
1670  ROS_ERROR("ERROR! No Object Model to Transform");
1671  return;
1672  }
1673  for (int i = 0; i < obj_ref->size(); i++) {
1674  pcl::PointCloud<PointT>::Ptr trans_cloud(
1675  new pcl::PointCloud<PointT>);
1676  pcl::transformPointCloud(*(obj_ref->operator[](i).cluster_cloud),
1677  *trans_cloud, transform_model);
1678  Eigen::Vector4f trans_centroid = Eigen::Vector4f();
1679  pcl::compute3DCentroid<PointT, float>(
1680  *trans_cloud, trans_centroid);
1681  trans_models->push_back(obj_ref->operator[](i));
1682  trans_models->operator[](i).cluster_cloud = trans_cloud;
1683  trans_models->operator[](i).cluster_centroid = trans_centroid;
1684  }
1685  }
1686 
1688  pcl::PointCloud<PointT>::Ptr cloud,
1689  const ModelsPtr background_reference,
1690  const float threshold)
1691  {
1692  if (cloud->empty() || background_reference->empty()) {
1693  ROS_ERROR("ERROR! EMPTY DATA FOR BOUNDING BOX CLOUD");
1694  return;
1695  }
1696  ModelsPtr tmp_model(new Models);
1697  this->processInitCloud(cloud, tmp_model);
1698  pcl::PointCloud<PointT>::Ptr tmp_cloud(new pcl::PointCloud<PointT>);
1699  for (int i = 0; i < tmp_model->size(); i++) {
1700  Eigen::Vector4f surfel_centroid = Eigen::Vector4f();
1701  surfel_centroid = tmp_model->operator[](i).cluster_centroid;
1702  surfel_centroid(3) = 0.0f;
1703  float surfel_dist = static_cast<float>(
1704  pcl::distances::l2(surfel_centroid, current_pose_));
1705  if (surfel_dist < (this->previous_distance_ * growth_rate_)) {
1706  float probability = 0.0f;
1707  for (int j = 0; j < background_reference->size(); j++) {
1708  ReferenceModel *r_mod = new ReferenceModel;
1709  float prob = this->targetCandidateToReferenceLikelihood<float>(
1710  tmp_model->operator[](i),
1711  background_reference->operator[](j).cluster_cloud,
1712  background_reference->operator[](j).cluster_normals,
1713  background_reference->operator[](j).cluster_centroid,
1714  r_mod);
1715  if (prob > probability) {
1716  probability = prob;
1717  }
1718  }
1719  if (probability < 0.60f) {
1720  *tmp_cloud = *tmp_cloud + *(
1721  tmp_model->operator[](i).cluster_cloud);
1722  } else {
1723  this->object_reference_->push_back(tmp_model->operator[](i));
1724  }
1725  }
1726  }
1727  if (tmp_cloud->size() > (static_cast<int>(cloud->size() / 4))) {
1728  cloud->clear();
1729  pcl::copyPointCloud<PointT, PointT>(*tmp_cloud, *cloud);
1730  }
1731  }
1732 
1733  template<typename T, typename U, typename V>
1735  T v, U vmin, V vmax)
1736  {
1737  cv::Scalar c = cv::Scalar(0.0, 0.0, 0.0);
1738  T dv;
1739  if (v < vmin)
1740  v = vmin;
1741  if (v > vmax)
1742  v = vmax;
1743  dv = vmax - vmin;
1744  if (v < (vmin + 0.25 * dv)) {
1745  c.val[0] = 0;
1746  c.val[1] = 4 * (v - vmin) / dv;
1747  } else if (v < (vmin + 0.5 * dv)) {
1748  c.val[0] = 0;
1749  c.val[2] = 1 + 4 * (vmin + 0.25 * dv - v) / dv;
1750  } else if (v < (vmin + 0.75 * dv)) {
1751  c.val[0] = 4 * (v - vmin - 0.5 * dv) / dv;
1752  c.val[2] = 0;
1753  } else {
1754  c.val[1] = 1 + 4 * (vmin + 0.75 * dv - v) / dv;
1755  c.val[2] = 0;
1756  }
1757  return(c);
1758  }
1759 
1761  const pcl::PointCloud<PointT>::Ptr cloud,
1762  std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr > &supervoxel_clusters,
1763  std::multimap<uint32_t, uint32_t> &supervoxel_adjacency,
1764  const float seed_resolution)
1765  {
1766  if (cloud->empty() || seed_resolution <= 0.0f) {
1767  ROS_ERROR("ERROR: Supervoxel input cloud empty...\n Incorrect Seed");
1768  return;
1769  }
1770  boost::mutex::scoped_lock lock(mutex_);
1771  pcl::SupervoxelClustering<PointT> super(
1773  static_cast<double>(seed_resolution),
1774  use_transform_);
1775  super.setInputCloud(cloud);
1776  super.setColorImportance(color_importance_);
1777  super.setSpatialImportance(spatial_importance_);
1778  super.setNormalImportance(normal_importance_);
1779  supervoxel_clusters.clear();
1780  super.extract(supervoxel_clusters);
1781  super.getSupervoxelAdjacency(supervoxel_adjacency);
1782  }
1783 
1785  const pcl::PointCloud<PointT>::Ptr cloud,
1786  std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr > &supervoxel_clusters,
1787  std::multimap<uint32_t, uint32_t> &supervoxel_adjacency)
1788  {
1789  if (cloud->empty()) {
1790  ROS_ERROR("ERROR: Supervoxel input cloud empty...");
1791  return;
1792  }
1793  boost::mutex::scoped_lock lock(mutex_);
1794  pcl::SupervoxelClustering<PointT> super(voxel_resolution_,
1796  use_transform_);
1797  super.setInputCloud(cloud);
1798  super.setColorImportance(color_importance_);
1799  super.setSpatialImportance(spatial_importance_);
1800  super.setNormalImportance(normal_importance_);
1801  supervoxel_clusters.clear();
1802  super.extract(supervoxel_clusters);
1803  super.getSupervoxelAdjacency(supervoxel_adjacency);
1804  }
1805 
1807  const std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr> supervoxel_clusters,
1808  sensor_msgs::PointCloud2 &ros_cloud,
1809  jsk_recognition_msgs::ClusterPointIndices &ros_indices,
1810  const std_msgs::Header &header)
1811  {
1812  pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
1813  std::vector<pcl::PointIndices> all_indices;
1814  for (std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr >::const_iterator
1815  it = supervoxel_clusters.begin();
1816  it != supervoxel_clusters.end();
1817  ++it) {
1818  pcl::Supervoxel<PointT>::Ptr super_voxel = it->second;
1819  pcl::PointCloud<PointT>::Ptr super_voxel_cloud = super_voxel->voxels_;
1820  pcl::PointIndices indices;
1821  for (size_t i = 0; i < super_voxel_cloud->size(); i++) {
1822  indices.indices.push_back(i + output->points.size());
1823  }
1824  all_indices.push_back(indices);
1825  *output = *output + *super_voxel_cloud;
1826  }
1827  ros_indices.cluster_indices.clear();
1828  ros_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
1829  all_indices, header);
1830  ros_cloud.data.clear();
1831  pcl::toROSMsg(*output, ros_cloud);
1832  ros_indices.header = header;
1833  ros_cloud.header = header;
1834  }
1835 
1837  const jsk_recognition_msgs::ClusterPointIndices &sv_indices,
1838  const std::vector<uint32_t> &tdp_list,
1839  jsk_recognition_msgs::ClusterPointIndices &ros_indices)
1840  {
1841  ros_indices.cluster_indices.clear();
1842  for (std::vector<uint32_t>::const_iterator it = tdp_list.begin();
1843  it != tdp_list.end(); it++) {
1844  ros_indices.cluster_indices.push_back(sv_indices.cluster_indices[*it]);
1845  }
1846  ros_indices.header = sv_indices.header;
1847  }
1848 
1850  Config &config, uint32_t level)
1851  {
1852  boost::mutex::scoped_lock lock(mutex_);
1853  this->color_importance_ = config.color_importance;
1854  this->spatial_importance_ = config.spatial_importance;
1855  this->normal_importance_ = config.normal_importance;
1856  this->voxel_resolution_ = config.voxel_resolution;
1857  this->seed_resolution_ = config.seed_resolution;
1858  this->use_transform_ = config.use_transform;
1859 
1860  this->min_cluster_size_ = static_cast<int>(config.min_cluster_size);
1861  this->threshold_ = static_cast<float>(config.threshold);
1862  this->bin_size_ = static_cast<int>(config.bin_size);
1863  this->eps_distance_ = static_cast<float>(config.eps_distance);
1864  this->eps_min_samples_ = static_cast<float>(config.eps_min_samples);
1865  this->vfh_scaling_ = static_cast<float>(config.vfh_scaling);
1866  this->color_scaling_ = static_cast<float>(config.color_scaling);
1867  this->structure_scaling_ = static_cast<float>(config.structure_scaling);
1868  this->update_tracker_reference_ = config.update_tracker_reference;
1869  this->update_filter_template_ = config.update_filter_template;
1870  this->history_window_size_ = static_cast<int>(config.history_window_size);
1871  }
1872 }
1873 
void publishSupervoxel(const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr >, sensor_msgs::PointCloud2 &, jsk_recognition_msgs::ClusterPointIndices &, const std_msgs::Header &)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
void estimatedPFPose(const geometry_msgs::PoseStamped::ConstPtr &, PointXYZRPY &)
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_bkgd_cloud_
Eigen::Vector4f cloudMeanNormal(const pcl::PointCloud< pcl::Normal >::Ptr, bool=true)
void publish(const boost::shared_ptr< M > &message) const
void filterCloudForBoundingBoxViz(pcl::PointCloud< PointT >::Ptr, const ModelsPtr, const float=0.6f)
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_pose_
end
void transformModelPrimitives(const ModelsPtr &, ModelsPtr, const Eigen::Affine3f &)
pointer T
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_obj_pose_
void processInitCloud(const pcl::PointCloud< PointT >::Ptr, ModelsPtr)
jsk_pcl_ros::TargetAdaptiveTrackingConfig Config
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_obj_cloud_
alpha
void getRotationMatrixFromRPY(const PointXYZRPY &, Eigen::Matrix< T, 3, 3 > &)
std::map< uint32_t, std::vector< uint32_t > > adjacent_voxel_indices
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
TFSIMD_FORCE_INLINE const tfScalar & getY() const
void computeScatterMatrix(const pcl::PointCloud< PointT >::Ptr, const Eigen::Vector4f)
T dot(T *pf1, T *pf2, int length)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
T localVoxelConvexityLikelihood(Eigen::Vector4f, Eigen::Vector4f, Eigen::Vector4f, Eigen::Vector4f)
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
#define ROS_WARN(...)
ros::Publisher advertise(ros::NodeHandle &nh, std::string topic, int queue_size)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
struct svm_problem prob
pcl::tracking::ParticleXYZRPY PointXYZRPY
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void output(int index, double value)
void backgroundReferenceLikelihood(const ModelsPtr, const ModelsPtr, std::map< uint32_t, float >)
#define M_PI
#define ROS_INFO(...)
void computeLocalPairwiseFeautures(const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr > &, const std::map< uint32_t, std::vector< uint32_t > > &, cv::Mat &, const int=3)
boost::shared_ptr< ros::NodeHandle > pnh_
void computePointFPFH(const pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, cv::Mat &, bool=true) const
pcl::PointXYZRGBNormal convertVector4fToPointXyzRgbNormal(const Eigen::Vector4f &, const Eigen::Vector4f &, const cv::Scalar)
void computeCloudClusterRPYHistogram(const pcl::PointCloud< PointT >::Ptr, const pcl::PointCloud< pcl::Normal >::Ptr, cv::Mat &) const
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::TargetAdaptiveTracking, nodelet::Nodelet)
void sendTransform(const StampedTransform &transform)
std::vector< ReferenceModel > Models
begin
void setEulerZYX(const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll) __attribute__((deprecated))
virtual std::vector< pcl::PointIndices::Ptr > clusterPointIndicesToPointIndices(const jsk_recognition_msgs::ClusterPointIndicesConstPtr &)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
std::vector< PCLIndicesMsg > convertToROSPointIndices(const std::vector< pcl::PointIndices::Ptr > cluster_indices, const std_msgs::Header &header)
void supervoxelSegmentation(const pcl::PointCloud< PointT >::Ptr, std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr > &, std::multimap< uint32_t, uint32_t > &)
void voxelizeAndProcessPointCloud(const pcl::PointCloud< PointT >::Ptr cloud, const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr > &, const std::multimap< uint32_t, uint32_t > &, std::vector< AdjacentInfo > &, ModelsPtr &, bool=true, bool=true, bool=true, bool=false)
br
T targetCandidateToReferenceLikelihood(const ReferenceModel &, const pcl::PointCloud< PointT >::Ptr, const pcl::PointCloud< pcl::Normal >::Ptr, const Eigen::Vector4f &, ReferenceModel *=NULL)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
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)
Quaternion getRotation() const
virtual void objInitCallback(const sensor_msgs::PointCloud2::ConstPtr &, const sensor_msgs::PointCloud2::ConstPtr &, const geometry_msgs::PoseStamped::ConstPtr &)
void estimatePointCloudNormals(const pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, T=0.05f, bool=false) const
void computeColorHistogram(const pcl::PointCloud< PointT >::Ptr, cv::Mat &, const int=16, const int=16, bool=true) const
pcl::PointCloud< PointT >::Ptr previous_template_
TFSIMD_FORCE_INLINE const tfScalar & getX() const
static Time now()
static const Transform & getIdentity()
virtual void callback(const sensor_msgs::PointCloud2::ConstPtr &, const geometry_msgs::PoseStamped::ConstPtr &)
int theta
void targetDescriptiveSurfelsIndices(const jsk_recognition_msgs::ClusterPointIndices &, const std::vector< uint32_t > &, jsk_recognition_msgs::ClusterPointIndices &)
c
void targetDescriptiveSurfelsEstimationAndUpdate(pcl::PointCloud< PointT >::Ptr, const Eigen::Affine3f &, const TargetAdaptiveTracking::PointXYZRPY &, const std_msgs::Header)
void processVoxelForReferenceModel(const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr >, const std::multimap< uint32_t, uint32_t >, const uint32_t, TargetAdaptiveTracking::ReferenceModel *)
cloud
boost::shared_ptr< message_filters::Synchronizer< ObjectSyncPolicy > > obj_sync_
#define ROS_ERROR(...)
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
double distance(const urdf::Pose &transform)
float templateCloudFilterLenght(const pcl::PointCloud< PointT >::Ptr)
bool filterPointCloud(pcl::PointCloud< PointT >::Ptr, const Eigen::Vector4f, const ModelsPtr, const float)
void compute3DCentroids(const pcl::PointCloud< PointT >::Ptr, Eigen::Vector4f &) const


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47