localization.cpp
Go to the documentation of this file.
00001 #include <agile_grasp/localization.h>
00002 
00003 std::vector<GraspHypothesis> Localization::localizeHands(const PointCloud::Ptr& cloud_in, int size_left,
00004         const std::vector<int>& indices, bool calculates_antipodal, bool uses_clustering)
00005 {
00006         double t0 = omp_get_wtime();
00007         std::vector<GraspHypothesis> hand_list;
00008 
00009         // set camera source for all points (0 = left, 1 = right)
00010         std::cout << "Generating camera sources for " << cloud_in->size() << " points ...\n";
00011         Eigen::VectorXi pts_cam_source(cloud_in->size());
00012         if (size_left == cloud_in->size())
00013                 pts_cam_source << Eigen::VectorXi::Zero(size_left);
00014         else
00015                 pts_cam_source << Eigen::VectorXi::Zero(size_left), Eigen::VectorXi::Ones(cloud_in->size() - size_left);
00016                 
00017         // remove NAN points from the cloud
00018         std::vector<int> nan_indices;
00019         pcl::removeNaNFromPointCloud(*cloud_in, *cloud_in, nan_indices);
00020 
00021         // reduce point cloud to workspace
00022         std::cout << "Filtering workspace ...\n";
00023         PointCloud::Ptr cloud(new PointCloud);
00024         filterWorkspace(cloud_in, pts_cam_source, cloud, pts_cam_source);
00025         std::cout << " " << cloud->size() << " points left\n";
00026 
00027         // store complete cloud for later plotting
00028         PointCloud::Ptr cloud_plot(new PointCloud);
00029         *cloud_plot = *cloud;
00030         *cloud_ = *cloud;
00031 
00032         // voxelize point cloud
00033         std::cout << "Voxelizing point cloud\n";
00034         double t1_voxels = omp_get_wtime();
00035         voxelizeCloud(cloud, pts_cam_source, cloud, pts_cam_source, 0.003);
00036         double t2_voxels = omp_get_wtime() - t1_voxels;
00037         std::cout << " Created " << cloud->points.size() << " voxels in " << t2_voxels << " sec\n";
00038 
00039         // plot camera source for each point in the cloud
00040         if (plots_camera_sources_)
00041                 plot_.plotCameraSource(pts_cam_source, cloud);
00042 
00043         if (uses_clustering)
00044         {
00045     std::cout << "Finding point cloud clusters ... \n";
00046         
00047                 // Create the segmentation object for the planar model and set all the parameters
00048                 pcl::SACSegmentation<pcl::PointXYZ> seg;
00049                 pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
00050                 pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
00051                 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_plane(new pcl::PointCloud<pcl::PointXYZ>());
00052                 seg.setOptimizeCoefficients(true);
00053                 seg.setModelType(pcl::SACMODEL_PLANE);
00054                 seg.setMethodType(pcl::SAC_RANSAC);
00055                 seg.setMaxIterations(100);
00056                 seg.setDistanceThreshold(0.01);
00057 
00058                 // Segment the largest planar component from the remaining cloud
00059                 seg.setInputCloud(cloud);
00060                 seg.segment(*inliers, *coefficients);
00061                 if (inliers->indices.size() == 0)
00062                 {
00063                         std::cout << " Could not estimate a planar model for the given dataset." << std::endl;
00064                         hand_list.resize(0);
00065                         return hand_list;
00066                 }
00067     
00068     std::cout << " PointCloud representing the planar component: " << inliers->indices.size()
00069       << " data points." << std::endl;
00070 
00071                 // Extract the nonplanar inliers
00072                 pcl::ExtractIndices<pcl::PointXYZ> extract;
00073                 extract.setInputCloud(cloud);
00074                 extract.setIndices(inliers);
00075                 extract.setNegative(true);
00076                 std::vector<int> indices_cluster;
00077                 extract.filter(indices_cluster);
00078                 PointCloud::Ptr cloud_cluster(new PointCloud);
00079                 cloud_cluster->points.resize(indices_cluster.size());
00080                 Eigen::VectorXi cluster_cam_source(indices_cluster.size());
00081                 for (int i = 0; i < indices_cluster.size(); i++)
00082                 {
00083                         cloud_cluster->points[i] = cloud->points[indices_cluster[i]];
00084                         cluster_cam_source[i] = pts_cam_source[indices_cluster[i]];
00085                 }
00086                 cloud = cloud_cluster;
00087                 *cloud_plot = *cloud;
00088                 std::cout << " PointCloud representing the non-planar component: " << cloud->points.size()
00089       << " data points." << std::endl;
00090         }
00091 
00092         // draw down-sampled and workspace reduced cloud
00093         cloud_plot = cloud;
00094   
00095   // find hand configurations
00096   HandSearch hand_search(finger_width_, hand_outer_diameter_, hand_depth_, 
00097     hand_height_, init_bite_, num_threads_, num_samples_, plots_hands_);
00098         hand_list = hand_search.findHands(cloud, pts_cam_source, indices, cloud_plot, 
00099     calculates_antipodal, uses_clustering);
00100 
00101         // remove hands at boundaries of workspace
00102         if (filters_boundaries_)
00103   {
00104     std::cout << "Filtering out hands close to workspace boundaries ...\n";
00105     hand_list = filterHands(hand_list);
00106     std::cout << " # hands left: " << hand_list.size() << "\n";
00107   }
00108 
00109         double t2 = omp_get_wtime();
00110         std::cout << "Hand localization done in " << t2 - t0 << " sec\n";
00111 
00112         if (plots_hands_)
00113                 plot_.plotHands(hand_list, cloud_plot, "");
00114 
00115         return hand_list;
00116 }
00117 
00118 std::vector<GraspHypothesis> Localization::predictAntipodalHands(
00119         const std::vector<GraspHypothesis>& hand_list, const std::string& svm_filename)
00120 {
00121         double t0 = omp_get_wtime();
00122         std::vector<GraspHypothesis> antipodal_hands;
00123         Learning learn(num_threads_);
00124         Eigen::Matrix<double, 3, 2> cams_mat;
00125         cams_mat.col(0) = cam_tf_left_.block<3, 1>(0, 3);
00126         cams_mat.col(1) = cam_tf_right_.block<3, 1>(0, 3);
00127         antipodal_hands = learn.classify(hand_list, svm_filename, cams_mat);
00128         std::cout << " runtime: " << omp_get_wtime() - t0 << " sec\n";
00129         std::cout << antipodal_hands.size() << " antipodal hand configurations found\n"; 
00130   if (plots_hands_)
00131                 plot_.plotHands(hand_list, antipodal_hands, cloud_, "Antipodal Hands");
00132         return antipodal_hands;
00133 }
00134 
00135 std::vector<GraspHypothesis> Localization::localizeHands(const std::string& pcd_filename_left,
00136         const std::string& pcd_filename_right, bool calculates_antipodal, bool uses_clustering)
00137 {
00138         std::vector<int> indices(0);
00139         return localizeHands(pcd_filename_left, pcd_filename_right, indices, calculates_antipodal, uses_clustering);
00140 }
00141 
00142 std::vector<GraspHypothesis> Localization::localizeHands(const std::string& pcd_filename_left,
00143         const std::string& pcd_filename_right, const std::vector<int>& indices, bool calculates_antipodal,
00144         bool uses_clustering)
00145 {
00146         double t0 = omp_get_wtime();
00147 
00148         // load point clouds
00149         PointCloud::Ptr cloud_left(new PointCloud);
00150         if (pcl::io::loadPCDFile<pcl::PointXYZ>(pcd_filename_left, *cloud_left) == -1) //* load the file
00151         {
00152                 PCL_ERROR("Couldn't read pcd_filename_left file \n");
00153                 std::vector<GraspHypothesis> hand_list(0);
00154                 return hand_list;
00155         }
00156         if (pcd_filename_right.length() > 0)
00157                 std::cout << "Loaded left point cloud with " << cloud_left->width * cloud_left->height << " data points.\n";
00158         else
00159                 std::cout << "Loaded point cloud with " << cloud_left->width * cloud_left->height << " data points.\n";
00160 
00161         PointCloud::Ptr cloud_right(new PointCloud);
00162         if (pcd_filename_right.length() > 0)
00163         {
00164                 if (pcl::io::loadPCDFile<pcl::PointXYZ>(pcd_filename_right, *cloud_right) == -1) //* load the file
00165                 {
00166                         PCL_ERROR("Couldn't read pcd_filename_right file \n");
00167                         std::vector<GraspHypothesis> hand_list(0);
00168                         return hand_list;
00169                 }
00170                 std::cout << "Loaded right point cloud with " << cloud_right->width * cloud_right->height << " data points.\n";
00171                 std::cout << "Loaded both clouds in " << omp_get_wtime() - t0 << " sec\n";
00172         }
00173         
00174         // concatenate point clouds
00175         std::cout << "Concatenating point clouds ...\n";
00176         PointCloud::Ptr cloud(new PointCloud);
00177         *cloud = *cloud_left + *cloud_right;
00178 
00179         return localizeHands(cloud, cloud_left->size(), indices, calculates_antipodal, uses_clustering);
00180 }
00181 
00182 void Localization::filterWorkspace(const PointCloud::Ptr& cloud_in, const Eigen::VectorXi& pts_cam_source_in,
00183         PointCloud::Ptr& cloud_out, Eigen::VectorXi& pts_cam_source_out)
00184 {
00185         std::vector<int> indices(cloud_in->points.size());
00186         int c = 0;
00187         PointCloud::Ptr cloud(new PointCloud);
00188 //  std::cout << "workspace_: " << workspace_.transpose() << "\n";
00189 
00190         for (int i = 0; i < cloud_in->points.size(); i++)
00191         {
00192 //    std::cout << "i: " << i << "\n";
00193                 const pcl::PointXYZ& p = cloud_in->points[i];
00194                 if (p.x >= workspace_(0) && p.x <= workspace_(1) && p.y >= workspace_(2) && p.y <= workspace_(3)
00195                                 && p.z >= workspace_(4) && p.z <= workspace_(5))
00196                 {
00197                         cloud->points.push_back(p);
00198                         indices[c] = i;
00199                         c++;
00200                 }
00201         }
00202 
00203         Eigen::VectorXi pts_cam_source(c);
00204         for (int i = 0; i < pts_cam_source.size(); i++)
00205         {
00206                 pts_cam_source(i) = pts_cam_source_in(indices[i]);
00207         }
00208 
00209         cloud_out = cloud;
00210         pts_cam_source_out = pts_cam_source;
00211 }
00212 
00213 void Localization::voxelizeCloud(const PointCloud::Ptr& cloud_in, const Eigen::VectorXi& pts_cam_source_in,
00214         PointCloud::Ptr& cloud_out, Eigen::VectorXi& pts_cam_source_out, double cell_size)
00215 {
00216         Eigen::Vector3d min_left, min_right;
00217         min_left << 10000, 10000, 10000;
00218         min_right << 10000, 10000, 10000;
00219         Eigen::Matrix3Xd pts(3, cloud_in->points.size());
00220         int num_left = 0;
00221         int num_right = 0;
00222         for (int i = 0; i < cloud_in->points.size(); i++)
00223         {
00224                 if (pts_cam_source_in(i) == 0)
00225                 {
00226                         if (cloud_in->points[i].x < min_left(0))
00227                                 min_left(0) = cloud_in->points[i].x;
00228                         if (cloud_in->points[i].y < min_left(1))
00229                                 min_left(1) = cloud_in->points[i].y;
00230                         if (cloud_in->points[i].z < min_left(2))
00231                                 min_left(2) = cloud_in->points[i].z;
00232                         num_left++;
00233                 }
00234                 else if (pts_cam_source_in(i) == 1)
00235                 {
00236                         if (cloud_in->points[i].x < min_right(0))
00237                                 min_right(0) = cloud_in->points[i].x;
00238                         if (cloud_in->points[i].y < min_right(1))
00239                                 min_right(1) = cloud_in->points[i].y;
00240                         if (cloud_in->points[i].z < min_right(2))
00241                                 min_right(2) = cloud_in->points[i].z;
00242                         num_right++;
00243                 }
00244                 pts.col(i) = cloud_in->points[i].getVector3fMap().cast<double>();
00245         }
00246 
00247         // find the cell that each point falls into
00248         std::set<Eigen::Vector3i, Localization::UniqueVectorComparator> bins_left;
00249         std::set<Eigen::Vector3i, Localization::UniqueVectorComparator> bins_right;
00250         int prev;
00251         for (int i = 0; i < pts.cols(); i++)
00252         {
00253                 if (pts_cam_source_in(i) == 0)
00254                 {
00255                         Eigen::Vector3i v = floorVector((pts.col(i) - min_left) / cell_size);
00256                         bins_left.insert(v);
00257                         prev = bins_left.size();
00258                 }
00259                 else if (pts_cam_source_in(i) == 1)
00260                 {
00261                         Eigen::Vector3i v = floorVector((pts.col(i) - min_right) / cell_size);
00262                         bins_right.insert(v);
00263                 }
00264         }
00265 
00266         // calculate the cell values
00267         Eigen::Matrix3Xd voxels_left(3, bins_left.size());
00268         Eigen::Matrix3Xd voxels_right(3, bins_right.size());
00269         int i = 0;
00270         for (std::set<Eigen::Vector3i, Localization::UniqueVectorComparator>::iterator it = bins_left.begin();
00271                         it != bins_left.end(); it++)
00272         {
00273                 voxels_left.col(i) = (*it).cast<double>();
00274                 i++;
00275         }
00276         i = 0;
00277         for (std::set<Eigen::Vector3i, Localization::UniqueVectorComparator>::iterator it = bins_right.begin();
00278                         it != bins_right.end(); it++)
00279         {
00280                 voxels_right.col(i) = (*it).cast<double>();
00281                 i++;
00282         }
00283 
00284         voxels_left.row(0) = voxels_left.row(0) * cell_size
00285                         + Eigen::VectorXd::Ones(voxels_left.cols()) * min_left(0);
00286         voxels_left.row(1) = voxels_left.row(1) * cell_size
00287                         + Eigen::VectorXd::Ones(voxels_left.cols()) * min_left(1);
00288         voxels_left.row(2) = voxels_left.row(2) * cell_size
00289                         + Eigen::VectorXd::Ones(voxels_left.cols()) * min_left(2);
00290         voxels_right.row(0) = voxels_right.row(0) * cell_size
00291                         + Eigen::VectorXd::Ones(voxels_right.cols()) * min_right(0);
00292         voxels_right.row(1) = voxels_right.row(1) * cell_size
00293                         + Eigen::VectorXd::Ones(voxels_right.cols()) * min_right(1);
00294         voxels_right.row(2) = voxels_right.row(2) * cell_size
00295                         + Eigen::VectorXd::Ones(voxels_right.cols()) * min_right(2);
00296 
00297         PointCloud::Ptr cloud(new PointCloud);
00298         cloud->resize(bins_left.size() + bins_right.size());
00299         Eigen::VectorXi pts_cam_source(bins_left.size() + bins_right.size());
00300         for (int i = 0; i < bins_left.size(); i++)
00301         {
00302                 pcl::PointXYZ p;
00303                 p.x = voxels_left(0, i);
00304                 p.y = voxels_left(1, i);
00305                 p.z = voxels_left(2, i);
00306                 cloud->points[i] = p;
00307                 pts_cam_source(i) = 0;
00308         }
00309         for (int i = 0; i < bins_right.size(); i++)
00310         {
00311                 pcl::PointXYZ p;
00312                 p.x = voxels_right(0, i);
00313                 p.y = voxels_right(1, i);
00314                 p.z = voxels_right(2, i);
00315                 cloud->points[bins_left.size() + i] = p;
00316                 pts_cam_source(bins_left.size() + i) = 1;
00317         }
00318 
00319         cloud_out = cloud;
00320         pts_cam_source_out = pts_cam_source;
00321 }
00322 
00323 Eigen::Vector3i Localization::floorVector(const Eigen::Vector3d& a)
00324 {
00325         Eigen::Vector3i b;
00326         b << floor(a(0)), floor(a(1)), floor(a(2));
00327         return b;
00328 }
00329 
00330 std::vector<GraspHypothesis> Localization::filterHands(const std::vector<GraspHypothesis>& hand_list)
00331 {
00332         const double MIN_DIST = 0.02;
00333 
00334         std::vector<GraspHypothesis> filtered_hand_list;
00335 
00336         for (int i = 0; i < hand_list.size(); i++)
00337         {
00338                 const Eigen::Vector3d& center = hand_list[i].getGraspSurface();
00339                 int k;
00340                 for (k = 0; k < workspace_.size(); k++)
00341                 {
00342                         if (fabs((center(floor(k / 2.0)) - workspace_(k))) < MIN_DIST)
00343                         {
00344                                 break;
00345                         }
00346                 }
00347                 if (k == workspace_.size())
00348                 {
00349                         filtered_hand_list.push_back(hand_list[i]);
00350                 }
00351         }
00352 
00353         return filtered_hand_list;
00354 }
00355 
00356 std::vector<Handle> Localization::findHandles(const std::vector<GraspHypothesis>& hand_list, int min_inliers,
00357         double min_length, bool is_plotting)
00358 {
00359         HandleSearch handle_search;
00360         std::vector<Handle> handles = handle_search.findHandles(hand_list, min_inliers, min_length);
00361         if (is_plotting)
00362                 handle_search.plotHandles(handles, cloud_, "");
00363         return handles;
00364 }


agile_grasp
Author(s):
autogenerated on Thu Aug 27 2015 12:01:28