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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:57