patch_search.cpp
Go to the documentation of this file.
00001 
00002 #include <iostream>
00003 #include <limits>
00004 #include <cmath>
00005 #include <cstdlib>
00006 #include <map>
00007 
00008 #include <boost/thread/thread.hpp>
00009 #include <pcl/common/common_headers.h>
00010 #include <pcl/common/common_headers.h>
00011 #include <pcl/features/normal_3d.h>
00012 #include <pcl/io/pcd_io.h>
00013 #include <pcl/console/parse.h>
00014 #include <pcl/point_types.h>
00015 #include <pcl/filters/statistical_outlier_removal.h>
00016 #include <pcl/filters/passthrough.h>
00017 
00018 #include <sensor_msgs/PointCloud2.h>
00019 #include <sensor_msgs/point_cloud_conversion.h>
00020 
00021 #include <ros/ros.h>
00022 #include <pcl_ros/transforms.h>
00023 #include <sensor_msgs/PointCloud2.h>
00024 
00025 #include <tf/tf.h>
00026 #include <visualization_msgs/Marker.h>
00027 #include <visualization_msgs/MarkerArray.h>
00028 #include <eigen3/Eigen/src/Core/EigenBase.h>
00029 #include <eigen3/Eigen/src/Geometry/Quaternion.h>
00030 
00031 #include <octomap_ros/OctomapROS.h>
00032 #include <octomap/octomap.h>
00033 #include <octomap_ros/conversions.h>
00034 
00035 #include <surfacelet/SurfacePatch.h>
00036 #include <surfacelet/PatchMap.h>
00037 
00038 #include <omp.h>
00039 using namespace std;
00040 
00041 unsigned int text_id = 0;
00042 pcl::PointCloud<pcl::PointXYZ> cloud;
00043 pcl::PointCloud<pcl::PointXYZ> cloud_nans_removed;
00044 pcl::PointCloud<pcl::PointXYZ> cloud_not_used;
00045 bool cloud_received = false;
00046 
00047 void filterXYZ(pcl::PointCloud<pcl::PointXYZ> &cloud, pcl::PointCloud<pcl::PointXYZ> &cloud_filtered, double min_x,
00048         double max_x, double min_y, double max_y, double min_z, double max_z) {
00049 
00050     pcl::PassThrough<pcl::PointXYZ> pass;
00051 
00052     // filter x
00053     pass.setInputCloud(boost::make_shared<pcl::PointCloud<pcl::PointXYZ> >(cloud));
00054     pass.setFilterFieldName("x");
00055     pass.setFilterLimits(min_x, max_x);
00056     pass.filter(cloud_filtered);
00057 
00058     // filter y
00059     pass.setInputCloud(boost::make_shared<pcl::PointCloud<pcl::PointXYZ> >(cloud_filtered));
00060     pass.setFilterFieldName("y");
00061     pass.setFilterLimits(min_y, max_y);
00062     pass.filter(cloud_filtered);
00063 
00064     // filter z
00065     pass.setInputCloud(boost::make_shared<pcl::PointCloud<pcl::PointXYZ> >(cloud_filtered));
00066     pass.setFilterFieldName("z");
00067     pass.setFilterLimits(min_z, max_z);
00068     pass.filter(cloud_filtered);
00069 
00070 }
00071 
00072 inline pcl::PointXYZ VectorEigen2PointXYZ(Eigen::Vector3f v) {
00073     pcl::PointXYZ p;
00074     p.x = v[0];
00075     p.y = v[1];
00076     p.z = v[2];
00077     return p;
00078 }
00079 
00080 void graphSegmentation(const Eigen::MatrixXi adjacency, std::vector<std::set<int> >& subgraphs) {
00081 
00082     subgraphs.clear();
00083 
00084     std::set<int> usable_indexes;
00085     for (unsigned int i = 0; i < adjacency.rows(); i++) {
00086         usable_indexes.insert(i);
00087     }
00088 
00089     while (usable_indexes.size() > 0) {
00090 
00091         std::cout << "index size " << usable_indexes.size() << std::endl;
00092         std::set<int> tmp_set;
00093 
00094         //sample point from set
00095         std::set<int>::iterator it = usable_indexes.begin();
00096         std::advance(it, rand() % usable_indexes.size());
00097         int index = *it;
00098 
00099         //check connectivity for the index
00100         for (int j = 0; j < adjacency.rows(); ++j) {
00101             if (adjacency(index, j) == 1) {
00102                 tmp_set.insert(j);
00103 
00104                 //remove from set
00105                 it = usable_indexes.find(j);
00106                 if (!(it == usable_indexes.end())) usable_indexes.erase(it);
00107             }
00108         }
00109         //remove from set
00110         it = usable_indexes.find(index);
00111         if (!(it == usable_indexes.end())) usable_indexes.erase(it);
00112 
00113         subgraphs.push_back(tmp_set);
00114     }
00115 }
00116 
00117 void depthFirstSearch(const int node, Eigen::MatrixXi& adjacency, std::set<int>& graph) {
00118 
00119     graph.insert(node);
00120     for (int i = 0; i < adjacency.cols(); ++i) {
00121         if (adjacency(node, i) == 1) {
00122             adjacency(node, i) = 0;
00123             depthFirstSearch(i, adjacency, graph);
00124         }
00125     }
00126 }
00127 
00128 void connectedComponents(const Eigen::MatrixXi& adjacency, std::vector<std::set<int> >& subgraphs) {
00129     subgraphs.clear();
00130 
00131     std::set<int> usable_indexes;
00132     for (unsigned int i = 0; i < adjacency.rows(); i++) {
00133         usable_indexes.insert(i);
00134     }
00135     Eigen::MatrixXi tmp = adjacency;
00136 
00137     while (usable_indexes.size() > 0) {
00138 
00139         std::cout << "index size " << usable_indexes.size() << std::endl;
00140         std::set<int> tmp_set;
00141 
00142         //sample point from set
00143         std::set<int>::iterator it = usable_indexes.begin();
00144         std::advance(it, rand() % usable_indexes.size());
00145         int index = *it;
00146 
00147         depthFirstSearch(index, tmp, tmp_set);
00148 
00149         int i = 0;
00150         //check connectivity for the index
00151         BOOST_FOREACH(i, tmp_set)
00152         {
00153             //remove from set
00154             it = usable_indexes.find(i);
00155             if (!(it == usable_indexes.end())) usable_indexes.erase(it);
00156         }
00157         if (tmp_set.size() > 1) {
00158             subgraphs.push_back(tmp_set);
00159         }
00160     }
00161 }
00162 
00163 void cloudCallBack(const sensor_msgs::PointCloud2ConstPtr& msg) {
00164 
00165     if (!cloud_received) {
00166 
00167         pcl::fromROSMsg(*msg, cloud);
00168         pcl::PointCloud<pcl::PointXYZ> tmp_cloud;
00169         filterXYZ(cloud, tmp_cloud, -0.5, 0.3, -0.5, 0.4, -2.0, 1.0);
00170 //        filterXYZ(cloud,tmp_cloud, -2.0, 2.0, -2.0, 2.0, -2.0,2.0);
00171         for (unsigned int i = 0; i < tmp_cloud.points.size(); ++i) {
00172             if (!pcl_isnan (tmp_cloud.points[i].x) && !pcl_isnan (tmp_cloud.points[i].y)
00173                     && !pcl_isnan (tmp_cloud.points[i].z)) {
00174                 cloud_nans_removed.points.push_back(tmp_cloud.points[i]);
00175             }
00176         }
00177         cloud_nans_removed.is_dense = false;
00178         cloud_nans_removed.height = 1;
00179         cloud_nans_removed.width = cloud_nans_removed.points.size();
00180 
00181         pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
00182         sor.setInputCloud(cloud_nans_removed.makeShared());
00183         sor.setMeanK(50);
00184         sor.setStddevMulThresh(1.0);
00185         sor.filter(tmp_cloud);
00186         cloud_nans_removed = tmp_cloud;
00187         cloud_received = true;
00188     }
00189 
00190 }
00191 
00192 void constructSolutionMarker(pcl::PointCloud<pcl::PointXYZ> surface_samples,
00193         const std::vector<std::vector<unsigned int> >& solutions, const std::string frame_id,
00194         std::vector<visualization_msgs::Marker>& marker_list) {
00195 
00196     marker_list.clear();
00197     visualization_msgs::Marker marker;
00198 
00199     // Set the frame ID and timestamp.  See the TF tutorials for information on these.
00200     marker.header.frame_id = frame_id;
00201     marker.header.stamp = ros::Time::now();
00202 
00203     // Set the namespace and id for this marker.  This serves to create a unique ID
00204     // Any marker sent with the same namespace and id will overwrite the old one
00205     marker.ns = "coverage";
00206 
00207     // Set the marker type.  Initially this is CUBE, and cycles between that and SPHERE, ARROW, and CYLINDER
00208     marker.type = visualization_msgs::Marker::LINE_LIST;
00209 
00210     // Set the marker action.  Options are ADD and DELETE
00211     marker.action = visualization_msgs::Marker::MODIFY;
00212 
00213     // Set the scale of the marker -- 1x1x1 here means 1m on a side
00214     marker.scale.x = 0.01;
00215     marker.scale.y = 0.01;
00216     marker.scale.z = 0.01;
00217 
00218     // Set the color -- be sure to set alpha to something non-zero!
00219     marker.color.r = 1;
00220     marker.color.g = 1;
00221     marker.color.b = 0.5;
00222     marker.color.a = 1.0;
00223 
00224     geometry_msgs::Point start;
00225     geometry_msgs::Point end;
00226     std::cout << "Contructing TSP markers for " << solutions.size() << " graphs " << std::endl;
00227 
00228     for (unsigned int i = 0; i < solutions.size(); i++) {
00229         marker.id = i;
00230         marker.points.clear();
00231 
00232         for (unsigned int j = 0; j < solutions[i].size() - 2; j++) {
00233             start.x = surface_samples[solutions[i][j]].x;
00234             start.y = surface_samples[solutions[i][j]].y;
00235             start.z = surface_samples[solutions[i][j]].z;
00236             end.x = surface_samples[solutions[i][j + 1]].x;
00237             end.y = surface_samples[solutions[i][j + 1]].y;
00238             end.z = surface_samples[solutions[i][j + 1]].z;
00239 
00240             marker.points.push_back(start);
00241             marker.points.push_back(end);
00242         }
00243         marker_list.push_back(marker);
00244     }
00245 
00246 }
00247 
00248 // --------------
00249 // -----Main-----
00250 // --------------
00251 int main(int argc, char** argv) {
00252 
00253     ros::init(argc, argv, "listener");
00254     ros::NodeHandle n;
00255 
00256         ros::Subscriber sub = n.subscribe("/kinect/depth/points_filtered", 1, cloudCallBack);
00257         ros::Publisher pub = n.advertise<sensor_msgs::PointCloud2>("cloud_used", 1);
00258         ros::Publisher pub2 = n.advertise<sensor_msgs::PointCloud2>("cloud_not_used", 1);
00259         ros::Publisher pub_marker = n.advertise<visualization_msgs::MarkerArray>("surface_patches", 1);
00260         ros::Publisher pub_marker2 = n.advertise<visualization_msgs::MarkerArray>("surface_normals", 1);
00261 
00262     ros::Rate loop_rate(10);
00263     while (!cloud_received) {
00264 
00265         ros::spinOnce();
00266         loop_rate.sleep();
00267         cout << "No cloud received.";
00268     }
00269 
00270 //Patch construction and publishing
00271     surfacelet::PatchMap map;
00272     pcl::PointCloud<pcl::PointXYZ> not_used_cloud;
00273     map.insertScan(cloud_nans_removed, not_used_cloud);
00274 
00275     sensor_msgs::PointCloud2 not_used_msg;
00276     pcl::toROSMsg(not_used_cloud, not_used_msg);
00277     not_used_msg.header.stamp = ros::Time::now();
00278     not_used_msg.header.frame_id = cloud.header.frame_id;
00279     pub2.publish(not_used_msg);
00280 
00281     sensor_msgs::PointCloud2 msg;
00282     pcl::toROSMsg(cloud_nans_removed, msg);
00283     msg.header.stamp = ros::Time::now();
00284     msg.header.frame_id = cloud.header.frame_id;
00285     pub.publish(msg);
00286 
00287     visualization_msgs::MarkerArray array;
00288     map.constructMarker(cloud.header.frame_id, array);
00289     cout << " size " << array.markers.size() << endl;
00290     pub_marker.publish(array);
00291 
00292     visualization_msgs::MarkerArray normal_marker;
00293     map.constructNormalMarker(cloud.header.frame_id, normal_marker);
00294     pub_marker2.publish(normal_marker);
00295 
00296 }
00297 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


surfacelet
Author(s): Juergen Hess
autogenerated on Wed Dec 26 2012 15:24:47