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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45