extract_indices.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2012, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  *
00039  */
00040 
00041 #include <pcl/filters/impl/extract_indices.hpp>
00042 
00044 void
00045 pcl::ExtractIndices<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
00046 {
00047   // TODO: the PCLPointCloud2 implementation is not yet using the keep_organized_ system -FF
00048   if (indices_->empty () || (input_->width * input_->height == 0))
00049   {
00050     output.width = output.height = 0;
00051     output.data.clear ();
00052     // If negative, copy all the data
00053     if (negative_)
00054       output = *input_;
00055     return;
00056   }
00057   if (indices_->size () == (input_->width * input_->height))
00058   {
00059     // If negative, then return an empty cloud
00060     if (negative_)
00061     {
00062       output.width = output.height = 0;
00063       output.data.clear ();
00064     }
00065     // else, we need to return all points
00066     else
00067       output = *input_;
00068     return;
00069   }
00070 
00071   // Copy the common fields (header and fields should have already been copied)
00072   output.is_bigendian = input_->is_bigendian;
00073   output.point_step   = input_->point_step;
00074   output.height       = 1;
00075   // TODO: check the output cloud and assign is_dense based on whether the points are valid or not
00076   output.is_dense     = false;
00077 
00078   if (negative_)
00079   {
00080     // Prepare a vector holding all indices
00081     std::vector<int> all_indices (input_->width * input_->height);
00082     for (int i = 0; i < static_cast<int>(all_indices.size ()); ++i)
00083       all_indices[i] = i;
00084 
00085     std::vector<int> indices = *indices_;
00086     std::sort (indices.begin (), indices.end ());
00087 
00088     // Get the diference
00089     std::vector<int> remaining_indices;
00090     set_difference (all_indices.begin (), all_indices.end (), indices.begin (), indices.end (),
00091                     inserter (remaining_indices, remaining_indices.begin ()));
00092 
00093     // Prepare the output and copy the data
00094     output.width = static_cast<uint32_t> (remaining_indices.size ());
00095     output.data.resize (remaining_indices.size () * output.point_step);
00096     for (size_t i = 0; i < remaining_indices.size (); ++i)
00097       memcpy (&output.data[i * output.point_step], &input_->data[remaining_indices[i] * output.point_step], output.point_step);
00098   }
00099   else
00100   {
00101     // Prepare the output and copy the data
00102     output.width = static_cast<uint32_t> (indices_->size ());
00103     output.data.resize (indices_->size () * output.point_step);
00104     for (size_t i = 0; i < indices_->size (); ++i)
00105       memcpy (&output.data[i * output.point_step], &input_->data[(*indices_)[i] * output.point_step], output.point_step);
00106   }
00107   output.row_step = output.point_step * output.width;
00108 }
00109 
00111 void
00112 pcl::ExtractIndices<pcl::PCLPointCloud2>::applyFilter (std::vector<int> &indices)
00113 {
00114   if (negative_)
00115   {
00116     // If the subset is the full set
00117     if (indices_->size () == (input_->width * input_->height))
00118     {
00119       // Empty set copy
00120       indices.clear ();
00121       return;
00122     }
00123 
00124     // Set up the full indices set
00125     std::vector<int> indices_fullset (input_->width * input_->height);
00126     for (int p_it = 0; p_it < static_cast<int> (indices_fullset.size ()); ++p_it)
00127       indices_fullset[p_it] = p_it;
00128 
00129     // If the subset is the empty set
00130     if (indices_->empty () || (input_->width * input_->height == 0))
00131     {
00132       // Full set copy
00133       indices = indices_fullset;
00134       return;
00135     }
00136 
00137     // If the subset is a proper subset
00138     // Set up the subset input indices
00139     std::vector<int> indices_subset = *indices_;
00140     std::sort (indices_subset.begin (), indices_subset.end ());
00141 
00142     // Get the difference
00143     set_difference (indices_fullset.begin (), indices_fullset.end (), indices_subset.begin (), indices_subset.end (), inserter (indices, indices.begin ()));
00144   }
00145   else
00146     indices = *indices_;
00147 }
00148 
00149 #ifndef PCL_NO_PRECOMPILE
00150 #include <pcl/impl/instantiate.hpp>
00151 #include <pcl/point_types.h>
00152 
00153 #ifdef PCL_ONLY_CORE_POINT_TYPES
00154   PCL_INSTANTIATE(ExtractIndices, (pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::Normal)(pcl::PointXYZRGBNormal))
00155 #else
00156   PCL_INSTANTIATE(ExtractIndices, PCL_POINT_TYPES)
00157 #endif
00158 
00159 #endif    // PCL_NO_PRECOMPILE
00160 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:23:44