00001
00002
00003
00004 #include <jsk_pcl_ros/target_adaptive_tracking.h>
00005 #include <map>
00006
00007 namespace jsk_pcl_ros
00008 {
00009 TargetAdaptiveTracking::TargetAdaptiveTracking() :
00010 DiagnosticNodelet("target_adaptive_tracking"),
00011 init_counter_(0),
00012 update_counter_(0),
00013 growth_rate_(1.15)
00014 {
00015 this->object_reference_ = ModelsPtr(new Models);
00016 this->background_reference_ = ModelsPtr(new Models);
00017 this->previous_template_ = pcl::PointCloud<PointT>::Ptr(
00018 new pcl::PointCloud<PointT>);
00019 }
00020
00021 void TargetAdaptiveTracking::onInit()
00022 {
00023 DiagnosticNodelet::onInit();
00024
00025 srv_ = boost::shared_ptr<dynamic_reconfigure::Server<Config> >(
00026 new dynamic_reconfigure::Server<Config>);
00027 dynamic_reconfigure::Server<Config>::CallbackType f =
00028 boost::bind(&TargetAdaptiveTracking::configCallback, this, _1, _2);
00029 srv_->setCallback(f);
00030
00031 this->pub_cloud_ = advertise<sensor_msgs::PointCloud2>(
00032 *pnh_, "/target_adaptive_tracking/output/cloud", 1);
00033
00034
00035
00036
00037 this->pub_templ_ = advertise<sensor_msgs::PointCloud2>(
00038 *pnh_, "/selected_pointcloud", 1);
00039
00040 this->pub_sindices_ = advertise<
00041 jsk_recognition_msgs::ClusterPointIndices>(
00042 *pnh_, "/target_adaptive_tracking/supervoxel/indices", 1);
00043
00044 this->pub_scloud_ = advertise<sensor_msgs::PointCloud2>(
00045 *pnh_, "/target_adaptive_tracking/supervoxel/cloud", 1);
00046
00047 this->pub_normal_ = advertise<sensor_msgs::PointCloud2>(
00048 *pnh_, "/target_adaptive_tracking/output/normal", 1);
00049
00050 this->pub_tdp_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
00051 *pnh_, "/target_adaptive_tracking/supervoxel/tdp_indices", 1);
00052
00053 this->pub_inliers_ = advertise<sensor_msgs::PointCloud2>(
00054 *pnh_, "/target_adaptive_tracking/output/inliers", 1);
00055
00056 this->pub_centroids_ = advertise<sensor_msgs::PointCloud2>(
00057 *pnh_, "/target_adaptive_tracking/output/centroids", 1);
00058
00059 this->pub_pose_ = advertise<geometry_msgs::PoseStamped>(
00060 *pnh_, "/target_adaptive_tracking/output/object_pose", 1);
00061
00062 this->pub_prob_ = advertise<sensor_msgs::PointCloud2>(
00063 *pnh_, "/target_adaptive_tracking/output/probability_map", 1);
00064 }
00065
00066 void TargetAdaptiveTracking::subscribe()
00067 {
00068 this->sub_obj_cloud_.subscribe(*pnh_, "input_obj_cloud", 1);
00069 this->sub_bkgd_cloud_.subscribe(*pnh_, "input_bkgd_cloud", 1);
00070 this->sub_obj_pose_.subscribe(*pnh_, "input_obj_pose", 1);
00071 this->obj_sync_ = boost::make_shared<message_filters::Synchronizer<
00072 ObjectSyncPolicy> >(100);
00073 this->obj_sync_->connectInput(
00074 sub_obj_cloud_, sub_bkgd_cloud_, sub_obj_pose_);
00075 this->obj_sync_->registerCallback(
00076 boost::bind(&TargetAdaptiveTracking::objInitCallback,
00077 this, _1, _2, _3));
00078 this->sub_cloud_.subscribe(*pnh_, "input_cloud", 1);
00079 this->sub_pose_.subscribe(*pnh_, "input_pose", 1);
00080 this->sync_ = boost::make_shared<message_filters::Synchronizer<
00081 SyncPolicy> >(100);
00082 this->sync_->connectInput(sub_cloud_, sub_pose_);
00083 this->sync_->registerCallback(
00084 boost::bind(&TargetAdaptiveTracking::callback,
00085 this, _1, _2));
00086 }
00087
00088 void TargetAdaptiveTracking::unsubscribe()
00089 {
00090 this->sub_cloud_.unsubscribe();
00091 this->sub_pose_.unsubscribe();
00092 this->sub_obj_cloud_.unsubscribe();
00093 this->sub_obj_pose_.unsubscribe();
00094 }
00095
00096 void TargetAdaptiveTracking::updateDiagnostic(
00097 diagnostic_updater::DiagnosticStatusWrapper &stat)
00098 {
00099 if (vital_checker_->isAlive()) {
00100 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00101 "TargetAdaptiveTracking running");
00102 } else {
00103 jsk_topic_tools::addDiagnosticErrorSummary(
00104 "TargetAdaptiveTracking", vital_checker_, stat);
00105 }
00106 }
00107
00108 void TargetAdaptiveTracking::objInitCallback(
00109 const sensor_msgs::PointCloud2::ConstPtr &cloud_msg,
00110 const sensor_msgs::PointCloud2::ConstPtr &bkgd_msg,
00111 const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
00112 {
00113 pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00114 pcl::fromROSMsg(*cloud_msg, *cloud);
00115 pcl::PointCloud<PointT>::Ptr bkgd_cloud (new pcl::PointCloud<PointT>);
00116 pcl::fromROSMsg(*bkgd_msg, *bkgd_cloud);
00117 if (this->init_counter_++ > 0) {
00118 ROS_WARN("Object is re-initalized! stopping & reseting...");
00119 }
00120 if (!cloud->empty() && !bkgd_cloud->empty()) {
00121 this->motion_history_.clear();
00122 PointXYZRPY motion_displacement;
00123 this->estimatedPFPose(pose_msg, motion_displacement);
00124 this->previous_pose_ = this->current_pose_;
00125 this->object_reference_ = ModelsPtr(new Models);
00126 this->processInitCloud(cloud, this->object_reference_);
00127 this->background_reference_ = ModelsPtr(new Models);
00128 this->processInitCloud(bkgd_cloud, this->background_reference_);
00129 previous_distance_ = this->templateCloudFilterLenght(cloud);
00130 this->previous_template_->clear();
00131 pcl::copyPointCloud<PointT, PointT>(*cloud, *previous_template_);
00132 this->previous_transform_ = tf::Transform::getIdentity();
00133
00134 sensor_msgs::PointCloud2 ros_templ;
00135 pcl::toROSMsg(*cloud, ros_templ);
00136 ros_templ.header = cloud_msg->header;
00137 this->pub_templ_.publish(ros_templ);
00138 }
00139 }
00140
00141 void TargetAdaptiveTracking::processInitCloud(
00142 const pcl::PointCloud<PointT>::Ptr cloud,
00143 ModelsPtr object_reference)
00144 {
00145 if (cloud->empty()) {
00146 ROS_ERROR("OBJECT INIT CLOUD IS EMPTY");
00147 return;
00148 }
00149 float seed_resolution = static_cast<float>(this->seed_resolution_) / 2.0f;
00150 float seed_factor = seed_resolution;
00151 for (int i = 0; i < 3; i++) {
00152 std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> supervoxel_clusters;
00153 std::multimap<uint32_t, uint32_t> supervoxel_adjacency;
00154 this->supervoxelSegmentation(
00155 cloud, supervoxel_clusters, supervoxel_adjacency, seed_resolution);
00156 ModelsPtr obj_ref(new Models);
00157 std::vector<AdjacentInfo> supervoxel_list;
00158 this->voxelizeAndProcessPointCloud(
00159 cloud, supervoxel_clusters, supervoxel_adjacency,
00160 supervoxel_list, obj_ref, true, true, true, true);
00161 for (int j = 0; j < obj_ref->size(); j++) {
00162 object_reference->push_back(obj_ref->operator[](j));
00163 }
00164 seed_resolution += seed_factor;
00165 }
00166 }
00167
00168 void TargetAdaptiveTracking::callback(
00169 const sensor_msgs::PointCloud2::ConstPtr &cloud_msg,
00170 const geometry_msgs::PoseStamped::ConstPtr &pose_msg) {
00171 if (this->object_reference_->empty())
00172 {
00173 ROS_WARN("No Model To Track Selected");
00174 return;
00175 }
00176 ROS_INFO("\n\n\033[34m------------RUNNING CALLBACK-------------\033[0m");
00177 ros::Time begin = ros::Time::now();
00178 PointXYZRPY motion_displacement;
00179 this->estimatedPFPose(pose_msg, motion_displacement);
00180 std::cout << "Motion Displacement: " << motion_displacement << std::endl;
00181
00182 pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00183 pcl::fromROSMsg(*cloud_msg, *cloud);
00184 bool use_tf = false;
00185 tf::TransformListener tf_listener;
00186 tf::StampedTransform transform;
00187 ros::Time now = ros::Time(0);
00188 std::string child_frame = "/camera_rgb_optical_frame";
00189 std::string parent_frame = "/track_result";
00190 Eigen::Affine3f transform_model = Eigen::Affine3f::Identity();
00191 tf::Transform update_transform;
00192 if (use_tf) {
00193 bool wft_ok = tf_listener.waitForTransform(
00194 child_frame, parent_frame, now, ros::Duration(2.0f));
00195 if (!wft_ok) {
00196 ROS_ERROR("CANNOT TRANSFORM SOURCE AND TARGET FRAMES");
00197 return;
00198 }
00199 tf_listener.lookupTransform(
00200 child_frame, parent_frame, now, transform);
00201 tf::Quaternion tf_quaternion = transform.getRotation();
00202 transform_model = Eigen::Affine3f::Identity();
00203 transform_model.translation() <<
00204 transform.getOrigin().getX(),
00205 transform.getOrigin().getY(),
00206 transform.getOrigin().getZ();
00207 Eigen::Quaternion<float> quaternion = Eigen::Quaternion<float>(
00208 tf_quaternion.w(), tf_quaternion.x(),
00209 tf_quaternion.y(), tf_quaternion.z());
00210 transform_model.rotate(quaternion);
00211 tf::Vector3 origin = tf::Vector3(transform.getOrigin().getX(),
00212 transform.getOrigin().getY(),
00213 transform.getOrigin().getZ());
00214 update_transform.setOrigin(origin);
00215 tf::Quaternion update_quaternion = tf_quaternion;
00216 update_transform.setRotation(update_quaternion +
00217 this->previous_transform_.getRotation());
00218
00219 } else {
00220 transform_model = Eigen::Affine3f::Identity();
00221 transform_model.translation() << pose_msg->pose.position.x,
00222 pose_msg->pose.position.y, pose_msg->pose.position.z;
00223 Eigen::Quaternion<float> pf_quat = Eigen::Quaternion<float>(
00224 pose_msg->pose.orientation.w, pose_msg->pose.orientation.x,
00225 pose_msg->pose.orientation.y, pose_msg->pose.orientation.z);
00226 transform_model.rotate(pf_quat);
00227 tf::Vector3 origin = tf::Vector3(
00228 pose_msg->pose.position.x,
00229 pose_msg->pose.position.y,
00230 pose_msg->pose.position.z);
00231 update_transform.setOrigin(origin);
00232 tf::Quaternion update_quaternion = tf::Quaternion(
00233 pose_msg->pose.orientation.x, pose_msg->pose.orientation.y,
00234 pose_msg->pose.orientation.z, pose_msg->pose.orientation.w);
00235 update_transform.setRotation(update_quaternion *
00236 this->previous_transform_.getRotation());
00237 }
00238
00239 Eigen::Affine3f transform_reference = Eigen::Affine3f::Identity();
00240 const int motion_hist_index = static_cast<int>(
00241 this->motion_history_.size()) - 1;
00242 transform_reference.translation() <<
00243 motion_history_[motion_hist_index].x,
00244 motion_history_[motion_hist_index].y,
00245 motion_history_[motion_hist_index].z;
00246 Eigen::Affine3f transformation_matrix = transform_model *
00247 transform_reference.inverse();
00248 bool is_cloud_exist = this->filterPointCloud(
00249 cloud, this->current_pose_, this->object_reference_, 1.5f);
00250 if (is_cloud_exist && this->update_filter_template_) {
00251 this->targetDescriptiveSurfelsEstimationAndUpdate(
00252 cloud, transformation_matrix, motion_displacement,
00253 cloud_msg->header);
00254 }
00255 ros::Time end = ros::Time::now();
00256 std::cout << "Processing Time: " << end - begin << std::endl;
00257
00258 static tf::TransformBroadcaster br;
00259 br.sendTransform(tf::StampedTransform(
00260 update_transform, cloud_msg->header.stamp,
00261 cloud_msg->header.frame_id, "object_pose"));
00262 this->previous_transform_ = update_transform;
00263
00264 geometry_msgs::PoseStamped update_pose;
00265 tf::poseTFToMsg(update_transform, update_pose.pose);
00266 update_pose.header.stamp = cloud_msg->header.stamp;
00267 update_pose.header.frame_id = child_frame;
00268 this->pub_pose_.publish(update_pose);
00269
00270 sensor_msgs::PointCloud2 ros_cloud;
00271 pcl::toROSMsg(*cloud, ros_cloud);
00272 ros_cloud.header.stamp = cloud_msg->header.stamp;
00273 ros_cloud.header.frame_id = child_frame;
00274 this->pub_cloud_.publish(ros_cloud);
00275 }
00276
00277 void TargetAdaptiveTracking::voxelizeAndProcessPointCloud(
00278 const pcl::PointCloud<PointT>::Ptr cloud,
00279 const std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> &
00280 supervoxel_clusters,
00281 const std::multimap<uint32_t, uint32_t> &supervoxel_adjacency,
00282 std::vector<AdjacentInfo> &supervoxel_list,
00283 TargetAdaptiveTracking::ModelsPtr &models,
00284 bool norm_flag, bool feat_flag, bool cent_flag, bool neigh_pfh)
00285 {
00286 if (cloud->empty() || supervoxel_clusters.empty()) {
00287 return;
00288 }
00289 models = ModelsPtr(new Models);
00290 int icounter = 0;
00291 for (std::multimap<uint32_t, pcl::Supervoxel<PointT>::Ptr>::const_iterator
00292 label_itr = supervoxel_clusters.begin(); label_itr !=
00293 supervoxel_clusters.end(); label_itr++) {
00294 ReferenceModel ref_model;
00295 ref_model.flag = true;
00296 ref_model.supervoxel_index = label_itr->first;
00297 uint32_t supervoxel_label = label_itr->first;
00298 pcl::Supervoxel<PointT>::Ptr supervoxel =
00299 supervoxel_clusters.at(supervoxel_label);
00300 if (supervoxel->voxels_->size() > min_cluster_size_) {
00301 std::vector<uint32_t> adjacent_voxels;
00302 for (std::multimap<uint32_t, uint32_t>::const_iterator
00303 adjacent_itr = supervoxel_adjacency.equal_range(
00304 supervoxel_label).first; adjacent_itr !=
00305 supervoxel_adjacency.equal_range(
00306 supervoxel_label).second; ++adjacent_itr) {
00307 pcl::Supervoxel<PointT>::Ptr neighbor_supervoxel =
00308 supervoxel_clusters.at(adjacent_itr->second);
00309 if (neighbor_supervoxel->voxels_->size() >
00310 min_cluster_size_) {
00311 adjacent_voxels.push_back(adjacent_itr->second);
00312 }
00313 icounter++;
00314 }
00315 AdjacentInfo a_info;
00316 a_info.adjacent_voxel_indices[supervoxel_label] = adjacent_voxels;
00317 supervoxel_list.push_back(a_info);
00318 a_info.voxel_index = supervoxel_label;
00319 ref_model.cluster_neigbors = a_info;
00320 ref_model.cluster_cloud = pcl::PointCloud<PointT>::Ptr(
00321 new pcl::PointCloud<PointT>);
00322 ref_model.cluster_cloud = supervoxel->voxels_;
00323 if (norm_flag) {
00324 ref_model.cluster_normals = pcl::PointCloud<pcl::Normal>::Ptr(
00325 new pcl::PointCloud<pcl::Normal>);
00326 ref_model.cluster_normals = supervoxel->normals_;
00327 }
00328 if (feat_flag) {
00329 this->computeCloudClusterRPYHistogram(
00330 ref_model.cluster_cloud,
00331 ref_model.cluster_normals,
00332 ref_model.cluster_vfh_hist);
00333 this->computeColorHistogram(
00334 ref_model.cluster_cloud,
00335 ref_model.cluster_color_hist);
00336 }
00337 if (cent_flag) {
00338 ref_model.cluster_centroid = Eigen::Vector4f();
00339 ref_model.cluster_centroid =
00340 supervoxel->centroid_.getVector4fMap();
00341 }
00342 ref_model.flag = false;
00343 ref_model.match_counter = 0;
00344 models->push_back(ref_model);
00345 }
00346 }
00347 std::cout << "Cloud Voxel size: " << models->size() << std::endl;
00348
00349
00350 if (neigh_pfh) {
00351 for (int i = 0; i < models->size(); i++) {
00352 this->computeLocalPairwiseFeautures(
00353 supervoxel_clusters,
00354 models->operator[](i).cluster_neigbors.adjacent_voxel_indices,
00355 models->operator[](i).neigbour_pfh);
00356 }
00357 }
00358 }
00359
00360 void TargetAdaptiveTracking::targetDescriptiveSurfelsEstimationAndUpdate(
00361 pcl::PointCloud<PointT>::Ptr cloud,
00362 const Eigen::Affine3f &transformation_matrix,
00363 const TargetAdaptiveTracking::PointXYZRPY &motion_disp,
00364 const std_msgs::Header header)
00365 {
00366 if (cloud->empty()) {
00367 ROS_ERROR("ERROR: Global Layer Input Empty");
00368 return;
00369 }
00370 pcl::PointCloud<PointT>::Ptr n_cloud(new pcl::PointCloud<PointT>);
00371 Models obj_ref = *object_reference_;
00372 std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> supervoxel_clusters;
00373 std::multimap<uint32_t, uint32_t> supervoxel_adjacency;
00374 this->supervoxelSegmentation(cloud,
00375 supervoxel_clusters,
00376 supervoxel_adjacency);
00377 Eigen::Matrix<float, 3, 3> rotation_matrix;
00378 rotation_matrix = transformation_matrix.rotation();
00379
00380 std::vector<AdjacentInfo> supervoxel_list;
00381 ModelsPtr t_voxels = ModelsPtr(new Models);
00382 this->voxelizeAndProcessPointCloud(
00383 cloud, supervoxel_clusters, supervoxel_adjacency,
00384 supervoxel_list, t_voxels, true, false, true);
00385 Models target_voxels = *t_voxels;
00386
00387 ROS_INFO("\033[35m MODEL TRANSITION FOR MATCHING \033[0m");
00388 std::map<int, int> matching_indices;
00389 pcl::PointCloud<PointT>::Ptr template_cloud(new pcl::PointCloud<PointT>);
00390 for (int j = 0; j < obj_ref.size(); j++) {
00391 if (!obj_ref[j].flag) {
00392 float distance = FLT_MAX;
00393 int nearest_index = -1;
00394 Eigen::Vector4f obj_centroid;
00395 obj_centroid = transformation_matrix * obj_ref[j].cluster_centroid;
00396 for (int i = 0; i < target_voxels.size(); i++) {
00397 if (!target_voxels[i].flag) {
00398 Eigen::Vector4f t_centroid =
00399 target_voxels[i].cluster_centroid;
00400 t_centroid(3) = 1.0f;
00401 float dist = static_cast<float>(
00402 pcl::distances::l2(obj_centroid, t_centroid));
00403 if (dist < distance) {
00404 distance = dist;
00405 nearest_index = i;
00406 }
00407 }
00408 }
00409 if (nearest_index != -1) {
00410 matching_indices[j] = nearest_index;
00411 }
00412 const int motion_hist_index = this->motion_history_.size() - 1;
00413 obj_ref[j].centroid_distance(0) = obj_ref[j].cluster_centroid(0) -
00414 this->motion_history_[motion_hist_index].x;
00415 obj_ref[j].centroid_distance(1) = obj_ref[j].cluster_centroid(1) -
00416 this->motion_history_[motion_hist_index].y;
00417 obj_ref[j].centroid_distance(2) = obj_ref[j].cluster_centroid(2) -
00418 this->motion_history_[motion_hist_index].z;
00419 }
00420 }
00421 ROS_INFO("\033[35m MATCHING THROUGH NIEGBOUR SEARCH \033[0m");
00422 int counter = 0;
00423 float connectivity_lenght = 2.0f;
00424 pcl::PointCloud<PointT>::Ptr est_centroid_cloud(
00425 new pcl::PointCloud<PointT>);
00426 std::multimap<uint32_t, Eigen::Vector3f> estimated_centroids;
00427 std::multimap<uint32_t, float> estimated_match_prob;
00428 std::multimap<uint32_t, ReferenceModel*> estimated_match_info;
00429 std::vector<uint32_t> best_match_index;
00430 std::multimap<uint32_t, float> all_probabilites;
00431 for (std::map<int, int>::iterator itr = matching_indices.begin();
00432 itr != matching_indices.end(); itr++) {
00433 if (!target_voxels[itr->second].flag) {
00434 std::map<uint32_t, std::vector<uint32_t> > neigb =
00435 target_voxels[itr->second].cluster_neigbors.adjacent_voxel_indices;
00436 uint32_t v_ind = target_voxels[
00437 itr->second].cluster_neigbors.voxel_index;
00438 uint32_t bm_index = v_ind;
00439 float probability = 0.0f;
00440 ReferenceModel *voxel_model = new ReferenceModel;
00441 probability = this->targetCandidateToReferenceLikelihood<float>(
00442 obj_ref[itr->first], target_voxels[itr->second].cluster_cloud,
00443 target_voxels[itr->second].cluster_normals,
00444 target_voxels[itr->second].cluster_centroid, voxel_model);
00445 voxel_model->query_index = itr->first;
00446
00447
00448
00449
00450 bool is_voxel_adjacency_info = true;
00451 float local_weight = 0.0f;
00452 if (is_voxel_adjacency_info) {
00453 cv::Mat histogram_phf;
00454 this->computeLocalPairwiseFeautures(
00455 supervoxel_clusters, neigb, histogram_phf);
00456 voxel_model->cluster_neigbors.adjacent_voxel_indices = neigb;
00457 voxel_model->neigbour_pfh = histogram_phf.clone();
00458 float dist_phf = static_cast<float>(
00459 cv::compareHist(obj_ref[itr->first].neigbour_pfh,
00460 histogram_phf, CV_COMP_BHATTACHARYYA));
00461 local_weight = std::exp(-this->structure_scaling_ * dist_phf);
00462 probability *= local_weight;
00463 }
00464 for (std::vector<uint32_t>::iterator it =
00465 neigb.find(v_ind)->second.begin();
00466 it != neigb.find(v_ind)->second.end(); it++) {
00467 ReferenceModel *voxel_mod = new ReferenceModel;
00468 float prob = this->targetCandidateToReferenceLikelihood<float>(
00469 obj_ref[itr->first], supervoxel_clusters.at(*it)->voxels_,
00470 supervoxel_clusters.at(*it)->normals_,
00471 supervoxel_clusters.at(*it)->centroid_.getVector4fMap(),
00472 voxel_mod);
00473 voxel_mod->query_index = itr->first;
00474 if (is_voxel_adjacency_info) {
00475 std::map<uint32_t, std::vector<uint32_t> > local_adjacency;
00476 std::vector<uint32_t> list_adj;
00477 for (std::multimap<uint32_t, uint32_t>::const_iterator
00478 adjacent_itr = supervoxel_adjacency.equal_range(
00479 *it).first; adjacent_itr !=
00480 supervoxel_adjacency.equal_range(*it).second;
00481 ++adjacent_itr) {
00482 list_adj.push_back(adjacent_itr->second);
00483 }
00484 local_adjacency[*it] = list_adj;
00485 cv::Mat local_phf;
00486 this->computeLocalPairwiseFeautures(
00487 supervoxel_clusters, local_adjacency, local_phf);
00488 voxel_mod->neigbour_pfh = local_phf.clone();
00489 voxel_mod->cluster_neigbors.adjacent_voxel_indices =
00490 local_adjacency;
00491 float dist_phf = static_cast<float>(
00492 cv::compareHist(obj_ref[itr->first].neigbour_pfh,
00493 local_phf, CV_COMP_BHATTACHARYYA));
00494 float phf_prob = std::exp(-this->structure_scaling_ * dist_phf);
00495 local_weight = phf_prob;
00496 prob *= phf_prob;
00497 }
00498
00499 float matching_dist = static_cast<float>(pcl::distances::l2(
00500 supervoxel_clusters.at(v_ind)->centroid_.getVector4fMap(),
00501 supervoxel_clusters.at(*it)->centroid_.getVector4fMap()));
00502 if (matching_dist > this->seed_resolution_ / connectivity_lenght) {
00503 prob *= 0.0f;
00504 }
00505 if (prob > probability) {
00506 probability = prob;
00507 bm_index = *it;
00508 voxel_model = voxel_mod;
00509 }
00510 }
00511 all_probabilites.insert(
00512 std::pair<uint32_t, float>(bm_index, probability));
00513 if (probability > threshold_) {
00514 Eigen::Vector3f estimated_position = supervoxel_clusters.at(
00515 bm_index)->centroid_.getVector3fMap() - rotation_matrix *
00516 obj_ref[itr->first].centroid_distance ;
00517 Eigen::Vector4f estimated_pos = Eigen::Vector4f(
00518 estimated_position(0), estimated_position(1),
00519 estimated_position(2), 0.0f);
00520 float match_dist = static_cast<float>(
00521 pcl::distances::l2(estimated_pos, current_pose_));
00522
00523 if (match_dist < this->seed_resolution_ / connectivity_lenght) {
00524 best_match_index.push_back(bm_index);
00525 estimated_centroids.insert(
00526 std::pair<uint32_t, Eigen::Vector3f>(
00527 bm_index, estimated_position));
00528 estimated_match_prob.insert(
00529 std::pair<uint32_t, float>(bm_index, probability));
00530 estimated_match_info.insert(
00531 std::pair<uint32_t, ReferenceModel*>(
00532 bm_index, voxel_model));
00533 obj_ref[itr->first].history_window.push_back(1);
00534 PointT pt;
00535 pt.x = estimated_position(0);
00536 pt.y = estimated_position(1);
00537 pt.z = estimated_position(2);
00538 pt.r = 255;
00539 est_centroid_cloud->push_back(pt);
00540 counter++;
00541 } else {
00542 ROS_WARN("-- Outlier not added...");
00543 }
00544 } else {
00545 obj_ref[itr->first].history_window.push_back(0);
00546 }
00547 }
00548 }
00549 pcl::PointCloud<PointT>::Ptr prob_cloud(new pcl::PointCloud<PointT>);
00550 for (std::multimap<uint32_t, float>::iterator it = all_probabilites.begin();
00551 it != all_probabilites.end(); it++) {
00552 if (it->second > eps_distance_) {
00553 for (int i = 0; i < supervoxel_clusters.at(
00554 it->first)->voxels_->size(); i++) {
00555 PointT pt = supervoxel_clusters.at(it->first)->voxels_->points[i];
00556 pt.r = 255 * it->second;
00557 pt.g = 255 * it->second;
00558 pt.b = 255 * it->second;
00559 prob_cloud->push_back(pt);
00560 }
00561 }
00562 }
00563 sensor_msgs::PointCloud2 ros_prob;
00564 pcl::toROSMsg(*prob_cloud, ros_prob);
00565 ros_prob.header = header;
00566 this->pub_prob_.publish(ros_prob);
00567
00568 pcl::PointCloud<PointT>::Ptr inliers(new pcl::PointCloud<PointT>);
00569 std::vector<uint32_t> outlier_index;
00570
00571 ROS_INFO("\033[35m OUTLIER FILTERING VIA BACKPROJECTION \033[0m");
00572 Eigen::Matrix<float, 3, 3> inv_rotation_matrix = rotation_matrix.inverse();
00573 PointT ptt;
00574 ptt.x = previous_pose_(0);
00575 ptt.y = previous_pose_(1);
00576 ptt.z = previous_pose_(2);
00577 ptt.b = 255;
00578 inliers->push_back(ptt);
00579 std::vector<uint32_t> matching_indx = best_match_index;
00580 best_match_index.clear();
00581 for (std::vector<uint32_t>::iterator it = matching_indx.begin();
00582 it != matching_indx.end(); it++) {
00583 Eigen::Vector4f cur_pt = supervoxel_clusters.at(
00584 *it)->centroid_.getVector4fMap();
00585 Eigen::Vector3f demean_pts = Eigen::Vector3f();
00586 demean_pts(0) = cur_pt(0) - this->current_pose_(0);
00587 demean_pts(1) = cur_pt(1) - this->current_pose_(1);
00588 demean_pts(2) = cur_pt(2) - this->current_pose_(2);
00589 int query_idx = estimated_match_info.find(*it)->second->query_index;
00590 Eigen::Vector3f abs_position = -(inv_rotation_matrix * demean_pts) +
00591 obj_ref[query_idx].cluster_centroid.head<3>();
00592 Eigen::Vector4f prev_vote = Eigen::Vector4f(
00593 abs_position(0), abs_position(1), abs_position(2), 0.0f);
00594 float matching_dist = static_cast<float>(
00595 pcl::distances::l2(prev_vote, this->previous_pose_));
00596
00597 PointT pt;
00598 pt.x = abs_position(0);
00599 pt.y = abs_position(1);
00600 pt.z = abs_position(2);
00601 if (matching_dist < this->seed_resolution_ / connectivity_lenght) {
00602 best_match_index.push_back(*it);
00603 pt.r = 255;
00604 pt.b = 255;
00605 } else {
00606 pt.g = 255;
00607 pt.b = 255;
00608 }
00609 inliers->push_back(pt);
00610 }
00611
00612
00613
00614
00615
00616
00617
00618
00619 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr centroid_normal(
00620 new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00621
00622
00623 for (std::vector<uint32_t>::iterator it = outlier_index.begin();
00624 it != outlier_index.end(); it++) {
00625 Eigen::Vector4f c_centroid = supervoxel_clusters.at(
00626 *it)->centroid_.getVector4fMap();
00627 Eigen::Vector4f c_normal = this->cloudMeanNormal(
00628 supervoxel_clusters.at(*it)->normals_);
00629 centroid_normal->push_back(
00630 this->convertVector4fToPointXyzRgbNormal(
00631 c_centroid, c_normal, cv::Scalar(0, 0, 255)));
00632 }
00633
00634 ROS_INFO("\033[35m CONVEX VOXELS \033[0m");
00635 pcl::PointCloud<PointT>::Ptr output(new pcl::PointCloud<PointT>);
00636 std::vector<uint32_t> neigb_lookup;
00637 neigb_lookup = best_match_index;
00638 std::vector<uint32_t> convex_ok;
00639 std::map<uint32_t, ReferenceModel*> convex_local_voxels;
00640
00641 for (std::vector<uint32_t>::iterator it = best_match_index.begin();
00642 it != best_match_index.end(); it++) {
00643 std::pair<std::multimap<uint32_t, uint32_t>::iterator,
00644 std::multimap<uint32_t, uint32_t>::iterator> ret;
00645 ret = supervoxel_adjacency.equal_range(*it);
00646 Eigen::Vector4f c_centroid = supervoxel_clusters.at(
00647 *it)->centroid_.getVector4fMap();
00648 Eigen::Vector4f c_normal = this->cloudMeanNormal(
00649 supervoxel_clusters.at(*it)->normals_);
00650
00651 centroid_normal->push_back(
00652 this->convertVector4fToPointXyzRgbNormal(
00653 c_centroid, c_normal, cv::Scalar(255, 0, 0)));
00654
00655 for (std::multimap<uint32_t, uint32_t>::iterator itr = ret.first;
00656 itr != ret.second; itr++) {
00657 bool is_process_neigh = true;
00658 for (std::vector<uint32_t>::iterator lup_it = neigb_lookup.begin();
00659 lup_it != neigb_lookup.end(); lup_it++) {
00660 if (*lup_it == itr->second) {
00661 is_process_neigh = false;
00662 break;
00663 }
00664 }
00665 if (!supervoxel_clusters.at(itr->second)->voxels_->empty() &&
00666 is_process_neigh) {
00667 bool is_common_neigh = false;
00668 if (!is_common_neigh) {
00669 neigb_lookup.push_back(itr->second);
00670 Eigen::Vector4f n_centroid = supervoxel_clusters.at(
00671 itr->second)->centroid_.getVector4fMap();
00672 Eigen::Vector4f n_normal = this->cloudMeanNormal(
00673 supervoxel_clusters.at(itr->second)->normals_);
00674 float convx_weight = this->localVoxelConvexityLikelihood<
00675 float>(c_centroid, c_normal, n_centroid, n_normal);
00676 if (convx_weight > 0.0f) {
00677 *output = *output + *supervoxel_clusters.at(
00678 itr->second)->voxels_;
00679
00680 ReferenceModel *ref_model = new ReferenceModel;
00681 this->processVoxelForReferenceModel(
00682 supervoxel_clusters, supervoxel_adjacency,
00683 itr->second, ref_model);
00684 if (!ref_model->flag) {
00685 Eigen::Vector4f convx_centroid = Eigen::Vector4f();
00686 convx_centroid = transformation_matrix.inverse() *
00687 ref_model->cluster_centroid;
00688 for (int j = 0; j < this->object_reference_->size();
00689 j++) {
00690 float rev_match_dist = static_cast<float>(
00691 pcl::distances::l2(convx_centroid,
00692 this->object_reference_->operator[](
00693 j).cluster_centroid));
00694 if (rev_match_dist < this->seed_resolution_) {
00695 float convx_dist = static_cast<float>(
00696 cv::compareHist(ref_model->cluster_vfh_hist,
00697 object_reference_->operator[](
00698 j).cluster_vfh_hist,
00699 CV_COMP_BHATTACHARYYA));
00700 float convx_prob = std::exp(
00701 -1 * this->vfh_scaling_ * convx_dist);
00702 if (convx_prob > this->threshold_) {
00703 ref_model->query_index = static_cast<int>(j);
00704 estimated_match_info.insert(
00705 std::pair<int32_t, ReferenceModel*>(
00706 itr->second, ref_model));
00707 convex_ok.push_back(itr->second);
00708 estimated_match_prob.insert(
00709 std::pair<uint32_t, float>(
00710 itr->second, convx_prob));
00711 centroid_normal->push_back(
00712 this->convertVector4fToPointXyzRgbNormal(
00713 n_centroid, n_normal,
00714 cv::Scalar(0, 255, 0)));
00715 ROS_INFO("\033[34m Added VOXEL \033[0m");
00716 break;
00717 }
00718 } else {
00719
00720
00721
00722 convex_local_voxels[itr->second] = ref_model;
00723 centroid_normal->push_back(
00724 this->convertVector4fToPointXyzRgbNormal(
00725 n_centroid, n_normal, cv::Scalar(0, 255, 0)));
00726 }
00727 }
00728 }
00729 }
00730 } else {
00731 std::pair<
00732 std::multimap<uint32_t, uint32_t>::iterator,
00733 std::multimap<uint32_t, uint32_t>::iterator> comm_neigb;
00734 comm_neigb = supervoxel_adjacency.equal_range(itr->second);
00735 uint32_t common_neigbour_index = 0;
00736 for (std::multimap<uint32_t, uint32_t>::iterator c_itr =
00737 comm_neigb.first; c_itr != comm_neigb.second;
00738 c_itr++) {
00739 if (!supervoxel_clusters.at(
00740 c_itr->second)->voxels_->empty()) {
00741 bool is_common_neigh = false;
00742 for (std::map<uint32_t, uint32_t>::iterator itr_ret =
00743 supervoxel_adjacency.equal_range(c_itr->first).
00744 first; itr_ret !=supervoxel_adjacency.equal_range(
00745 c_itr->first).second; itr_ret++) {
00746 if (itr_ret->second == *it) {
00747 is_common_neigh = true;
00748 common_neigbour_index = c_itr->second;
00749 break;
00750 }
00751 }
00752 if (is_common_neigh) {
00753 break;
00754 }
00755 }
00756 }
00757 if (common_neigbour_index > 0) {
00758 Eigen::Vector4f n_centroid_b = supervoxel_clusters.at(
00759 itr->second)->centroid_.getVector4fMap();
00760 Eigen::Vector4f n_normal_b = this->cloudMeanNormal(
00761 supervoxel_clusters.at(itr->second)->normals_);
00762 Eigen::Vector4f n_centroid_c = supervoxel_clusters.at(
00763 common_neigbour_index)->centroid_.getVector4fMap();
00764 Eigen::Vector4f n_normal_c = this->cloudMeanNormal(
00765 supervoxel_clusters.at(common_neigbour_index)->normals_);
00766 float convx_weight_ab = this->localVoxelConvexityLikelihood<
00767 float>(c_centroid, c_normal, n_centroid_b, n_normal_b);
00768 float convx_weight_ac = this->localVoxelConvexityLikelihood<
00769 float>(c_centroid, c_normal, n_centroid_c, n_normal_c);
00770 float convx_weight_bc = this->localVoxelConvexityLikelihood<
00771 float>(n_centroid_b, n_normal_b, n_centroid_c,
00772 n_normal_c);
00773 if (convx_weight_ab != 0.0f &&
00774 convx_weight_ac != 0.0f &&
00775 convx_weight_bc != 0.0f) {
00776 *output = *output + *supervoxel_clusters.at(
00777 itr->second)->voxels_;
00778 centroid_normal->push_back(
00779 this->convertVector4fToPointXyzRgbNormal(
00780 n_centroid_b, n_normal_b, cv::Scalar(0, 255, 0)));
00781 neigb_lookup.push_back(itr->second);
00782 ReferenceModel *ref_model = new ReferenceModel;
00783 this->processVoxelForReferenceModel(
00784 supervoxel_clusters, supervoxel_adjacency,
00785 itr->second, ref_model);
00786 if (!ref_model->flag) {
00787 Eigen::Vector4f convx_centroid = Eigen::Vector4f();
00788 convx_centroid = transformation_matrix.inverse() *
00789 ref_model->cluster_centroid;
00790 for (int j = 0; j < this->object_reference_->size(); j++) {
00791 float rev_match_dist = static_cast<float>(
00792 pcl::distances::l2(convx_centroid,
00793 this->object_reference_->operator[](
00794 j).cluster_centroid));
00795 if (rev_match_dist < this->seed_resolution_) {
00796 float convx_dist = static_cast<float>(
00797 cv::compareHist(ref_model->cluster_vfh_hist,
00798 object_reference_->operator[](
00799 j).cluster_vfh_hist, CV_COMP_BHATTACHARYYA));
00800 float convx_prob = std::exp(
00801 -1 * this->vfh_scaling_ * convx_dist);
00802 if (convx_prob > this->threshold_) {
00803 ref_model->query_index = static_cast<int>(j);
00804 estimated_match_info.insert(
00805 std::pair<int32_t, ReferenceModel*>(
00806 itr->second, ref_model));
00807 convex_ok.push_back(itr->second);
00808 estimated_match_prob.insert(
00809 std::pair<uint32_t, float>(
00810 itr->second, convx_prob));
00811 centroid_normal->push_back(
00812 this->convertVector4fToPointXyzRgbNormal(
00813 n_centroid_b, n_normal_b,
00814 cv::Scalar(0, 255, 0)));
00815 break;
00816 }
00817 } else {
00818 convex_local_voxels[itr->second] = ref_model;
00819 }
00820 }
00821 }
00822 }
00823 }
00824 }
00825 }
00826 }
00827 *output = *output + *supervoxel_clusters.at(*it)->voxels_;
00828 }
00829 for (int i = 0; i < convex_ok.size(); i++) {
00830 best_match_index.push_back(convex_ok[i]);
00831 }
00832
00833 ModelsPtr transform_model (new Models);
00834 this->transformModelPrimitives(
00835 this->object_reference_, transform_model, transformation_matrix);
00836 obj_ref.clear();
00837 obj_ref = *transform_model;
00838 if (best_match_index.size() > 2 && this->update_tracker_reference_) {
00839 ROS_INFO("\n\033[32mUpdating Tracking Reference Model\033[0m \n");
00840 std::map<int, ReferenceModel> matching_surfels;
00841 for (std::vector<uint32_t>::iterator it = best_match_index.begin();
00842 it != best_match_index.end(); it++) {
00843 float adaptive_factor = estimated_match_prob.find(*it)->second;
00844 std::pair<std::multimap<uint32_t, ReferenceModel*>::iterator,
00845 std::multimap<uint32_t, ReferenceModel*>::iterator> ret;
00846 ret = estimated_match_info.equal_range(*it);
00847 for (std::multimap<uint32_t, ReferenceModel*>::iterator itr =
00848 ret.first; itr != ret.second; ++itr) {
00849 cv::Mat nvfh_hist = cv::Mat::zeros(
00850 itr->second->cluster_vfh_hist.size(), CV_32F);
00851 nvfh_hist = itr->second->cluster_vfh_hist * adaptive_factor +
00852 obj_ref[itr->second->query_index].cluster_vfh_hist *
00853 (1 - adaptive_factor);
00854 cv::normalize(nvfh_hist, nvfh_hist, 0, 1,
00855 cv::NORM_MINMAX, -1, cv::Mat());
00856 cv::Mat ncolor_hist = cv::Mat::zeros(
00857 itr->second->cluster_color_hist.size(),
00858 itr->second->cluster_color_hist.type());
00859 ncolor_hist = itr->second->cluster_color_hist * adaptive_factor +
00860 obj_ref[itr->second->query_index].cluster_color_hist *
00861 (1 - adaptive_factor);
00862 cv::normalize(ncolor_hist, ncolor_hist, 0, 1,
00863 cv::NORM_MINMAX, -1, cv::Mat());
00864 cv::Mat local_phf = cv::Mat::zeros(
00865 itr->second->neigbour_pfh.size(),
00866 itr->second->neigbour_pfh.type());
00867 local_phf = itr->second->neigbour_pfh * adaptive_factor +
00868 obj_ref[itr->second->query_index].neigbour_pfh *
00869 (1 - adaptive_factor);
00870 cv::normalize(local_phf, local_phf, 0, 1,
00871 cv::NORM_MINMAX, -1, cv::Mat());
00872 int query_idx = estimated_match_info.find(
00873 *it)->second->query_index;
00874 obj_ref[query_idx].cluster_cloud = supervoxel_clusters.at(
00875 *it)->voxels_;
00876 obj_ref[query_idx].cluster_vfh_hist = nvfh_hist.clone();
00877 obj_ref[query_idx].cluster_color_hist = ncolor_hist.clone();
00878 obj_ref[query_idx].cluster_normals = supervoxel_clusters.at(
00879 *it)->normals_;
00880 obj_ref[query_idx].cluster_centroid = supervoxel_clusters.at(
00881 *it)->centroid_.getVector4fMap();
00882 obj_ref[query_idx].neigbour_pfh = local_phf.clone();
00883 obj_ref[query_idx].flag = false;
00884 matching_surfels[query_idx] = obj_ref[query_idx];
00885 obj_ref[query_idx].match_counter++;
00886 }
00887 }
00888 this->motion_history_.push_back(this->tracker_pose_);
00889 this->previous_pose_ = this->current_pose_;
00890
00891
00892
00893
00894 for (std::map<int, ReferenceModel>::iterator it =
00895 matching_surfels.begin(); it != matching_surfels.end(); it++) {
00896 this->object_reference_->operator[](it->first) = it->second;
00897 }
00898 for (std::map<uint32_t, ReferenceModel*>::iterator it =
00899 convex_local_voxels.begin(); it != convex_local_voxels.begin();
00900 it++) {
00901 this->object_reference_->push_back(*(it->second));
00902 }
00903 ModelsPtr tmp_model(new Models);
00904 if (this->update_counter_++ == this->history_window_size_) {
00905 for (int i = 0; i < this->object_reference_->size(); i++) {
00906 if (this->object_reference_->operator[](i).match_counter > 0) {
00907 ReferenceModel renew_model;
00908 renew_model = this->object_reference_->operator[](i);
00909 tmp_model->push_back(renew_model);
00910 } else {
00911 std::cout << "\033[033m OUTDATED MODEL \033[0m" << std::endl;
00912 }
00913 }
00914 this->update_counter_ = 0;
00915 this->object_reference_->clear();
00916 this->object_reference_ = tmp_model;
00917 }
00918
00919 } else {
00920 ROS_WARN("TRACKING MODEL CURRENTLY SET TO STATIC\n");
00921 }
00922 template_cloud->clear();
00923 int tmp_counter = 0;
00924 float argmax_lenght = 0.0f;
00925 for (int i = 0; i < this->object_reference_->size(); i++) {
00926 Eigen::Vector4f surfel_centroid = Eigen::Vector4f();
00927 surfel_centroid = this->object_reference_->operator[](
00928 i).cluster_centroid;
00929 surfel_centroid(3) = 0.0f;
00930 float surfel_dist = static_cast<float>(
00931 pcl::distances::l2(surfel_centroid, current_pose_));
00932 if (surfel_dist > argmax_lenght) {
00933 argmax_lenght = surfel_dist;
00934 }
00935 if (surfel_dist < (this->previous_distance_ * growth_rate_)) {
00936 float probability = 0.0f;
00937 for (int j = 0; j < this->background_reference_->size(); j++) {
00938 ReferenceModel *r_mod = new ReferenceModel;
00939 float prob = this->targetCandidateToReferenceLikelihood<float>(
00940 this->object_reference_->operator[](i),
00941 this->background_reference_->operator[](j).cluster_cloud,
00942 this->background_reference_->operator[](j).cluster_normals,
00943 this->background_reference_->operator[](j).cluster_centroid,
00944 r_mod);
00945 if (prob > probability) {
00946 probability = prob;
00947 }
00948 }
00949 if (probability < 0.60f) {
00950 *template_cloud = *template_cloud + *(
00951 this->object_reference_->operator[](i).cluster_cloud);
00952 tmp_counter++;
00953 } else {
00954 ROS_INFO("\033[35m SURFEL REMOVED AS BACKGRND \033[0m");
00955 }
00956 } else {
00957 ROS_INFO("\033[35m SURFEL REMOVED \033[0m]");
00958 }
00959 }
00960 if (argmax_lenght > (growth_rate_ * previous_distance_)) {
00961 argmax_lenght = previous_distance_ * growth_rate_;
00962 } else if (argmax_lenght < ((1 - growth_rate_) * previous_distance_)) {
00963 argmax_lenght = (1 - growth_rate_) * previous_distance_;
00964 }
00965 this->filterCloudForBoundingBoxViz(output, this->background_reference_);
00966 this->previous_distance_ = argmax_lenght;
00967
00968
00969
00970
00971 if (tmp_counter < 1) {
00972 template_cloud->clear();
00973 pcl::copyPointCloud<PointT, PointT>(*previous_template_, *template_cloud);
00974 } else {
00975 ROS_INFO("\033[34m UPDATING INFO...\033[0m");
00976
00977 pcl::copyPointCloud<PointT, PointT>(*template_cloud, *previous_template_);
00978 this->object_reference_ = ModelsPtr(new Models);
00979 this->processInitCloud(template_cloud, this->object_reference_);
00980 }
00981 std::cout << "\033[038m REFERENCE INFO \033[0m"
00982 << object_reference_->size() << std::endl;
00983 cloud->clear();
00984 pcl::copyPointCloud<PointT, PointT>(*output, *cloud);
00985 pcl::PointIndices tdp_ind;
00986 for (int i = 0; i < cloud->size(); i++) {
00987 tdp_ind.indices.push_back(i);
00988 }
00989 if (this->update_filter_template_) {
00990 sensor_msgs::PointCloud2 ros_templ;
00991 pcl::toROSMsg(*template_cloud, ros_templ);
00992 ros_templ.header = header;
00993 this->pub_templ_.publish(ros_templ);
00994 }
00995
00996 std::vector<pcl::PointIndices> all_indices;
00997 all_indices.push_back(tdp_ind);
00998 jsk_recognition_msgs::ClusterPointIndices tdp_indices;
00999 tdp_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
01000 all_indices, header);
01001 tdp_indices.header = header;
01002 this->pub_tdp_.publish(tdp_indices);
01003
01004
01005 sensor_msgs::PointCloud2 ros_svcloud;
01006 jsk_recognition_msgs::ClusterPointIndices ros_svindices;
01007 this->publishSupervoxel(
01008 supervoxel_clusters, ros_svcloud, ros_svindices, header);
01009 pub_scloud_.publish(ros_svcloud);
01010 pub_sindices_.publish(ros_svindices);
01011
01012
01013 sensor_msgs::PointCloud2 ros_inliers;
01014 pcl::toROSMsg(*inliers, ros_inliers);
01015 ros_inliers.header = header;
01016 this->pub_inliers_.publish(ros_inliers);
01017
01018
01019 sensor_msgs::PointCloud2 ros_centroids;
01020 pcl::toROSMsg(*est_centroid_cloud, ros_centroids);
01021 ros_centroids.header = header;
01022 this->pub_centroids_.publish(ros_centroids);
01023
01024
01025 sensor_msgs::PointCloud2 rviz_normal;
01026 pcl::toROSMsg(*centroid_normal, rviz_normal);
01027 rviz_normal.header = header;
01028 this->pub_normal_.publish(rviz_normal);
01029 }
01030
01031 void TargetAdaptiveTracking::processVoxelForReferenceModel(
01032 const std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> supervoxel_clusters,
01033 const std::multimap<uint32_t, uint32_t> supervoxel_adjacency,
01034 const uint32_t match_index,
01035 TargetAdaptiveTracking::ReferenceModel *ref_model)
01036 {
01037 if (supervoxel_clusters.empty() || supervoxel_adjacency.empty()) {
01038 ROS_ERROR("ERROR: empty data for updating voxel ref model");
01039 return;
01040 }
01041 if (supervoxel_clusters.at(
01042 match_index)->voxels_->size() > this->min_cluster_size_) {
01043 ref_model->flag = false;
01044 ref_model->cluster_cloud = supervoxel_clusters.at(
01045 match_index)->voxels_;
01046 ref_model->cluster_normals = supervoxel_clusters.at(
01047 match_index)->normals_;
01048 ref_model->cluster_centroid = supervoxel_clusters.at(
01049 match_index)->centroid_.getVector4fMap();
01050 this->computeCloudClusterRPYHistogram(
01051 ref_model->cluster_cloud,
01052 ref_model->cluster_normals,
01053 ref_model->cluster_vfh_hist);
01054 this->computeColorHistogram(
01055 ref_model->cluster_cloud,
01056 ref_model->cluster_color_hist);
01057 std::vector<uint32_t> adjacent_voxels;
01058 for (std::multimap<uint32_t, uint32_t>::const_iterator adjacent_itr =
01059 supervoxel_adjacency.equal_range(match_index).first;
01060 adjacent_itr != supervoxel_adjacency.equal_range(
01061 match_index).second; ++adjacent_itr) {
01062 pcl::Supervoxel<PointT>::Ptr neighbor_supervoxel =
01063 supervoxel_clusters.at(adjacent_itr->second);
01064 if (neighbor_supervoxel->voxels_->size() >
01065 min_cluster_size_) {
01066 adjacent_voxels.push_back(adjacent_itr->second);
01067 }
01068 }
01069 AdjacentInfo a_info;
01070 a_info.adjacent_voxel_indices[match_index] = adjacent_voxels;
01071 a_info.voxel_index = match_index;
01072 ref_model->cluster_neigbors = a_info;
01073 std::map<uint32_t, std::vector<uint32_t> > local_adj;
01074 local_adj[match_index] = adjacent_voxels;
01075 this->computeLocalPairwiseFeautures(
01076 supervoxel_clusters, local_adj, ref_model->neigbour_pfh);
01077 } else {
01078 ref_model->flag = true;
01079 }
01080 }
01081
01082 template<class T>
01083 T TargetAdaptiveTracking::targetCandidateToReferenceLikelihood(
01084 const TargetAdaptiveTracking::ReferenceModel &reference_model,
01085 const pcl::PointCloud<PointT>::Ptr cloud,
01086 const pcl::PointCloud<pcl::Normal>::Ptr normal,
01087 const Eigen::Vector4f ¢roid,
01088 ReferenceModel *voxel_model)
01089 {
01090 if (cloud->empty() || normal->empty()) {
01091 return 0.0f;
01092 }
01093 cv::Mat vfh_hist;
01094 this->computeCloudClusterRPYHistogram(cloud, normal, vfh_hist);
01095 cv::Mat color_hist;
01096 this->computeColorHistogram(cloud, color_hist);
01097 T dist_vfh = static_cast<T>(
01098 cv::compareHist(vfh_hist,
01099 reference_model.cluster_vfh_hist,
01100 CV_COMP_BHATTACHARYYA));
01101 T dist_col = static_cast<T>(
01102 cv::compareHist(color_hist,
01103 reference_model.cluster_color_hist,
01104 CV_COMP_BHATTACHARYYA));
01105 T probability = std::exp(-1 * this->vfh_scaling_ * dist_vfh) *
01106 std::exp(-1 * this->color_scaling_ * dist_col);
01107 bool convex_weight = false;
01108 if (convex_weight) {
01109 Eigen::Vector4f n_normal = this->cloudMeanNormal(normal);
01110 Eigen::Vector4f n_centroid = centroid;
01111 Eigen::Vector4f c_normal = this->cloudMeanNormal(
01112 reference_model.cluster_normals);
01113 Eigen::Vector4f c_centroid = reference_model.cluster_centroid;
01114 float convx_prob = this->localVoxelConvexityLikelihood<float>(
01115 c_centroid, c_normal, n_centroid, n_normal);
01116 probability * convx_prob;
01117 }
01118 voxel_model->cluster_vfh_hist = vfh_hist.clone();
01119 voxel_model->cluster_color_hist = color_hist.clone();
01120 return probability;
01121 }
01122
01123 template<class T>
01124 T TargetAdaptiveTracking::localVoxelConvexityLikelihood(
01125 Eigen::Vector4f c_centroid,
01126 Eigen::Vector4f c_normal,
01127 Eigen::Vector4f n_centroid,
01128 Eigen::Vector4f n_normal) {
01129 c_centroid(3) = 0.0f;
01130 c_normal(3) = 0.0f;
01131 n_centroid(3) = 0.0f;
01132 n_normal(3) = 0.0f;
01133 T weight = 1.0f;
01134 if ((n_centroid - c_centroid).dot(n_normal) > 0) {
01135 weight = static_cast<T>(std::pow(1 - (c_normal.dot(n_normal)), 2));
01136 return 1.0f;
01137 } else {
01138
01139 return 0.0f;
01140 }
01141 if (std::isnan(weight)) {
01142 return 0.0f;
01143 }
01144 T probability = std::exp(-1 * weight);
01145 return probability;
01146 }
01147
01148 void TargetAdaptiveTracking::backgroundReferenceLikelihood(
01149 const ModelsPtr background_reference,
01150 const ModelsPtr target_voxels,
01151 std::map<uint32_t, float> max_prob)
01152 {
01153 if (background_reference->empty() || target_voxels->empty()) {
01154 ROS_ERROR("INPUT DATA IS EMPTY");
01155 }
01156 for (int j = 0; j < target_voxels->size(); j++) {
01157 float probability = 0.0f;
01158 for (int i = 0; i < background_reference->size(); i++) {
01159 ReferenceModel *mod = new ReferenceModel;
01160 float prob = this->targetCandidateToReferenceLikelihood<float>(
01161 background_reference->operator[](i),
01162 target_voxels->operator[](j).cluster_cloud,
01163 target_voxels->operator[](j).cluster_normals,
01164 target_voxels->operator[](j).cluster_centroid,
01165 mod);
01166 if (prob > probability) {
01167 probability = prob;
01168 }
01169 }
01170 max_prob[target_voxels->operator[](j).supervoxel_index] = probability;
01171 }
01172 }
01173
01174 template<class T>
01175 void TargetAdaptiveTracking::estimatePointCloudNormals(
01176 const pcl::PointCloud<PointT>::Ptr cloud,
01177 pcl::PointCloud<pcl::Normal>::Ptr normals,
01178 const T k, bool use_knn) const {
01179 if (cloud->empty()) {
01180 ROS_ERROR("ERROR: The Input cloud is Empty.....");
01181 return;
01182 }
01183 pcl::NormalEstimationOMP<PointT, pcl::Normal> ne;
01184 ne.setInputCloud(cloud);
01185 ne.setNumberOfThreads(8);
01186 pcl::search::KdTree<PointT>::Ptr tree (new pcl::search::KdTree<PointT> ());
01187 ne.setSearchMethod(tree);
01188 if (use_knn) {
01189 ne.setKSearch(k);
01190 } else {
01191 ne.setRadiusSearch(k);
01192 } ne.compute(*normals);
01193 }
01194
01195 void TargetAdaptiveTracking::computeCloudClusterRPYHistogram(
01196 const pcl::PointCloud<PointT>::Ptr cloud,
01197 const pcl::PointCloud<pcl::Normal>::Ptr normal,
01198 cv::Mat &histogram) const
01199 {
01200 if (cloud->empty() || normal->empty()){
01201 ROS_ERROR("ERROR: Empty Input");
01202 return;
01203 }
01204 bool is_gfpfh = false;
01205 bool is_vfh = true;
01206 bool is_cvfh = false;
01207 if (is_gfpfh) {
01208 pcl::PointCloud<pcl::PointXYZL>::Ptr object(
01209 new pcl::PointCloud<pcl::PointXYZL>);
01210 for (int i = 0; i < cloud->size(); i++) {
01211 pcl::PointXYZL pt;
01212 pt.x = cloud->points[i].x;
01213 pt.y = cloud->points[i].y;
01214 pt.z = cloud->points[i].z;
01215 pt.label = 1;
01216 object->push_back(pt);
01217 }
01218 pcl::GFPFHEstimation<
01219 pcl::PointXYZL, pcl::PointXYZL, pcl::GFPFHSignature16> gfpfh;
01220 gfpfh.setInputCloud(object);
01221 gfpfh.setInputLabels(object);
01222 gfpfh.setOctreeLeafSize(0.01);
01223 gfpfh.setNumberOfClasses(1);
01224 pcl::PointCloud<pcl::GFPFHSignature16>::Ptr descriptor(
01225 new pcl::PointCloud<pcl::GFPFHSignature16>);
01226 gfpfh.compute(*descriptor);
01227 histogram = cv::Mat(sizeof(char), 16, CV_32F);
01228 for (int i = 0; i < histogram.cols; i++) {
01229 histogram.at<float>(0, i) = descriptor->points[0].histogram[i];
01230
01231 }
01232 }
01233 if (is_vfh) {
01234 pcl::VFHEstimation<PointT,
01235 pcl::Normal,
01236 pcl::VFHSignature308> vfh;
01237 vfh.setInputCloud(cloud);
01238 vfh.setInputNormals(normal);
01239 pcl::search::KdTree<PointT>::Ptr tree(
01240 new pcl::search::KdTree<PointT>);
01241 vfh.setSearchMethod(tree);
01242 pcl::PointCloud<pcl::VFHSignature308>::Ptr vfhs(
01243 new pcl::PointCloud<pcl::VFHSignature308>());
01244 vfh.compute(*vfhs);
01245 histogram = cv::Mat(sizeof(char), 308, CV_32F);
01246 for (int i = 0; i < histogram.cols; i++) {
01247 histogram.at<float>(0, i) = vfhs->points[0].histogram[i];
01248 }
01249 }
01250 if (is_cvfh) {
01251 pcl::CVFHEstimation<PointT,
01252 pcl::Normal,
01253 pcl::VFHSignature308> cvfh;
01254 cvfh.setInputCloud(cloud);
01255 cvfh.setInputNormals(normal);
01256 pcl::search::KdTree<PointT>::Ptr tree(
01257 new pcl::search::KdTree<PointT>);
01258 cvfh.setSearchMethod(tree);
01259 cvfh.setEPSAngleThreshold(5.0f / 180.0f * M_PI);
01260 cvfh.setCurvatureThreshold(1.0f);
01261 cvfh.setNormalizeBins(false);
01262 pcl::PointCloud<pcl::VFHSignature308>::Ptr cvfhs(
01263 new pcl::PointCloud<pcl::VFHSignature308>());
01264 cvfh.compute(*cvfhs);
01265 histogram = cv::Mat(sizeof(char), 308, CV_32F);
01266 for (int i = 0; i < histogram.cols; i++) {
01267 histogram.at<float>(0, i) = cvfhs->points[0].histogram[i];
01268 }
01269 }
01270 }
01271
01272 void TargetAdaptiveTracking::computeColorHistogram(
01273 const pcl::PointCloud<PointT>::Ptr cloud,
01274 cv::Mat &hist, const int hBin, const int sBin, bool is_norm) const
01275 {
01276 cv::Mat pixels = cv::Mat::zeros(
01277 sizeof(char), static_cast<int>(cloud->size()), CV_8UC3);
01278 for (int i = 0; i < cloud->size(); i++) {
01279 cv::Vec3b pix_val;
01280 pix_val[0] = cloud->points[i].b;
01281 pix_val[1] = cloud->points[i].g;
01282 pix_val[2] = cloud->points[i].r;
01283 pixels.at<cv::Vec3b>(0, i) = pix_val;
01284 }
01285 cv::Mat hsv;
01286 cv::cvtColor(pixels, hsv, CV_BGR2HSV);
01287 int histSize[] = {hBin, sBin};
01288 float h_ranges[] = {0, 180};
01289 float s_ranges[] = {0, 256};
01290 const float* ranges[] = {h_ranges, s_ranges};
01291 int channels[] = {0, 1};
01292 cv::calcHist(
01293 &hsv, 1, channels, cv::Mat(), hist, 2, histSize, ranges, true, false);
01294 if (is_norm) {
01295 cv::normalize(hist, hist, 0, 1, cv::NORM_MINMAX, -1, cv::Mat());
01296 }
01297 }
01298
01299 void TargetAdaptiveTracking::computePointFPFH(
01300 const pcl::PointCloud<PointT>::Ptr cloud,
01301 const pcl::PointCloud<pcl::Normal>::Ptr normals,
01302 cv::Mat &histogram, bool holistic) const
01303 {
01304 if (cloud->empty() || normals->empty()) {
01305 ROS_ERROR("-- ERROR: cannot compute FPFH");
01306 return;
01307 }
01308 pcl::FPFHEstimationOMP<PointT, pcl::Normal, pcl::FPFHSignature33> fpfh;
01309 fpfh.setInputCloud(cloud);
01310 fpfh.setInputNormals(normals);
01311 pcl::search::KdTree<PointT>::Ptr tree (new pcl::search::KdTree<PointT>);
01312 fpfh.setSearchMethod(tree);
01313 pcl::PointCloud<pcl::FPFHSignature33>::Ptr fpfhs(
01314 new pcl::PointCloud<pcl::FPFHSignature33> ());
01315 fpfh.setRadiusSearch(0.05);
01316 fpfh.compute(*fpfhs);
01317 const int hist_dim = 33;
01318 if (holistic) {
01319 histogram = cv::Mat::zeros(1, hist_dim, CV_32F);
01320 for (int i = 0; i < fpfhs->size(); i++) {
01321 for (int j = 0; j < hist_dim; j++) {
01322 histogram.at<float>(0, j) += fpfhs->points[i].histogram[j];
01323 }
01324 }
01325 } else {
01326 histogram = cv::Mat::zeros(
01327 static_cast<int>(fpfhs->size()), hist_dim, CV_32F);
01328 for (int i = 0; i < fpfhs->size(); i++) {
01329 for (int j = 0; j < hist_dim; j++) {
01330 histogram.at<float>(i, j) = fpfhs->points[i].histogram[j];
01331 }
01332 }
01333 }
01334 cv::normalize(histogram, histogram, 0, 1, cv::NORM_MINMAX, -1, cv::Mat());
01335 }
01336
01337 std::vector<pcl::PointIndices::Ptr>
01338 TargetAdaptiveTracking::clusterPointIndicesToPointIndices(
01339 const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_mgs)
01340 {
01341 std::vector<pcl::PointIndices::Ptr> ret;
01342 for (int i = 0; i < indices_mgs->cluster_indices.size(); i++) {
01343 std::vector<int> indices = indices_mgs->cluster_indices[i].indices;
01344 pcl::PointIndices::Ptr pcl_indices (new pcl::PointIndices);
01345 pcl_indices->indices = indices;
01346 ret.push_back(pcl_indices);
01347 }
01348 return ret;
01349 }
01350
01351 void TargetAdaptiveTracking::estimatedPFPose(
01352 const geometry_msgs::PoseStamped::ConstPtr &pose_msg,
01353 PointXYZRPY &motion_displacement)
01354 {
01355 PointXYZRPY current_pose;
01356 current_pose.x = pose_msg->pose.position.x;
01357 current_pose.y = pose_msg->pose.position.y;
01358 current_pose.z = pose_msg->pose.position.z;
01359 current_pose.roll = pose_msg->pose.orientation.x;
01360 current_pose.pitch = pose_msg->pose.orientation.y;
01361 current_pose.yaw = pose_msg->pose.orientation.z;
01362 current_pose.weight = pose_msg->pose.orientation.w;
01363 this->tracker_pose_ = current_pose;
01364 this->current_pose_(0) = current_pose.x;
01365 this->current_pose_(1) = current_pose.y;
01366 this->current_pose_(2) = current_pose.z;
01367 this->current_pose_(3) = 0.0f;
01368 if (!std::isnan(current_pose.x) && !std::isnan(current_pose.y) &&
01369 !std::isnan(current_pose.z)) {
01370 if (!this->motion_history_.empty()) {
01371 int last_index = static_cast<int>(
01372 this->motion_history_.size()) - 1;
01373 motion_displacement.x = current_pose.x -
01374 this->motion_history_[last_index].x;
01375 motion_displacement.y = current_pose.y -
01376 this->motion_history_[last_index].y;
01377 motion_displacement.z = current_pose.z -
01378 this->motion_history_[last_index].z;
01379 motion_displacement.roll = current_pose.roll -
01380 this->motion_history_[last_index].roll;
01381 motion_displacement.pitch = current_pose.pitch -
01382 this->motion_history_[last_index].pitch;
01383 motion_displacement.yaw = current_pose.yaw -
01384 this->motion_history_[last_index].yaw;
01385 } else {
01386 this->motion_history_.push_back(current_pose);
01387 }
01388 } else {
01389
01390 }
01391 }
01392
01393 void TargetAdaptiveTracking::compute3DCentroids(
01394 const pcl::PointCloud<PointT>::Ptr cloud,
01395 Eigen::Vector4f ¢re) const
01396 {
01397 if (cloud->empty()) {
01398 ROS_ERROR("ERROR: empty cloud for centroid");
01399 centre = Eigen::Vector4f(-1, -1, -1, -1);
01400 return;
01401 }
01402 Eigen::Vector4f centroid;
01403 pcl::compute3DCentroid<PointT, float>(*cloud, centroid);
01404 if (!std::isnan(centroid(0)) && !std::isnan(centroid(1)) && !std::isnan(centroid(2))) {
01405 centre = centroid;
01406 }
01407 }
01408
01409 Eigen::Vector4f TargetAdaptiveTracking::cloudMeanNormal(
01410 const pcl::PointCloud<pcl::Normal>::Ptr normal,
01411 bool isnorm)
01412 {
01413 if (normal->empty()) {
01414 return Eigen::Vector4f(0, 0, 0, 0);
01415 }
01416 float x = 0.0f;
01417 float y = 0.0f;
01418 float z = 0.0f;
01419 int icounter = 0;
01420 for (int i = 0; i < normal->size(); i++) {
01421 if ((!std::isnan(normal->points[i].normal_x)) &&
01422 (!std::isnan(normal->points[i].normal_y)) &&
01423 (!std::isnan(normal->points[i].normal_z))) {
01424 x += normal->points[i].normal_x;
01425 y += normal->points[i].normal_y;
01426 z += normal->points[i].normal_z;
01427 icounter++;
01428 }
01429 }
01430 Eigen::Vector4f n_mean = Eigen::Vector4f(
01431 x/static_cast<float>(icounter),
01432 y/static_cast<float>(icounter),
01433 z/static_cast<float>(icounter),
01434 0.0f);
01435 if (isnorm) {
01436 n_mean.normalize();
01437 }
01438 return n_mean;
01439 }
01440
01441 void TargetAdaptiveTracking::computeScatterMatrix(
01442 const pcl::PointCloud<PointT>::Ptr cloud,
01443 const Eigen::Vector4f centroid)
01444 {
01445 if (cloud->empty()) {
01446 ROS_ERROR("Empty input for computing Scatter Matrix");
01447 return;
01448 }
01449 const int rows = 3;
01450 const int cols = 3;
01451 Eigen::MatrixXf scatter_matrix = Eigen::Matrix3f::Zero(cols, rows);
01452 for (int i = 0; i < cloud->size(); i++) {
01453 Eigen::Vector3f de_mean = Eigen::Vector3f();
01454 de_mean(0) = cloud->points[i].x - centroid(0);
01455 de_mean(1) = cloud->points[i].y - centroid(1);
01456 de_mean(2) = cloud->points[i].z - centroid(2);
01457 Eigen::Vector3f t_de_mean = de_mean.transpose();
01458 for (int y = 0; y < rows; y++) {
01459 for (int x = 0; x < cols; x++) {
01460 scatter_matrix(y, x) += de_mean(y) * t_de_mean(x);
01461 }
01462 }
01463 }
01464 Eigen::EigenSolver<Eigen::MatrixXf> eigen_solver(scatter_matrix, true);
01465
01466 }
01467
01468 float TargetAdaptiveTracking::computeCoherency(
01469 const float dist, const float weight) {
01470 if (std::isnan(dist)) {
01471 return 0.0f;
01472 }
01473 return static_cast<float>(1/(1 + (weight * std::pow(dist, 2))));
01474 }
01475
01476 pcl::PointXYZRGBNormal
01477 TargetAdaptiveTracking::convertVector4fToPointXyzRgbNormal(
01478 const Eigen::Vector4f ¢roid,
01479 const Eigen::Vector4f &normal,
01480 const cv::Scalar color) {
01481 pcl::PointXYZRGBNormal pt;
01482 pt.x = centroid(0);
01483 pt.y = centroid(1);
01484 pt.z = centroid(2);
01485 pt.r = color.val[2];
01486 pt.g = color.val[1];
01487 pt.b = color.val[0];
01488 pt.normal_x = normal(0);
01489 pt.normal_y = normal(1);
01490 pt.normal_z = normal(2);
01491 return pt;
01492 }
01493
01494 template<typename T>
01495 void TargetAdaptiveTracking::getRotationMatrixFromRPY(
01496 const PointXYZRPY &motion_displacement,
01497 Eigen::Matrix<T, 3, 3> &rotation)
01498 {
01499 tf::Quaternion tf_quaternion;
01500 tf_quaternion.setEulerZYX(motion_displacement.yaw,
01501 motion_displacement.pitch,
01502 motion_displacement.roll);
01503 Eigen::Quaternion<float> quaternion = Eigen::Quaternion<float>(
01504 tf_quaternion.w(), tf_quaternion.x(),
01505 tf_quaternion.y(), tf_quaternion.z());
01506 rotation.template block<3, 3>(0, 0) =
01507 quaternion.normalized().toRotationMatrix();
01508 }
01509
01510 void TargetAdaptiveTracking::computeLocalPairwiseFeautures(
01511 const std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> &
01512 supervoxel_clusters, const std::map<uint32_t, std::vector<uint32_t> > &
01513 adjacency_list, cv::Mat &histogram, const int feature_count)
01514 {
01515 if (supervoxel_clusters.empty() || adjacency_list.empty()) {
01516 std::cout << supervoxel_clusters.size() << "\t"
01517 << adjacency_list.size() << std::endl;
01518 ROS_ERROR("ERROR: empty data returing no local feautures");
01519 return;
01520 }
01521 float d_pi = 1.0f / (2.0f * static_cast<float> (M_PI));
01522 histogram = cv::Mat::zeros(1, this->bin_size_ * feature_count, CV_32F);
01523 for (std::map<uint32_t, std::vector<uint32_t> >::const_iterator it =
01524 adjacency_list.begin(); it != adjacency_list.end(); it++) {
01525 pcl::Supervoxel<PointT>::Ptr supervoxel =
01526 supervoxel_clusters.at(it->first);
01527 Eigen::Vector4f c_normal = this->cloudMeanNormal(supervoxel->normals_);
01528 std::map<uint32_t, Eigen::Vector4f> cache_normals;
01529 int icounter = 0;
01530 for (std::vector<uint32_t>::const_iterator itr = it->second.begin();
01531 itr != it->second.end(); itr++) {
01532 pcl::Supervoxel<PointT>::Ptr neighbor_supervoxel =
01533 supervoxel_clusters.at(*itr);
01534 Eigen::Vector4f n_normal = this->cloudMeanNormal(
01535 neighbor_supervoxel->normals_);
01536 float alpha;
01537 float phi;
01538 float theta;
01539 float distance;
01540 pcl::computePairFeatures(
01541 supervoxel->centroid_.getVector4fMap(), c_normal,
01542 neighbor_supervoxel->centroid_.getVector4fMap(),
01543 n_normal, alpha, phi, theta, distance);
01544 int bin_index[feature_count];
01545 bin_index[0] = static_cast<int>(
01546 std::floor(this->bin_size_ * ((alpha + M_PI) * d_pi)));
01547 bin_index[1] = static_cast<int>(
01548 std::floor(this->bin_size_ * ((phi + 1.0f) * 0.5f)));
01549 bin_index[2] = static_cast<int>(
01550 std::floor(this->bin_size_ * ((theta + 1.0f) * 0.5f)));
01551 for (int i = 0; i < feature_count; i++) {
01552 if (bin_index[i] < 0) {
01553 bin_index[i] = 0;
01554 }
01555 if (bin_index[i] >= bin_size_) {
01556 bin_index[i] = bin_size_ - sizeof(char);
01557 }
01558
01559
01560 histogram.at<float>(
01561 0, bin_index[i] + (i * this->bin_size_)) += 1;
01562 }
01563 cache_normals[*itr] = n_normal;
01564 icounter++;
01565 }
01566 for (std::vector<uint32_t>::const_iterator itr = it->second.begin();
01567 itr != it->second.end(); itr++) {
01568 cache_normals.find(*itr)->second;
01569 for (std::vector<uint32_t>::const_iterator itr_in =
01570 it->second.begin(); itr_in != it->second.end(); itr_in++) {
01571 if (*itr != *itr_in) {
01572 float alpha;
01573 float phi;
01574 float theta;
01575 float distance;
01576 pcl::computePairFeatures(
01577 supervoxel_clusters.at(*itr)->centroid_.getVector4fMap(),
01578 cache_normals.find(*itr)->second, supervoxel_clusters.at(
01579 *itr_in)->centroid_.getVector4fMap(),
01580 cache_normals.find(*itr_in)->second,
01581 alpha, phi, theta, distance);
01582 int bin_index[feature_count];
01583 bin_index[0] = static_cast<int>(
01584 std::floor(this->bin_size_ * ((alpha + M_PI) * d_pi)));
01585 bin_index[1] = static_cast<int>(
01586 std::floor(this->bin_size_ * ((phi + 1.0f) * 0.5f)));
01587 bin_index[2] = static_cast<int>(
01588 std::floor(this->bin_size_ * ((theta + 1.0f) * 0.5f)));
01589 for (int i = 0; i < feature_count; i++) {
01590 if (bin_index[i] < 0) {
01591 bin_index[i] = 0;
01592 }
01593 if (bin_index[i] >= bin_size_) {
01594 bin_index[i] = bin_size_ - sizeof(char);
01595 }
01596 histogram.at<float>(
01597 0, bin_index[i] + (i * this->bin_size_)) += 1;
01598 }
01599 }
01600 }
01601 }
01602 cv::normalize(
01603 histogram, histogram, 0, 1, cv::NORM_MINMAX, -1, cv::Mat());
01604 }
01605 }
01606
01607
01608 float TargetAdaptiveTracking::templateCloudFilterLenght(
01609 const pcl::PointCloud<PointT>::Ptr cloud)
01610 {
01611 if (cloud->empty()) {
01612 ROS_ERROR("ERROR! Input Cloud is Empty");
01613 return -1.0f;
01614 }
01615 Eigen::Vector4f pivot_pt;
01616 pcl::compute3DCentroid<PointT, float>(*cloud, pivot_pt);
01617 Eigen::Vector4f max_pt;
01618 pcl::getMaxDistance<PointT>(*cloud, pivot_pt, max_pt);
01619 pivot_pt(3) = 0.0f;
01620 max_pt(3) = 0.0f;
01621 float dist = static_cast<float>(pcl::distances::l2(max_pt, pivot_pt));
01622 return (dist);
01623 }
01624
01625 bool TargetAdaptiveTracking::filterPointCloud(
01626 pcl::PointCloud<PointT>::Ptr cloud,
01627 const Eigen::Vector4f tracker_position,
01628 const ModelsPtr template_model,
01629 const float scaling_factor)
01630 {
01631 if (cloud->empty() || template_model->empty()) {
01632 ROS_ERROR("ERROR! Input data is empty is Empty");
01633 return false;
01634 }
01635 pcl::PointCloud<PointT>::Ptr template_cloud(new pcl::PointCloud<PointT>);
01636 for (int i = 0; i < template_model->size(); i++) {
01637 *template_cloud = *template_cloud + *(
01638 template_model->operator[](i).cluster_cloud);
01639 }
01640 float filter_distance = this->templateCloudFilterLenght(template_cloud);
01641 filter_distance *= scaling_factor;
01642 if (filter_distance < 0.05f) {
01643 return false;
01644 }
01645 pcl::PointCloud<PointT>::Ptr cloud_filter(new pcl::PointCloud<PointT>);
01646 pcl::PassThrough<PointT> pass;
01647 pass.setInputCloud(cloud);
01648 pass.setFilterFieldName("x");
01649 float min_x = tracker_position(0) - filter_distance;
01650 float max_x = tracker_position(0) + filter_distance;
01651 pass.setFilterLimits(min_x, max_x);
01652 pass.filter(*cloud_filter);
01653 pass.setInputCloud(cloud_filter);
01654 pass.setFilterFieldName("y");
01655 float min_y = tracker_position(1) - filter_distance;
01656 float max_y = tracker_position(1) + filter_distance;
01657 pass.setFilterLimits(min_y, max_y);
01658 pass.filter(*cloud_filter);
01659 pass.setInputCloud(cloud_filter);
01660 pass.setFilterFieldName("z");
01661 float min_z = tracker_position(2) - filter_distance;
01662 float max_z = tracker_position(2) + filter_distance;
01663 pass.setFilterLimits(min_z, max_z);
01664 pass.filter(*cloud_filter);
01665 if (cloud_filter->empty()) {
01666 return false;
01667 }
01668 cloud->empty();
01669 pcl::copyPointCloud<PointT, PointT>(*cloud_filter, *cloud);
01670 return true;
01671 }
01672
01673 void TargetAdaptiveTracking::transformModelPrimitives(
01674 const ModelsPtr &obj_ref,
01675 ModelsPtr trans_models,
01676 const Eigen::Affine3f &transform_model)
01677 {
01678 if (obj_ref->empty()) {
01679 ROS_ERROR("ERROR! No Object Model to Transform");
01680 return;
01681 }
01682 for (int i = 0; i < obj_ref->size(); i++) {
01683 pcl::PointCloud<PointT>::Ptr trans_cloud(
01684 new pcl::PointCloud<PointT>);
01685 pcl::transformPointCloud(*(obj_ref->operator[](i).cluster_cloud),
01686 *trans_cloud, transform_model);
01687 Eigen::Vector4f trans_centroid = Eigen::Vector4f();
01688 pcl::compute3DCentroid<PointT, float>(
01689 *trans_cloud, trans_centroid);
01690 trans_models->push_back(obj_ref->operator[](i));
01691 trans_models->operator[](i).cluster_cloud = trans_cloud;
01692 trans_models->operator[](i).cluster_centroid = trans_centroid;
01693 }
01694 }
01695
01696 void TargetAdaptiveTracking::filterCloudForBoundingBoxViz(
01697 pcl::PointCloud<PointT>::Ptr cloud,
01698 const ModelsPtr background_reference,
01699 const float threshold)
01700 {
01701 if (cloud->empty() || background_reference->empty()) {
01702 ROS_ERROR("ERROR! EMPTY DATA FOR BOUNDING BOX CLOUD");
01703 return;
01704 }
01705 ModelsPtr tmp_model(new Models);
01706 this->processInitCloud(cloud, tmp_model);
01707 pcl::PointCloud<PointT>::Ptr tmp_cloud(new pcl::PointCloud<PointT>);
01708 for (int i = 0; i < tmp_model->size(); i++) {
01709 Eigen::Vector4f surfel_centroid = Eigen::Vector4f();
01710 surfel_centroid = tmp_model->operator[](i).cluster_centroid;
01711 surfel_centroid(3) = 0.0f;
01712 float surfel_dist = static_cast<float>(
01713 pcl::distances::l2(surfel_centroid, current_pose_));
01714 if (surfel_dist < (this->previous_distance_ * growth_rate_)) {
01715 float probability = 0.0f;
01716 for (int j = 0; j < background_reference->size(); j++) {
01717 ReferenceModel *r_mod = new ReferenceModel;
01718 float prob = this->targetCandidateToReferenceLikelihood<float>(
01719 tmp_model->operator[](i),
01720 background_reference->operator[](j).cluster_cloud,
01721 background_reference->operator[](j).cluster_normals,
01722 background_reference->operator[](j).cluster_centroid,
01723 r_mod);
01724 if (prob > probability) {
01725 probability = prob;
01726 }
01727 }
01728 if (probability < 0.60f) {
01729 *tmp_cloud = *tmp_cloud + *(
01730 tmp_model->operator[](i).cluster_cloud);
01731 } else {
01732 this->object_reference_->push_back(tmp_model->operator[](i));
01733 }
01734 }
01735 }
01736 if (tmp_cloud->size() > (static_cast<int>(cloud->size() / 4))) {
01737 cloud->clear();
01738 pcl::copyPointCloud<PointT, PointT>(*tmp_cloud, *cloud);
01739 }
01740 }
01741
01742 template<typename T, typename U, typename V>
01743 cv::Scalar TargetAdaptiveTracking::plotJetColour(
01744 T v, U vmin, V vmax)
01745 {
01746 cv::Scalar c = cv::Scalar(0.0, 0.0, 0.0);
01747 T dv;
01748 if (v < vmin)
01749 v = vmin;
01750 if (v > vmax)
01751 v = vmax;
01752 dv = vmax - vmin;
01753 if (v < (vmin + 0.25 * dv)) {
01754 c.val[0] = 0;
01755 c.val[1] = 4 * (v - vmin) / dv;
01756 } else if (v < (vmin + 0.5 * dv)) {
01757 c.val[0] = 0;
01758 c.val[2] = 1 + 4 * (vmin + 0.25 * dv - v) / dv;
01759 } else if (v < (vmin + 0.75 * dv)) {
01760 c.val[0] = 4 * (v - vmin - 0.5 * dv) / dv;
01761 c.val[2] = 0;
01762 } else {
01763 c.val[1] = 1 + 4 * (vmin + 0.75 * dv - v) / dv;
01764 c.val[2] = 0;
01765 }
01766 return(c);
01767 }
01768
01769 void TargetAdaptiveTracking::supervoxelSegmentation(
01770 const pcl::PointCloud<PointT>::Ptr cloud,
01771 std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr > &supervoxel_clusters,
01772 std::multimap<uint32_t, uint32_t> &supervoxel_adjacency,
01773 const float seed_resolution)
01774 {
01775 if (cloud->empty() || seed_resolution <= 0.0f) {
01776 ROS_ERROR("ERROR: Supervoxel input cloud empty...\n Incorrect Seed");
01777 return;
01778 }
01779 boost::mutex::scoped_lock lock(mutex_);
01780 pcl::SupervoxelClustering<PointT> super(
01781 voxel_resolution_,
01782 static_cast<double>(seed_resolution),
01783 use_transform_);
01784 super.setInputCloud(cloud);
01785 super.setColorImportance(color_importance_);
01786 super.setSpatialImportance(spatial_importance_);
01787 super.setNormalImportance(normal_importance_);
01788 supervoxel_clusters.clear();
01789 super.extract(supervoxel_clusters);
01790 super.getSupervoxelAdjacency(supervoxel_adjacency);
01791 }
01792
01793 void TargetAdaptiveTracking::supervoxelSegmentation(
01794 const pcl::PointCloud<PointT>::Ptr cloud,
01795 std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr > &supervoxel_clusters,
01796 std::multimap<uint32_t, uint32_t> &supervoxel_adjacency)
01797 {
01798 if (cloud->empty()) {
01799 ROS_ERROR("ERROR: Supervoxel input cloud empty...");
01800 return;
01801 }
01802 boost::mutex::scoped_lock lock(mutex_);
01803 pcl::SupervoxelClustering<PointT> super(voxel_resolution_,
01804 seed_resolution_,
01805 use_transform_);
01806 super.setInputCloud(cloud);
01807 super.setColorImportance(color_importance_);
01808 super.setSpatialImportance(spatial_importance_);
01809 super.setNormalImportance(normal_importance_);
01810 supervoxel_clusters.clear();
01811 super.extract(supervoxel_clusters);
01812 super.getSupervoxelAdjacency(supervoxel_adjacency);
01813 }
01814
01815 void TargetAdaptiveTracking::publishSupervoxel(
01816 const std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr> supervoxel_clusters,
01817 sensor_msgs::PointCloud2 &ros_cloud,
01818 jsk_recognition_msgs::ClusterPointIndices &ros_indices,
01819 const std_msgs::Header &header)
01820 {
01821 pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
01822 std::vector<pcl::PointIndices> all_indices;
01823 for (std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr >::const_iterator
01824 it = supervoxel_clusters.begin();
01825 it != supervoxel_clusters.end();
01826 ++it) {
01827 pcl::Supervoxel<PointT>::Ptr super_voxel = it->second;
01828 pcl::PointCloud<PointT>::Ptr super_voxel_cloud = super_voxel->voxels_;
01829 pcl::PointIndices indices;
01830 for (size_t i = 0; i < super_voxel_cloud->size(); i++) {
01831 indices.indices.push_back(i + output->points.size());
01832 }
01833 all_indices.push_back(indices);
01834 *output = *output + *super_voxel_cloud;
01835 }
01836 ros_indices.cluster_indices.clear();
01837 ros_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
01838 all_indices, header);
01839 ros_cloud.data.clear();
01840 pcl::toROSMsg(*output, ros_cloud);
01841 ros_indices.header = header;
01842 ros_cloud.header = header;
01843 }
01844
01845 void TargetAdaptiveTracking::targetDescriptiveSurfelsIndices(
01846 const jsk_recognition_msgs::ClusterPointIndices &sv_indices,
01847 const std::vector<uint32_t> &tdp_list,
01848 jsk_recognition_msgs::ClusterPointIndices &ros_indices)
01849 {
01850 ros_indices.cluster_indices.clear();
01851 for (std::vector<uint32_t>::const_iterator it = tdp_list.begin();
01852 it != tdp_list.end(); it++) {
01853 ros_indices.cluster_indices.push_back(sv_indices.cluster_indices[*it]);
01854 }
01855 ros_indices.header = sv_indices.header;
01856 }
01857
01858 void TargetAdaptiveTracking::configCallback(
01859 Config &config, uint32_t level)
01860 {
01861 boost::mutex::scoped_lock lock(mutex_);
01862 this->color_importance_ = config.color_importance;
01863 this->spatial_importance_ = config.spatial_importance;
01864 this->normal_importance_ = config.normal_importance;
01865 this->voxel_resolution_ = config.voxel_resolution;
01866 this->seed_resolution_ = config.seed_resolution;
01867 this->use_transform_ = config.use_transform;
01868
01869 this->min_cluster_size_ = static_cast<int>(config.min_cluster_size);
01870 this->threshold_ = static_cast<float>(config.threshold);
01871 this->bin_size_ = static_cast<int>(config.bin_size);
01872 this->eps_distance_ = static_cast<float>(config.eps_distance);
01873 this->eps_min_samples_ = static_cast<float>(config.eps_min_samples);
01874 this->vfh_scaling_ = static_cast<float>(config.vfh_scaling);
01875 this->color_scaling_ = static_cast<float>(config.color_scaling);
01876 this->structure_scaling_ = static_cast<float>(config.structure_scaling);
01877 this->update_tracker_reference_ = config.update_tracker_reference;
01878 this->update_filter_template_ = config.update_filter_template;
01879 this->history_window_size_ = static_cast<int>(config.history_window_size);
01880 }
01881 }
01882
01883 #include <pluginlib/class_list_macros.h>
01884 PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::TargetAdaptiveTracking, nodelet::Nodelet);