Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00042 #include <ros/ros.h>
00043 #include <sensor_msgs/PointCloud2.h>
00044
00045 #include <pcl/point_types.h>
00046 #include <pcl/filters/voxel_grid.h>
00047 #include <pcl/filters/project_inliers.h>
00048 #include <pcl/features/normal_3d.h>
00049 #include <pcl/kdtree/kdtree_ann.h>
00050 #include <pcl/segmentation/sac_segmentation.h>
00051
00052 #include <pcl/PointIndices.h>
00053 #include <pcl/ModelCoefficients.h>
00054
00055 #include <table_pose/GetPose.h>
00056
00057 using namespace pcl;
00058
00059 ros::Publisher pub;
00060
00061 bool
00062 getTablePose (table_pose::GetPose::Request &req, table_pose::GetPose::Response &res)
00063 {
00064 PointCloud<PointXYZ> cloud;
00065 pcl::fromROSMsg (req.data, cloud);
00066
00067
00068 KdTreeANN<PointXYZ>::Ptr tree = boost::make_shared<KdTreeANN<PointXYZ> > ();
00069
00070
00071 VoxelGrid<PointXYZ> grid;
00072 grid.setInputCloud (cloud.makeShared ());
00073 grid.setLeafSize (0.01, 0.01, 0.01);
00074 grid.setFilterFieldName ("z");
00075 grid.setFilterLimits (0.5, 1.2);
00076
00077 PointCloud<PointXYZ> cloud_filtered;
00078 grid.filter (cloud_filtered);
00079
00080
00081 NormalEstimation<PointXYZ, Normal> n3d;
00082 n3d.setInputCloud (cloud_filtered.makeShared ());
00083 n3d.setSearchMethod (tree);
00084 n3d.setKSearch (0.01);
00085
00086 PointCloud<Normal> cloud_normals;
00087 n3d.compute (cloud_normals);
00088
00089
00090 SACSegmentationFromNormals<PointXYZ, Normal> seg;
00091 seg.setInputCloud (cloud_filtered.makeShared ());
00092 seg.setInputNormals (cloud_normals.makeShared ());
00093 seg.setNormalDistanceWeight (0.1);
00094 seg.setModelType (SACMODEL_NORMAL_PLANE);
00095 seg.setMethodType (SAC_RANSAC);
00096 seg.setDistanceThreshold (0.1);
00097 seg.setMaxIterations (10000);
00098
00099 PointIndices table_inliers;
00100 ModelCoefficients table_coefficients;
00101 seg.segment (table_inliers, table_coefficients);
00102
00103
00104 PointCloud<PointXYZ> table_projected;
00105 ProjectInliers<PointXYZ> proj;
00106 proj.setModelType (SACMODEL_NORMAL_PLANE);
00107 proj.setInputCloud (cloud_filtered.makeShared ());
00108 proj.setIndices (boost::make_shared<PointIndices> (table_inliers));
00109 proj.setModelCoefficients (boost::make_shared<ModelCoefficients> (table_coefficients));
00110 proj.filter (table_projected);
00111
00112
00113 PointCloud<PointXYZ> cloud_table;
00114 copyPointCloud (cloud_filtered, table_inliers, cloud_table);
00115 sensor_msgs::PointCloud2 cloud_out;
00116 pcl::toROSMsg (cloud_table, cloud_out);
00117 pub.publish (cloud_out);
00118
00119 return (true);
00120 }
00121
00122
00123 int
00124 main (int argc, char** argv)
00125 {
00126 ros::init (argc, argv, "table_pose");
00127
00128 ros::NodeHandle nh;
00129
00130 pub = nh.advertise<sensor_msgs::PointCloud2> ("table", 1);
00131
00132 ros::ServiceServer service = nh.advertiseService ("get_table_pose", getTablePose);
00133 ros::spin ();
00134
00135 return (0);
00136 }
00137
00138