Attention

You are viewing an older version of the documentation. The latest version is 2.2.

Detecting Specific Models and Their Parameters in 3D Point Clouds

In this tutorial we will learn how to detect a plane model in a 3D point cloud.

Note

This tutorial can be run both inside and outside a Docker* image. We assume that the pcl-oneapi-tutorial Deb package has been installed, and the user has copied the tutorial directory from /opt/intel/pcl/oneapi/tutorials/ to a user-writable directory.

  1. Prepare the environment:

    cd <path-to-oneapi-tutorials>/sample_consensus
    
    Copy to clipboard
  2. oneapi_passthrough.cpp should be in the directory with following content:

     1/*
     2 * Software License Agreement (BSD License)
     3 *
     4 *  Point Cloud Library (PCL) - www.pointclouds.org
     5 *  Copyright (c) 2010-2012, Willow Garage, Inc.
     6 *  Copyright (c) 2014-, Open Perception, Inc.
     7 *
     8 *  All rights reserved.
     9 *
    10 *  Redistribution and use in source and binary forms, with or without
    11 *  modification, are permitted provided that the following conditions
    12 *  are met:
    13 *
    14 *   * Redistributions of source code must retain the above copyright
    15 *     notice, this list of conditions and the following disclaimer.
    16 *   * Redistributions in binary form must reproduce the above
    17 *     copyright notice, this list of conditions and the following
    18 *     disclaimer in the documentation and/or other materials provided
    19 *     with the distribution.
    20 *   * Neither the name of the copyright holder(s) nor the names of its
    21 *     contributors may be used to endorse or promote products derived
    22 *     from this software without specific prior written permission.
    23 *
    24 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    25 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    26 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    27 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    28 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    29 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    30 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
    31 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
    32 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    33 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    34 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    35 *  POSSIBILITY OF SUCH DAMAGE.
    36 *
    37 */
    38
    39#include <pcl/oneapi/sample_consensus/sac_model_plane.h>
    40#include <pcl/oneapi/sample_consensus/ransac.h>
    41#include <pcl/io/pcd_io.h>
    42#include <pcl/point_types.h>
    43#include <pcl/point_cloud.h>
    44
    45
    46int main (int argc, char** argv)
    47{
    48  std::cout << "Running on device: " << dpct::get_default_queue().get_device().get_info<sycl::info::device::name>() << "\n";
    49  // Read Point Cloud
    50  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr( new pcl::PointCloud<pcl::PointXYZ>() );
    51  pcl::PointCloud<pcl::PointXYZ>::Ptr convex_ptr;
    52  int result = pcl::io::loadPCDFile("test59.pcd", *cloud_ptr);
    53  if (result != 0)
    54  {
    55    pcl::console::print_info ("Load pcd file failed.\n");
    56    return result;
    57  }
    58
    59  // Prepare Device Point Cloud Memory
    60  pcl::oneapi::SampleConsensusModel::PointCloud_xyz cloud_device_xyz;
    61  cloud_device_xyz.upload(cloud_ptr->points);
    62  pcl::oneapi::SampleConsensusModel::PointCloud & cloud_device = (pcl::oneapi::SampleConsensusModel::PointCloud &)cloud_device_xyz;
    63
    64  // Algorithm tests
    65  typename pcl::oneapi::SampleConsensusModelPlane::Ptr sac_model (new pcl::oneapi::SampleConsensusModelPlane (cloud_device));
    66  pcl::oneapi::RandomSampleConsensus sac (sac_model);
    67  sac.setMaxIterations (10000);
    68  sac.setDistanceThreshold (0.03);
    69  result = sac.computeModel ();
    70
    71  // Best model
    72  pcl::oneapi::SampleConsensusModelPlane::Indices sample;
    73  sac.getModel (sample);
    74
    75  // Coefficient
    76  pcl::oneapi::SampleConsensusModelPlane::Coefficients coeffs;
    77  sac.getModelCoefficients (coeffs);
    78
    79  // Inliers
    80  pcl::Indices pcl_inliers;
    81  int inliers_size = sac.getInliersSize ();
    82  pcl_inliers.resize(inliers_size);
    83
    84  pcl::oneapi::SampleConsensusModelPlane::IndicesPtr inliers = sac.getInliers ();
    85  inliers->download(pcl_inliers.data(), 0, inliers_size);
    86
    87  // Refined coefficient
    88  pcl::oneapi::SampleConsensusModelPlane::Coefficients coeff_refined;
    89  sac_model->optimizeModelCoefficients (*cloud_ptr, pcl_inliers, coeffs, coeff_refined);
    90
    91  // print log
    92  std::cout << "input cloud size: " << cloud_ptr->points.size() << std::endl;
    93  std::cout << "inliers size    : " << inliers_size << std::endl;
    94  std::cout << "  plane model coefficient: " << coeffs[0] << ", " << coeffs[1] << ", " << coeffs[2] << ", " << coeffs[3] << std::endl;
    95  std::cout << "  Optimized coefficient  : " << coeff_refined[0] << ", " << coeff_refined[1] << ", " << coeff_refined[2] << ", " << coeff_refined[3] << std::endl;
    96}
    
    Copy to clipboard
  3. Source the Intel® oneAPI Base Toolkit environment:

    source /opt/intel/oneapi/setvars.sh
    
    Copy to clipboard
  4. (Optional) Setup proxy setting to download test data:

    export http_proxy="http://<http_proxy>:port"
    export https_proxy="http://<https_proxy>:port"
    
    Copy to clipboard
  5. Build the code:

    mkdir build && cd build
    cmake ../
    make -j
    
    Copy to clipboard
  6. Run the binary:

    ./oneapi_passthrough
    
    Copy to clipboard
  7. Expected results example:

    input cloud size: 307200
    inliers size    : 77316
    plane model coefficient: -0.0789502, -0.816661, -0.571692, 0.546386
    Optimized coefficient  : -0.0722213, -0.818286, -0.570256, 0.547587
    
    Copy to clipboard

