passthrough.cpp
Go to the documentation of this file.
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: passthrough.cpp 5026 2012-03-12 02:51:44Z rusu $
00035  *
00036  */
00037 
00038 #include <pcl/impl/instantiate.hpp>
00039 #include <pcl/point_types.h>
00040 #include <pcl/filters/passthrough.h>
00041 #include <pcl/filters/impl/passthrough.hpp>
00042 
00044 void
00045 pcl::PassThrough<sensor_msgs::PointCloud2>::applyFilter (PointCloud2 &output)
00046 {
00047   if (!input_)
00048   {
00049     PCL_ERROR ("[pcl::%s::applyFilter] Input dataset not given!\n", getClassName ().c_str ());
00050     output.width = output.height = 0;
00051     output.data.clear ();
00052     return;
00053   }
00054 
00055   // If fields x/y/z are not present, we cannot filter
00056   if (x_idx_ == -1 || y_idx_ == -1 || z_idx_ == -1)
00057   {
00058     PCL_ERROR ("[pcl::%s::applyFilter] Input dataset doesn't have x-y-z coordinates!\n", getClassName ().c_str ());
00059     output.width = output.height = 0;
00060     output.data.clear ();
00061     return;
00062   }
00063 
00064   int nr_points = input_->width * input_->height;
00065 
00066   // Check if we're going to keep the organized structure of the cloud or not
00067   if (keep_organized_)
00068   {
00069     if (filter_field_name_.empty ())
00070     {
00071       // Silly - if no filtering is actually done, and we want to keep the data organized, 
00072       // just copy everything. Any optimizations that can be done here???
00073       output = *input_;
00074       return;
00075     }
00076 
00077     output.width = input_->width;
00078     output.height = input_->height;
00079     // Check what the user value is: if !finite, set is_dense to false, true otherwise
00080     if (!pcl_isfinite (user_filter_value_))
00081       output.is_dense = false;
00082     else
00083       output.is_dense = input_->is_dense;
00084   }
00085   else
00086   {
00087     // Copy the header (and thus the frame_id) + allocate enough space for points
00088     output.height = 1; // filtering breaks the organized structure
00089     // Because we're doing explit checks for isfinite, is_dense = true
00090     output.is_dense = true;
00091   }
00092   output.row_step = input_->row_step;
00093   output.point_step = input_->point_step;
00094   output.is_bigendian = input_->is_bigendian;
00095   output.data.resize (input_->data.size ());
00096 
00097   removed_indices_->resize (input_->data.size ());
00098 
00099   int nr_p = 0;
00100   int nr_removed_p = 0;
00101   // Create the first xyz_offset
00102   Eigen::Array4i xyz_offset (input_->fields[x_idx_].offset, input_->fields[y_idx_].offset,
00103                              input_->fields[z_idx_].offset, 0);
00104 
00105   Eigen::Vector4f pt = Eigen::Vector4f::Zero ();
00106   // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first...
00107   if (!filter_field_name_.empty ())
00108   {
00109     // Get the distance field index
00110     int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_);
00111     if (distance_idx == -1)
00112     {
00113       PCL_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.\n", getClassName ().c_str (), distance_idx);
00114       output.width = output.height = 0;
00115       output.data.clear ();
00116       return;
00117     }
00118 
00119     // @todo fixme
00120     if (input_->fields[distance_idx].datatype != sensor_msgs::PointField::FLOAT32)
00121     {
00122       PCL_ERROR ("[pcl::%s::downsample] Distance filtering requested, but distances are not float/double in the dataset! Only FLOAT32/FLOAT64 distances are supported right now.\n", getClassName ().c_str ());
00123       output.width = output.height = 0;
00124       output.data.clear ();
00125       return;
00126     }
00127 
00128     float badpt = std::numeric_limits<float>::quiet_NaN ();
00129     // Check whether we need to store filtered valued in place
00130     if (keep_organized_)
00131     {
00132       float distance_value = 0;
00133       // Go over all points
00134       for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
00135       {
00136         // Copy all the fields
00137         memcpy (&output.data[cp * output.point_step], &input_->data[cp * output.point_step], output.point_step);
00138 
00139         // Get the distance value
00140         memcpy (&distance_value, &input_->data[cp * input_->point_step + input_->fields[distance_idx].offset],
00141                 sizeof(float));
00142 
00143         if (filter_limit_negative_)
00144         {
00145           // Use a threshold for cutting out points which inside the interval
00146           if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_))
00147           {
00148             // Unoptimized memcpys: assume fields x, y, z are in random order
00149             memcpy (&output.data[xyz_offset[0]], &badpt, sizeof(float));
00150             memcpy (&output.data[xyz_offset[1]], &badpt, sizeof(float));
00151             memcpy (&output.data[xyz_offset[2]], &badpt, sizeof(float));
00152             continue;
00153           }
00154           else
00155           {
00156             if (extract_removed_indices_)
00157             {
00158               (*removed_indices_)[nr_removed_p] = cp;
00159               nr_removed_p++;
00160             }
00161           }
00162         }
00163         else
00164         {
00165           // Use a threshold for cutting out points which are too close/far away
00166           if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_))
00167           {
00168             // Unoptimized memcpys: assume fields x, y, z are in random order
00169             memcpy (&output.data[xyz_offset[0]], &badpt, sizeof(float));
00170             memcpy (&output.data[xyz_offset[1]], &badpt, sizeof(float));
00171             memcpy (&output.data[xyz_offset[2]], &badpt, sizeof(float));
00172             continue;
00173           }
00174           else
00175           {
00176             if (extract_removed_indices_)
00177             {
00178               (*removed_indices_)[nr_removed_p] = cp;
00179               nr_removed_p++;
00180             }
00181           }
00182         }
00183       }
00184     }
00185     // Remove filtered points
00186     else
00187     {
00188       // Go over all points
00189       float distance_value = 0;
00190       for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
00191       {
00192         // Get the distance value
00193         memcpy (&distance_value, &input_->data[cp * input_->point_step + input_->fields[distance_idx].offset],
00194                 sizeof(float));
00195 
00196         if (filter_limit_negative_)
00197         {
00198           // Use a threshold for cutting out points which inside the interval
00199           if (distance_value < filter_limit_max_ && distance_value > filter_limit_min_)
00200           {
00201             if (extract_removed_indices_)
00202             {
00203               (*removed_indices_)[nr_removed_p] = cp;
00204               nr_removed_p++;
00205             }
00206             continue;
00207           }
00208         }
00209         else
00210         {
00211           // Use a threshold for cutting out points which are too close/far away
00212           if (distance_value > filter_limit_max_ || distance_value < filter_limit_min_)
00213           {
00214             if (extract_removed_indices_)
00215             {
00216               (*removed_indices_)[nr_removed_p] = cp;
00217               nr_removed_p++;
00218             }
00219             continue;
00220           }
00221         }
00222 
00223         // Unoptimized memcpys: assume fields x, y, z are in random order
00224         memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float));
00225         memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof(float));
00226         memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof(float));
00227 
00228         // Check if the point is invalid
00229         if (!pcl_isfinite (pt[0]) || !pcl_isfinite (pt[1]) || !pcl_isfinite (pt[2]))
00230         {
00231           if (extract_removed_indices_)
00232           {
00233             (*removed_indices_)[nr_removed_p] = cp;
00234             nr_removed_p++;
00235           }
00236           continue;
00237         }
00238 
00239         // Copy all the fields
00240         memcpy (&output.data[nr_p * output.point_step], &input_->data[cp * output.point_step], output.point_step);
00241         nr_p++;
00242       }
00243       output.width = nr_p;
00244     } // !keep_organized_
00245   }
00246   // No distance filtering, process all data. No need to check for is_organized here as we did it above
00247   else
00248   {
00249     for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
00250     {
00251       // Unoptimized memcpys: assume fields x, y, z are in random order
00252       memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float));
00253       memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof(float));
00254       memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof(float));
00255 
00256       // Check if the point is invalid
00257       if (!pcl_isfinite (pt[0]) || !pcl_isfinite (pt[1]) || !pcl_isfinite (pt[2]))
00258       {
00259         if (extract_removed_indices_)
00260         {
00261           (*removed_indices_)[nr_removed_p] = cp;
00262           nr_removed_p++;
00263         }
00264         continue;
00265       }
00266 
00267       // Copy all the fields
00268       memcpy (&output.data[nr_p * output.point_step], &input_->data[cp * output.point_step], output.point_step);
00269       nr_p++;
00270     }
00271     output.width = nr_p;
00272   }
00273 
00274   output.row_step = output.point_step * output.width;
00275   output.data.resize (output.width * output.height * output.point_step);
00276 
00277   removed_indices_->resize (nr_removed_p);
00278 }
00279 // Instantiations of specific point types
00280 PCL_INSTANTIATE(PassThrough, PCL_XYZ_POINT_TYPES)
00281 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:16:20