11 DiagnosticNodelet(
"target_adaptive_tracking"),
19 new pcl::PointCloud<PointT>);
36 DiagnosticNodelet::onInit();
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"));
42 srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
43 dynamic_reconfigure::Server<Config>::CallbackType
f =
47 this->
pub_cloud_ = advertise<sensor_msgs::PointCloud2>(
48 *pnh_,
"/target_adaptive_tracking/output/cloud", 1);
53 this->
pub_templ_ = advertise<sensor_msgs::PointCloud2>(
54 *pnh_,
"/selected_pointcloud", 1);
57 jsk_recognition_msgs::ClusterPointIndices>(
58 *pnh_,
"/target_adaptive_tracking/supervoxel/indices", 1);
60 this->
pub_scloud_ = advertise<sensor_msgs::PointCloud2>(
61 *pnh_,
"/target_adaptive_tracking/supervoxel/cloud", 1);
63 this->
pub_normal_ = advertise<sensor_msgs::PointCloud2>(
64 *pnh_,
"/target_adaptive_tracking/output/normal", 1);
66 this->
pub_tdp_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
67 *pnh_,
"/target_adaptive_tracking/supervoxel/tdp_indices", 1);
69 this->
pub_inliers_ = advertise<sensor_msgs::PointCloud2>(
70 *pnh_,
"/target_adaptive_tracking/output/inliers", 1);
73 *pnh_,
"/target_adaptive_tracking/output/centroids", 1);
75 this->
pub_pose_ = advertise<geometry_msgs::PoseStamped>(
76 *pnh_,
"/target_adaptive_tracking/output/object_pose", 1);
78 this->
pub_prob_ = advertise<sensor_msgs::PointCloud2>(
79 *pnh_,
"/target_adaptive_tracking/output/probability_map", 1);
101 this->
sync_->registerCallback(
115 const sensor_msgs::PointCloud2::ConstPtr &cloud_msg,
116 const sensor_msgs::PointCloud2::ConstPtr &bkgd_msg,
117 const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
119 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
121 pcl::PointCloud<PointT>::Ptr bkgd_cloud (
new pcl::PointCloud<PointT>);
124 ROS_WARN(
"Object is re-initalized! stopping & reseting...");
126 if (!
cloud->empty() && !bkgd_cloud->empty()) {
140 sensor_msgs::PointCloud2 ros_templ;
142 ros_templ.header = cloud_msg->header;
148 const pcl::PointCloud<PointT>::Ptr cloud,
151 if (
cloud->empty()) {
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);
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));
170 seed_resolution += seed_factor;
175 const sensor_msgs::PointCloud2::ConstPtr &cloud_msg,
176 const geometry_msgs::PoseStamped::ConstPtr &pose_msg) {
179 ROS_WARN(
"No Model To Track Selected");
182 ROS_INFO(
"\n\n\033[34m------------RUNNING CALLBACK-------------\033[0m");
186 std::cout <<
"Motion Displacement: " << motion_displacement << std::endl;
188 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
193 Eigen::Affine3f transform_model = Eigen::Affine3f::Identity();
199 ROS_ERROR(
"CANNOT TRANSFORM SOURCE AND TARGET FRAMES");
205 transform_model = Eigen::Affine3f::Identity();
206 transform_model.translation() <<
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);
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);
236 pose_msg->pose.orientation.x, pose_msg->pose.orientation.y,
237 pose_msg->pose.orientation.z, pose_msg->pose.orientation.w);
242 Eigen::Affine3f transform_reference = Eigen::Affine3f::Identity();
243 const int motion_hist_index =
static_cast<int>(
245 transform_reference.translation() <<
249 Eigen::Affine3f transformation_matrix = transform_model *
250 transform_reference.inverse();
255 cloud, transformation_matrix, motion_displacement,
259 std::cout <<
"Processing Time: " <<
end -
begin << std::endl;
263 update_transform, cloud_msg->header.stamp,
264 cloud_msg->header.frame_id,
"object_pose"));
267 geometry_msgs::PoseStamped update_pose;
269 update_pose.header.stamp = cloud_msg->header.stamp;
273 sensor_msgs::PointCloud2 ros_cloud;
275 ros_cloud.header.stamp = cloud_msg->header.stamp;
281 const pcl::PointCloud<PointT>::Ptr cloud,
282 const std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> &
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)
289 if (
cloud->empty() || supervoxel_clusters.empty()) {
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++) {
298 ref_model.
flag =
true;
300 uint32_t supervoxel_label = label_itr->first;
301 pcl::Supervoxel<PointT>::Ptr supervoxel =
302 supervoxel_clusters.at(supervoxel_label);
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);
320 supervoxel_list.push_back(a_info);
324 new pcl::PointCloud<PointT>);
328 new pcl::PointCloud<pcl::Normal>);
343 supervoxel->centroid_.getVector4fMap();
345 ref_model.
flag =
false;
347 models->push_back(ref_model);
350 std::cout <<
"Cloud Voxel size: " << models->size() << std::endl;
354 for (
int i = 0;
i < models->size();
i++) {
357 models->operator[](
i).cluster_neigbors.adjacent_voxel_indices,
358 models->operator[](
i).neigbour_pfh);
364 pcl::PointCloud<PointT>::Ptr cloud,
365 const Eigen::Affine3f &transformation_matrix,
367 const std_msgs::Header
header)
369 if (
cloud->empty()) {
370 ROS_ERROR(
"ERROR: Global Layer Input Empty");
373 pcl::PointCloud<PointT>::Ptr n_cloud(
new pcl::PointCloud<PointT>);
375 std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> supervoxel_clusters;
376 std::multimap<uint32_t, uint32_t> supervoxel_adjacency;
379 supervoxel_adjacency);
380 Eigen::Matrix<float, 3, 3> rotation_matrix;
381 rotation_matrix = transformation_matrix.rotation();
383 std::vector<AdjacentInfo> supervoxel_list;
386 cloud, supervoxel_clusters, supervoxel_adjacency,
387 supervoxel_list, t_voxels,
true,
false,
true);
388 Models target_voxels = *t_voxels;
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) {
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));
412 if (nearest_index != -1) {
413 matching_indices[j] = nearest_index;
416 obj_ref[j].centroid_distance(0) = obj_ref[j].cluster_centroid(0) -
418 obj_ref[j].centroid_distance(1) = obj_ref[j].cluster_centroid(1) -
420 obj_ref[j].centroid_distance(2) = obj_ref[j].cluster_centroid(2) -
424 ROS_INFO(
"\033[35m MATCHING THROUGH NIEGBOUR SEARCH \033[0m");
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;
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);
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);
461 float dist_phf =
static_cast<float>(
462 cv::compareHist(obj_ref[itr->first].neigbour_pfh,
463 histogram_phf, CV_COMP_BHATTACHARYYA));
467 for (std::vector<uint32_t>::iterator it =
468 neigb.find(v_ind)->second.begin();
469 it != neigb.find(v_ind)->second.end(); it++) {
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(),
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;
485 list_adj.push_back(adjacent_itr->second);
487 local_adjacency[*it] = list_adj;
490 supervoxel_clusters, local_adjacency, local_phf);
494 float dist_phf =
static_cast<float>(
495 cv::compareHist(obj_ref[itr->first].neigbour_pfh,
496 local_phf, CV_COMP_BHATTACHARYYA));
498 local_weight = phf_prob;
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()));
511 voxel_model = voxel_mod;
514 all_probabilites.insert(
515 std::pair<uint32_t, float>(bm_index,
probability));
517 Eigen::Vector3f estimated_position = supervoxel_clusters.at(
518 bm_index)->centroid_.getVector3fMap() - rotation_matrix *
520 Eigen::Vector4f estimated_pos = Eigen::Vector4f(
521 estimated_position(0), estimated_position(1),
522 estimated_position(2), 0.0
f);
523 float match_dist =
static_cast<float>(
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);
538 pt.x = estimated_position(0);
539 pt.y = estimated_position(1);
540 pt.z = estimated_position(2);
542 est_centroid_cloud->push_back(pt);
545 ROS_WARN(
"-- Outlier not added...");
548 obj_ref[itr->first].history_window.push_back(0);
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++) {
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);
566 sensor_msgs::PointCloud2 ros_prob;
571 pcl::PointCloud<PointT>::Ptr inliers(
new pcl::PointCloud<PointT>);
572 std::vector<uint32_t> outlier_index;
574 ROS_INFO(
"\033[35m OUTLIER FILTERING VIA BACKPROJECTION \033[0m");
575 Eigen::Matrix<float, 3, 3> inv_rotation_matrix = rotation_matrix.inverse();
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();
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.0
f);
597 float matching_dist =
static_cast<float>(
601 pt.x = abs_position(0);
602 pt.y = abs_position(1);
603 pt.z = abs_position(2);
605 best_match_index.push_back(*it);
612 inliers->push_back(pt);
622 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr centroid_normal(
623 new pcl::PointCloud<pcl::PointXYZRGBNormal>);
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();
631 supervoxel_clusters.at(*it)->normals_);
632 centroid_normal->push_back(
634 c_centroid, c_normal, cv::Scalar(0, 0, 255)));
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;
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();
652 supervoxel_clusters.at(*it)->normals_);
654 centroid_normal->push_back(
656 c_centroid, c_normal, cv::Scalar(255, 0, 0)));
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;
668 if (!supervoxel_clusters.at(itr->second)->voxels_->empty() &&
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();
676 supervoxel_clusters.at(itr->second)->normals_);
678 float>(c_centroid, c_normal, n_centroid, n_normal);
679 if (convx_weight > 0.0
f) {
680 *output = *output + *supervoxel_clusters.at(
681 itr->second)->voxels_;
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() *
693 float rev_match_dist =
static_cast<float>(
694 pcl::distances::l2(convx_centroid,
696 j).cluster_centroid));
698 float convx_dist =
static_cast<float>(
702 CV_COMP_BHATTACHARYYA));
703 float convx_prob = std::exp(
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");
725 convex_local_voxels[itr->second] = ref_model;
726 centroid_normal->push_back(
728 n_centroid, n_normal, cv::Scalar(0, 255, 0)));
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;
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;
755 if (is_common_neigh) {
760 if (common_neigbour_index > 0) {
761 Eigen::Vector4f n_centroid_b = supervoxel_clusters.at(
762 itr->second)->centroid_.getVector4fMap();
764 supervoxel_clusters.at(itr->second)->normals_);
765 Eigen::Vector4f n_centroid_c = supervoxel_clusters.at(
766 common_neigbour_index)->centroid_.getVector4fMap();
768 supervoxel_clusters.at(common_neigbour_index)->normals_);
770 float>(c_centroid, c_normal, n_centroid_b, n_normal_b);
772 float>(c_centroid, c_normal, n_centroid_c, n_normal_c);
774 float>(n_centroid_b, n_normal_b, n_centroid_c,
776 if (convx_weight_ab != 0.0
f &&
777 convx_weight_ac != 0.0
f &&
778 convx_weight_bc != 0.0
f) {
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);
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() *
794 float rev_match_dist =
static_cast<float>(
795 pcl::distances::l2(convx_centroid,
797 j).cluster_centroid));
799 float convx_dist =
static_cast<float>(
802 j).cluster_vfh_hist, CV_COMP_BHATTACHARYYA));
803 float convx_prob = std::exp(
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)));
821 convex_local_voxels[itr->second] = ref_model;
830 *output = *output + *supervoxel_clusters.at(*it)->voxels_;
832 for (
int i = 0;
i < convex_ok.size();
i++) {
833 best_match_index.push_back(convex_ok[
i]);
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(
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(
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++;
897 for (std::map<int, ReferenceModel>::iterator it =
898 matching_surfels.begin(); it != matching_surfels.end(); it++) {
901 for (std::map<uint32_t, ReferenceModel*>::iterator it =
902 convex_local_voxels.begin(); it != convex_local_voxels.begin();
912 tmp_model->push_back(renew_model);
914 std::cout <<
"\033[033m OUTDATED MODEL \033[0m" << std::endl;
923 ROS_WARN(
"TRACKING MODEL CURRENTLY SET TO STATIC\n");
925 template_cloud->clear();
927 float argmax_lenght = 0.0f;
929 Eigen::Vector4f surfel_centroid = Eigen::Vector4f();
932 surfel_centroid(3) = 0.0f;
933 float surfel_dist =
static_cast<float>(
935 if (surfel_dist > argmax_lenght) {
936 argmax_lenght = surfel_dist;
942 float prob = this->targetCandidateToReferenceLikelihood<float>(
944 this->background_reference_->operator[](j).cluster_cloud,
945 this->background_reference_->operator[](j).cluster_normals,
946 this->background_reference_->operator[](j).cluster_centroid,
953 *template_cloud = *template_cloud + *(
957 ROS_INFO(
"\033[35m SURFEL REMOVED AS BACKGRND \033[0m");
960 ROS_INFO(
"\033[35m SURFEL REMOVED \033[0m]");
969 this->previous_distance_ = argmax_lenght;
974 if (tmp_counter < 1) {
975 template_cloud->clear();
978 ROS_INFO(
"\033[34m UPDATING INFO...\033[0m");
984 std::cout <<
"\033[038m REFERENCE INFO \033[0m"
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);
993 sensor_msgs::PointCloud2 ros_templ;
995 ros_templ.header =
header;
999 std::vector<pcl::PointIndices> all_indices;
1000 all_indices.push_back(tdp_ind);
1001 jsk_recognition_msgs::ClusterPointIndices tdp_indices;
1004 tdp_indices.header =
header;
1008 sensor_msgs::PointCloud2 ros_svcloud;
1009 jsk_recognition_msgs::ClusterPointIndices ros_svindices;
1011 supervoxel_clusters, ros_svcloud, ros_svindices,
header);
1016 sensor_msgs::PointCloud2 ros_inliers;
1018 ros_inliers.header =
header;
1022 sensor_msgs::PointCloud2 ros_centroids;
1024 ros_centroids.header =
header;
1028 sensor_msgs::PointCloud2 rviz_normal;
1030 rviz_normal.header =
header;
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,
1040 if (supervoxel_clusters.empty() || supervoxel_adjacency.empty()) {
1041 ROS_ERROR(
"ERROR: empty data for updating voxel ref model");
1044 if (supervoxel_clusters.at(
1045 match_index)->voxels_->size() > this->min_cluster_size_) {
1046 ref_model->
flag =
false;
1048 match_index)->voxels_;
1050 match_index)->normals_;
1052 match_index)->centroid_.getVector4fMap();
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);
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);
1081 ref_model->
flag =
true;
1088 const pcl::PointCloud<PointT>::Ptr cloud,
1089 const pcl::PointCloud<pcl::Normal>::Ptr normal,
1090 const Eigen::Vector4f ¢roid,
1093 if (
cloud->empty() || normal->empty()) {
1100 T dist_vfh =
static_cast<T>(
1101 cv::compareHist(vfh_hist,
1103 CV_COMP_BHATTACHARYYA));
1104 T dist_col =
static_cast<T>(
1105 cv::compareHist(color_hist,
1107 CV_COMP_BHATTACHARYYA));
1110 bool convex_weight =
false;
1111 if (convex_weight) {
1113 Eigen::Vector4f n_centroid = centroid;
1117 float convx_prob = this->localVoxelConvexityLikelihood<float>(
1118 c_centroid, c_normal, n_centroid, n_normal);
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;
1134 n_centroid(3) = 0.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));
1144 if (std::isnan(weight)) {
1154 std::map<uint32_t, float> max_prob)
1156 if (background_reference->empty() || target_voxels->empty()) {
1159 for (
int j = 0; j < target_voxels->size(); j++) {
1161 for (
int i = 0;
i < background_reference->size();
i++) {
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,
1173 max_prob[target_voxels->operator[](j).supervoxel_index] =
probability;
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.....");
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);
1194 ne.setRadiusSearch(
k);
1195 } ne.compute(*normals);
1199 const pcl::PointCloud<PointT>::Ptr cloud,
1200 const pcl::PointCloud<pcl::Normal>::Ptr normal,
1201 cv::Mat &histogram)
const
1203 if (
cloud->empty() || normal->empty()){
1207 bool is_gfpfh =
false;
1209 bool is_cvfh =
false;
1211 pcl::PointCloud<pcl::PointXYZL>::Ptr
object(
1212 new pcl::PointCloud<pcl::PointXYZL>);
1213 for (
int i = 0;
i <
cloud->size();
i++) {
1215 pt.x =
cloud->points[
i].x;
1216 pt.y =
cloud->points[
i].y;
1217 pt.z =
cloud->points[
i].z;
1219 object->push_back(pt);
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];
1237 pcl::VFHEstimation<
PointT,
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>());
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];
1254 pcl::CVFHEstimation<
PointT,
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.0
f / 180.0
f *
M_PI);
1263 cvfh.setCurvatureThreshold(1.0
f);
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];
1276 const pcl::PointCloud<PointT>::Ptr cloud,
1277 cv::Mat &hist,
const int hBin,
const int sBin,
bool is_norm)
const
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++) {
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;
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};
1296 &hsv, 1, channels, cv::Mat(), hist, 2, histSize, ranges,
true,
false);
1298 cv::normalize(hist, hist, 0, 1, cv::NORM_MINMAX, -1, cv::Mat());
1303 const pcl::PointCloud<PointT>::Ptr cloud,
1304 const pcl::PointCloud<pcl::Normal>::Ptr normals,
1305 cv::Mat &histogram,
bool holistic)
const
1307 if (
cloud->empty() || normals->empty()) {
1308 ROS_ERROR(
"-- ERROR: cannot compute FPFH");
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;
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];
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];
1337 cv::normalize(histogram, histogram, 0, 1, cv::NORM_MINMAX, -1, cv::Mat());
1340 std::vector<pcl::PointIndices::Ptr>
1342 const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_mgs)
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);
1355 const geometry_msgs::PoseStamped::ConstPtr &pose_msg,
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;
1371 if (!std::isnan(current_pose.x) && !std::isnan(current_pose.y) &&
1372 !std::isnan(current_pose.z)) {
1374 int last_index =
static_cast<int>(
1376 motion_displacement.x = current_pose.x -
1378 motion_displacement.y = current_pose.y -
1380 motion_displacement.z = current_pose.z -
1382 motion_displacement.roll = current_pose.roll -
1384 motion_displacement.pitch = current_pose.pitch -
1386 motion_displacement.yaw = current_pose.yaw -
1397 const pcl::PointCloud<PointT>::Ptr cloud,
1398 Eigen::Vector4f ¢re)
const
1400 if (
cloud->empty()) {
1401 ROS_ERROR(
"ERROR: empty cloud for centroid");
1402 centre = Eigen::Vector4f(-1, -1, -1, -1);
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))) {
1413 const pcl::PointCloud<pcl::Normal>::Ptr normal,
1416 if (normal->empty()) {
1417 return Eigen::Vector4f(0, 0, 0, 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;
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),
1445 const pcl::PointCloud<PointT>::Ptr cloud,
1446 const Eigen::Vector4f centroid)
1448 if (
cloud->empty()) {
1449 ROS_ERROR(
"Empty input for computing Scatter Matrix");
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);
1467 Eigen::EigenSolver<Eigen::MatrixXf> eigen_solver(scatter_matrix,
true);
1472 const float dist,
const float weight) {
1473 if (std::isnan(dist)) {
1476 return static_cast<float>(1/(1 + (weight * std::pow(dist, 2))));
1479 pcl::PointXYZRGBNormal
1481 const Eigen::Vector4f ¢roid,
1482 const Eigen::Vector4f &normal,
1483 const cv::Scalar color) {
1484 pcl::PointXYZRGBNormal pt;
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);
1497 template<
typename T>
1500 Eigen::Matrix<T, 3, 3> &rotation)
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();
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)
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");
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;
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);
1538 neighbor_supervoxel->normals_);
1543 pcl::computePairFeatures(
1544 supervoxel->centroid_.getVector4fMap(), c_normal,
1545 neighbor_supervoxel->centroid_.getVector4fMap(),
1547 int bin_index[feature_count];
1548 bin_index[0] =
static_cast<int>(
1550 bin_index[1] =
static_cast<int>(
1551 std::floor(this->
bin_size_ * ((phi + 1.0
f) * 0.5
f)));
1552 bin_index[2] =
static_cast<int>(
1553 std::floor(this->
bin_size_ * ((theta + 1.0
f) * 0.5
f)));
1554 for (
int i = 0;
i < feature_count;
i++) {
1555 if (bin_index[
i] < 0) {
1563 histogram.at<
float>(
1566 cache_normals[*itr] = n_normal;
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) {
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,
1585 int bin_index[feature_count];
1586 bin_index[0] =
static_cast<int>(
1588 bin_index[1] =
static_cast<int>(
1589 std::floor(this->
bin_size_ * ((phi + 1.0
f) * 0.5
f)));
1590 bin_index[2] =
static_cast<int>(
1591 std::floor(this->
bin_size_ * ((theta + 1.0
f) * 0.5
f)));
1592 for (
int i = 0;
i < feature_count;
i++) {
1593 if (bin_index[
i] < 0) {
1599 histogram.at<
float>(
1606 histogram, histogram, 0, 1, cv::NORM_MINMAX, -1, cv::Mat());
1612 const pcl::PointCloud<PointT>::Ptr cloud)
1614 if (
cloud->empty()) {
1615 ROS_ERROR(
"ERROR! Input Cloud is Empty");
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);
1624 float dist =
static_cast<float>(pcl::distances::l2(max_pt, pivot_pt));
1629 pcl::PointCloud<PointT>::Ptr cloud,
1630 const Eigen::Vector4f tracker_position,
1632 const float scaling_factor)
1634 if (
cloud->empty() || template_model->empty()) {
1635 ROS_ERROR(
"ERROR! Input data is empty is Empty");
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);
1644 filter_distance *= scaling_factor;
1645 if (filter_distance < 0.05
f) {
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()) {
1672 pcl::copyPointCloud<PointT, PointT>(*cloud_filter, *
cloud);
1679 const Eigen::Affine3f &transform_model)
1681 if (obj_ref->empty()) {
1682 ROS_ERROR(
"ERROR! No Object Model to Transform");
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;
1700 pcl::PointCloud<PointT>::Ptr cloud,
1702 const float threshold)
1704 if (
cloud->empty() || background_reference->empty()) {
1705 ROS_ERROR(
"ERROR! EMPTY DATA FOR BOUNDING BOX CLOUD");
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>(
1719 for (
int j = 0; j < background_reference->size(); j++) {
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,
1732 *tmp_cloud = *tmp_cloud + *(
1733 tmp_model->operator[](
i).cluster_cloud);
1739 if (tmp_cloud->size() > (
static_cast<int>(
cloud->size() / 4))) {
1741 pcl::copyPointCloud<PointT, PointT>(*tmp_cloud, *
cloud);
1745 template<
typename T,
typename U,
typename V>
1747 T v, U vmin, V vmax)
1749 cv::Scalar
c = cv::Scalar(0.0, 0.0, 0.0);
1756 if (
v < (vmin + 0.25 * dv)) {
1758 c.val[1] = 4 * (
v - vmin) / dv;
1759 }
else if (
v < (vmin + 0.5 * dv)) {
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;
1766 c.val[1] = 1 + 4 * (vmin + 0.75 * dv -
v) / dv;
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)
1778 if (
cloud->empty() || seed_resolution <= 0.0f) {
1779 ROS_ERROR(
"ERROR: Supervoxel input cloud empty...\n Incorrect Seed");
1783 pcl::SupervoxelClustering<PointT> super(
1785 static_cast<double>(seed_resolution)
1786 #
if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
1791 super.setInputCloud(
cloud);
1795 supervoxel_clusters.clear();
1796 super.extract(supervoxel_clusters);
1797 super.getSupervoxelAdjacency(supervoxel_adjacency);
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)
1805 if (
cloud->empty()) {
1806 ROS_ERROR(
"ERROR: Supervoxel input cloud empty...");
1812 #
if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
1817 super.setInputCloud(
cloud);
1821 supervoxel_clusters.clear();
1822 super.extract(supervoxel_clusters);
1823 super.getSupervoxelAdjacency(supervoxel_adjacency);
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)
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();
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());
1844 all_indices.push_back(indices);
1845 *output = *output + *super_voxel_cloud;
1847 ros_indices.cluster_indices.clear();
1850 ros_cloud.data.clear();
1852 ros_indices.header =
header;
1853 ros_cloud.header =
header;
1857 const jsk_recognition_msgs::ClusterPointIndices &sv_indices,
1858 const std::vector<uint32_t> &tdp_list,
1859 jsk_recognition_msgs::ClusterPointIndices &ros_indices)
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]);
1866 ros_indices.header = sv_indices.header;
1870 Config &config, uint32_t level)
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);
1885 this->
vfh_scaling_ =
static_cast<float>(config.vfh_scaling);