Code Explanation

Load the test data from GitHub* into a PointCloud<PointXYZ>.

  // Read Point Cloud
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr( new pcl::PointCloud<pcl::PointXYZ>() );
  pcl::PointCloud<pcl::PointXYZ>::Ptr convex_ptr;
  int result = pcl::io::loadPCDFile("test59.pcd", *cloud_ptr);
  if (result != 0)
  {
    pcl::console::print_info ("Load pcd file failed.\n");
    return result;
  }
Copy to clipboard

Create GPU input and output device arrays, and load point cloud data into the input device array.

  // Prepare Device Point Cloud Memory
  pcl::oneapi::SampleConsensusModel::PointCloud_xyz cloud_device_xyz;
  cloud_device_xyz.upload(cloud_ptr->points);
  pcl::oneapi::SampleConsensusModel::PointCloud & cloud_device = (pcl::oneapi::SampleConsensusModel::PointCloud &)cloud_device_xyz;
Copy to clipboard

Start computing the model.

  typename pcl::oneapi::SampleConsensusModelPlane::Ptr sac_model (new pcl::oneapi::SampleConsensusModelPlane (cloud_device));
  pcl::oneapi::RandomSampleConsensus sac (sac_model);
  sac.setMaxIterations (10000);
  sac.setDistanceThreshold (0.03);
  result = sac.computeModel ();
Copy to clipboard

Result (best model):

  pcl::oneapi::SampleConsensusModelPlane::Indices sample;
  sac.getModel (sample);
Copy to clipboard

Result (coefficient model):

  pcl::oneapi::SampleConsensusModelPlane::Coefficients coeffs;
  sac.getModelCoefficients (coeffs);
Copy to clipboard

Result (inliers model):

  pcl::Indices pcl_inliers;
  int inliers_size = sac.getInliersSize ();
  pcl_inliers.resize(inliers_size);

  pcl::oneapi::SampleConsensusModelPlane::IndicesPtr inliers = sac.getInliers ();
  inliers->download(pcl_inliers.data(), 0, inliers_size);
Copy to clipboard

Result (refined coefficient model):

  pcl::oneapi::SampleConsensusModelPlane::Coefficients coeff_refined;
  sac_model->optimizeModelCoefficients (*cloud_ptr, pcl_inliers, coeffs, coeff_refined);
Copy to clipboard

Result (output log):

  std::cout << "input cloud size: " << cloud_ptr->points.size() << std::endl;
  std::cout << "inliers size    : " << inliers_size << std::endl;
  std::cout << "  plane model coefficient: " << coeffs[0] << ", " << coeffs[1] << ", " << coeffs[2] << ", " << coeffs[3] << std::endl;
  std::cout << "  Optimized coefficient  : " << coeff_refined[0] << ", " << coeff_refined[1] << ", " << coeff_refined[2] << ", " << coeff_refined[3] << std::endl;
Copy to clipboard