Passthrough.hpp
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 the copyright holder(s) 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  * Passthrough.hpp -> Modification
00037  *
00038  *      Author: roberto
00039  *
00040  * This is a modified implementation of the method for online estimation of kinematic structures described in our paper
00041  * "Online Interactive Perception of Articulated Objects with Multi-Level Recursive Estimation Based on Task-Specific Priors"
00042  * (Martín-Martín and Brock, 2014) and the extension to segment, reconstruct and track shapes introduced in our paper
00043  * "An Integrated Approach to Visual Perception of Articulated Objects" (Martín-Martín, Höfer and Brock, 2016)
00044  * This implementation can be used to reproduce the results of the paper and to be applied to new research.
00045  * The implementation allows also to be extended to perceive different information/models or to use additional sources of information.
00046  * A detail explanation of the method and the system can be found in our paper.
00047  *
00048  * If you are using this implementation in your research, please consider citing our work:
00049  *
00050 @inproceedings{martinmartin_ip_iros_2014,
00051 Title = {Online Interactive Perception of Articulated Objects with Multi-Level Recursive Estimation Based on Task-Specific Priors},
00052 Author = {Roberto {Mart\'in-Mart\'in} and Oliver Brock},
00053 Booktitle = {Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems},
00054 Pages = {2494-2501},
00055 Year = {2014},
00056 Location = {Chicago, Illinois, USA},
00057 Note = {http://www.robotics.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martinmartin_ip_iros_2014.pdf},
00058 Url = {http://www.robotics.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martinmartin_ip_iros_2014.pdf},
00059 Projectname = {Interactive Perception}
00060 }
00061 
00062 @inproceedings{martinmartin_hoefer_iros_2016,
00063 Title = {An Integrated Approach to Visual Perception of Articulated Objects},
00064 Author = {Roberto {Mart\'{i}n-Mart\'{i}n} and Sebastian H\"ofer and Oliver Brock},
00065 Booktitle = {Proceedings of the IEEE International Conference on Robotics and Automation},
00066 Pages = {5091 - 5097},
00067 Year = {2016},
00068 Doi = {10.1109/ICRA.2016.7487714},
00069 Location = {Stockholm, Sweden},
00070 Month = {05},
00071 Note = {http://www.redaktion.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martin_hoefer_15_iros_sr_opt.pdf},
00072 Url = {http://www.redaktion.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martin_hoefer_15_iros_sr_opt.pdf},
00073 Url2 = {http://ieeexplore.ieee.org/xpl/articleDetails.jsp?tp=&arnumber=7487714},
00074 Projectname = {Interactive Perception}
00075 }
00076  * If you have questions or suggestions, contact us:
00077  * roberto.martinmartin@tu-berlin.de
00078  *
00079  * Enjoy!
00080  */
00081 
00082 #ifndef SHAPE_RECONSTRUCTION_PCL_FILTERS_IMPL_PASSTHROUGH_HPP_
00083 #define SHAPE_RECONSTRUCTION_PCL_FILTERS_IMPL_PASSTHROUGH_HPP_
00084 
00085 #include <shape_reconstruction/Passthrough.h>
00086 #include <pcl/common/io.h>
00087 #include <vector>
00088 #include <iterator>
00089 
00090 using namespace pcl;
00091 
00092 namespace shape_reconstruction{
00093 
00095 template <typename PointT> void
00096 shape_reconstruction::PassThrough<PointT>::applyFilter (PointCloud &output)
00097 {
00098     std::vector<int> indices;
00099     if (keep_organized_)
00100     {
00101         bool temp = extract_removed_indices_;
00102         extract_removed_indices_ = true;
00103         applyFilterIndices (indices);
00104         extract_removed_indices_ = temp;
00105 
00106         output = *input_;
00107         for (int rii = 0; rii < static_cast<int> (removed_indices_->size ()); ++rii)  // rii = removed indices iterator
00108             output.points[(*removed_indices_)[rii]].x = output.points[(*removed_indices_)[rii]].y = output.points[(*removed_indices_)[rii]].z = user_filter_value_;
00109         if (!pcl_isfinite (user_filter_value_))
00110             output.is_dense = false;
00111     }
00112     else
00113     {
00114         output.is_dense = true;
00115         applyFilterIndices (indices);
00116         copyPointCloud (*input_, indices, output);
00117     }
00118 }
00119 
00121 template <typename PointT> void
00122 shape_reconstruction::PassThrough<PointT>::applyFilterIndices (std::vector<int> &indices)
00123 {
00124     // The arrays to be used
00125     indices.resize (indices_->size ());
00126     removed_indices_->resize (indices_->size ());
00127     int oii = 0, rii = 0;  // oii = output indices iterator, rii = removed indices iterator
00128 
00129     // Has a field name been specified?
00130     if (filter_field_name_.empty ())
00131     {
00132         // Only filter for non-finite entries then
00133         for (int iii = 0; iii < static_cast<int> (indices_->size ()); ++iii)  // iii = input indices iterator
00134         {
00135             // Non-finite entries are always passed to removed indices
00136             if (!pcl_isfinite (input_->points[(*indices_)[iii]].x) ||
00137                     !pcl_isfinite (input_->points[(*indices_)[iii]].y) ||
00138                     !pcl_isfinite (input_->points[(*indices_)[iii]].z))
00139             {
00140                 if (extract_removed_indices_)
00141                     (*removed_indices_)[rii++] = (*indices_)[iii];
00142                 continue;
00143             }
00144             indices[oii++] = (*indices_)[iii];
00145         }
00146     }
00147     else
00148     {
00149         // Attempt to get the field name's index
00150         std::vector<pcl::PCLPointField> fields;
00151         int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields);
00152         if (distance_idx == -1)
00153         {
00154             PCL_WARN ("[pcl::%s::applyFilter] Unable to find field name in point type.\n", getClassName ().c_str ());
00155             indices.clear ();
00156             removed_indices_->clear ();
00157             return;
00158         }
00159 
00160         if(labels_.size()==0)
00161         {
00162 
00163 
00164             // Filter for non-finite entries and the specified field limits
00165             for (int iii = 0; iii < static_cast<int> (indices_->size ()); ++iii)  // iii = input indices iterator
00166             {
00167                 // Non-finite entries are always passed to removed indices
00168                 if (!pcl_isfinite (input_->points[(*indices_)[iii]].x) ||
00169                         !pcl_isfinite (input_->points[(*indices_)[iii]].y) ||
00170                         !pcl_isfinite (input_->points[(*indices_)[iii]].z))
00171                 {
00172                     if (extract_removed_indices_)
00173                         (*removed_indices_)[rii++] = (*indices_)[iii];
00174                     continue;
00175                 }
00176 
00177                 // Get the field's value
00178                 const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&input_->points[(*indices_)[iii]]);
00179                 float field_value = 0;
00180                 memcpy (&field_value, pt_data + fields[distance_idx].offset, sizeof (float));
00181 
00182                 // Remove NAN/INF/-INF values. We expect passthrough to output clean valid data.
00183                 if (!pcl_isfinite (field_value))
00184                 {
00185                     if (extract_removed_indices_)
00186                         (*removed_indices_)[rii++] = (*indices_)[iii];
00187                     continue;
00188                 }
00189 
00190                 // Outside of the field limits are passed to removed indices
00191                 if (!negative_ && (field_value < filter_limit_min_ || field_value > filter_limit_max_))
00192                 {
00193                     if (extract_removed_indices_)
00194                         (*removed_indices_)[rii++] = (*indices_)[iii];
00195                     continue;
00196                 }
00197 
00198                 // Inside of the field limits are passed to removed indices if negative was set
00199                 if (negative_ && field_value >= filter_limit_min_ && field_value <= filter_limit_max_)
00200                 {
00201                     if (extract_removed_indices_)
00202                         (*removed_indices_)[rii++] = (*indices_)[iii];
00203                     continue;
00204                 }
00205 
00206                 // Otherwise it was a normal point for output (inlier)
00207                 indices[oii++] = (*indices_)[iii];
00208             }
00209 
00210         }else{
00211 
00212             // Filter for non-finite entries and the specified field limits
00213             for (int iii = 0; iii < static_cast<int> (indices_->size ()); ++iii)  // iii = input indices iterator
00214             {
00215                 // Non-finite entries are always passed to removed indices
00216                 if (!pcl_isfinite (input_->points[(*indices_)[iii]].x) ||
00217                         !pcl_isfinite (input_->points[(*indices_)[iii]].y) ||
00218                         !pcl_isfinite (input_->points[(*indices_)[iii]].z))
00219                 {
00220                     if (extract_removed_indices_)
00221                         (*removed_indices_)[rii++] = (*indices_)[iii];
00222                     continue;
00223                 }
00224 
00225                 // Get the field's value
00226                 const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&input_->points[(*indices_)[iii]]);
00227                 uint32_t field_value = 0;
00228                 memcpy (&field_value, pt_data + fields[distance_idx].offset, sizeof (uint32_t));
00229 
00230                 // Remove NAN/INF/-INF values. We expect passthrough to output clean valid data.
00231                 if (!pcl_isfinite (field_value))
00232                 {
00233                     if (extract_removed_indices_)
00234                         (*removed_indices_)[rii++] = (*indices_)[iii];
00235                     continue;
00236                 }
00237 
00238                 std::vector<unsigned int>::iterator find_result = std::find(std::begin(labels_), std::end(labels_), (unsigned int)field_value);
00239 
00240                 // Outside of the field limits are passed to removed indices
00241                 if (!negative_ &&  find_result == labels_.end())
00242                 {
00243                     if (extract_removed_indices_)
00244                         (*removed_indices_)[rii++] = (*indices_)[iii];
00245                     continue;
00246                 }
00247 
00248                 // Inside of the field limits are passed to removed indices if negative was set
00249                 if (negative_ && find_result != labels_.end())
00250                 {
00251                     if (extract_removed_indices_)
00252                         (*removed_indices_)[rii++] = (*indices_)[iii];
00253                     continue;
00254                 }
00255 
00256                 // Otherwise it was a normal point for output (inlier)
00257                 indices[oii++] = (*indices_)[iii];
00258             }
00259         }
00260     }
00261 
00262     // Resize the output arrays
00263     indices.resize (oii);
00264     removed_indices_->resize (rii);
00265 }
00266 }
00267 
00268 #endif  // PCL_FILTERS_IMPL_PASSTHROUGH_HPP_


shape_reconstruction
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:34:01