$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * $Id: segmentation_plane.cpp 35524 2011-01-26 08:20:18Z rusu $ 00035 * 00036 */ 00037 00046 #include "pcl/ModelCoefficients.h" 00047 00048 #include "pcl/io/pcd_io.h" 00049 #include "pcl/point_types.h" 00050 00051 #include "pcl/sample_consensus/method_types.h" 00052 #include "pcl/sample_consensus/model_types.h" 00053 #include "pcl/segmentation/sac_segmentation.h" 00054 00055 /* ---[ */ 00056 int 00057 main (int argc, char** argv) 00058 { 00059 pcl::PointCloud<pcl::PointXYZ> cloud; 00060 00061 // Fill in the cloud data 00062 cloud.width = 15; 00063 cloud.height = 1; 00064 cloud.points.resize (cloud.width * cloud.height); 00065 00066 // Generate the data 00067 for (size_t i = 0; i < cloud.points.size (); ++i) 00068 { 00069 cloud.points[i].x = 1024 * rand () / (RAND_MAX + 1.0); 00070 cloud.points[i].y = 1024 * rand () / (RAND_MAX + 1.0); 00071 cloud.points[i].z = 1.0; 00072 } 00073 00074 // Set a few outliers 00075 cloud.points[0].z = 2.0; 00076 cloud.points[3].z = -2.0; 00077 cloud.points[6].z = 4.0; 00078 00079 std::cerr << "Point cloud data: " << cloud.points.size () << " points" << std::endl; 00080 for (size_t i = 0; i < cloud.points.size (); ++i) 00081 std::cerr << " " << cloud.points[i].x << " " << cloud.points[i].y << " " << cloud.points[i].z << std::endl; 00082 00083 pcl::ModelCoefficients coefficients; 00084 pcl::PointIndices inliers; 00085 // Create the segmentation object 00086 pcl::SACSegmentation<pcl::PointXYZ> seg; 00087 // Optional 00088 seg.setOptimizeCoefficients (true); 00089 // Mandatory 00090 seg.setModelType (pcl::SACMODEL_PLANE); 00091 seg.setMethodType (pcl::SAC_RANSAC); 00092 seg.setDistanceThreshold (0.01); 00093 00094 pcl::PointCloud<pcl::PointXYZ>::Ptr cloudptr (new pcl::PointCloud<pcl::PointXYZ> (cloud)); 00095 seg.setInputCloud (cloudptr); 00096 seg.segment (inliers, coefficients); 00097 00098 if (inliers.indices.size () == 0) 00099 { 00100 ROS_ERROR ("Could not estimate a planar model for the given dataset."); 00101 return (-1); 00102 } 00103 00104 std::cerr << "Model coefficients: " << coefficients.values[0] << " " << coefficients.values[1] << " " 00105 << coefficients.values[2] << " " << coefficients.values[3] << std::endl; 00106 00107 std::cerr << "Model inliers: " << inliers.indices.size () << std::endl; 00108 for (size_t i = 0; i < inliers.indices.size (); ++i) 00109 std::cerr << inliers.indices[i] << " " << cloud.points[inliers.indices[i]].x << " " 00110 << cloud.points[inliers.indices[i]].y << " " 00111 << cloud.points[inliers.indices[i]].z << std::endl; 00112 00113 return (0); 00114 } 00115 /* ]--- */