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.h -> 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_PASSTHROUGH_H_ 00083 #define SHAPE_RECONSTRUCTION_PCL_FILTERS_PASSTHROUGH_H_ 00084 00085 #include <pcl/filters/filter_indices.h> 00086 #include <pcl/filters/filter.h> 00087 #include <pcl/filters/passthrough.h> 00088 00089 namespace shape_reconstruction 00090 { 00123 template <typename PointT> 00124 class PassThrough : public pcl::FilterIndices<PointT> 00125 { 00126 protected: 00127 typedef typename pcl::FilterIndices<PointT>::PointCloud PointCloud; 00128 typedef typename PointCloud::Ptr PointCloudPtr; 00129 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00130 typedef typename pcl::traits::fieldList<PointT>::type FieldList; 00131 00132 public: 00133 00134 typedef boost::shared_ptr< PassThrough<PointT> > Ptr; 00135 typedef boost::shared_ptr< const PassThrough<PointT> > ConstPtr; 00136 00137 00141 PassThrough (bool extract_removed_indices = false) : 00142 pcl::FilterIndices<PointT>::FilterIndices (extract_removed_indices), 00143 filter_field_name_ (""), 00144 filter_limit_min_ (FLT_MIN), 00145 filter_limit_max_ (FLT_MAX) 00146 { 00147 filter_name_ = "PassThrough"; 00148 } 00149 00154 inline void 00155 setFilterFieldName (const std::string &field_name) 00156 { 00157 filter_field_name_ = field_name; 00158 } 00159 00163 inline std::string const 00164 getFilterFieldName () 00165 { 00166 return (filter_field_name_); 00167 } 00168 00174 inline void 00175 setFilterLimits (const float &limit_min, const float &limit_max) 00176 { 00177 filter_limit_min_ = limit_min; 00178 filter_limit_max_ = limit_max; 00179 } 00180 00185 inline void 00186 getFilterLimits (float &limit_min, float &limit_max) 00187 { 00188 limit_min = filter_limit_min_; 00189 limit_max = filter_limit_max_; 00190 } 00191 00197 inline void 00198 setFilterLimitsNegative (const bool limit_negative) 00199 { 00200 negative_ = limit_negative; 00201 } 00202 00207 inline void 00208 getFilterLimitsNegative (bool &limit_negative) 00209 { 00210 limit_negative = negative_; 00211 } 00212 00217 inline bool 00218 getFilterLimitsNegative () 00219 { 00220 return (negative_); 00221 } 00222 00223 inline void 00224 setLabels (const std::vector<uint32_t>& labels) 00225 { 00226 labels_ = labels; 00227 } 00228 00229 protected: 00230 using pcl::PCLBase<PointT>::input_; 00231 using pcl::PCLBase<PointT>::indices_; 00232 using pcl::Filter<PointT>::filter_name_; 00233 using pcl::Filter<PointT>::getClassName; 00234 using pcl::FilterIndices<PointT>::negative_; 00235 using pcl::FilterIndices<PointT>::keep_organized_; 00236 using pcl::FilterIndices<PointT>::user_filter_value_; 00237 using pcl::FilterIndices<PointT>::extract_removed_indices_; 00238 using pcl::FilterIndices<PointT>::removed_indices_; 00239 00243 void 00244 applyFilter (PointCloud &output); 00245 00249 void 00250 applyFilter (std::vector<int> &indices) 00251 { 00252 applyFilterIndices (indices); 00253 } 00254 00258 void 00259 applyFilterIndices (std::vector<int> &indices); 00260 00261 private: 00263 std::string filter_field_name_; 00264 00266 float filter_limit_min_; 00267 00269 float filter_limit_max_; 00270 00271 std::vector<uint32_t> labels_; 00272 }; 00273 00274 // //////////////////////////////////////////////////////////////////////////////////////////// 00275 // /** \brief PassThrough uses the base Filter class methods to pass through all data that satisfies the user given 00276 // * constraints. 00277 // * \author Radu B. Rusu 00278 // * \ingroup filters 00279 // */ 00280 // template<> 00281 // class PCL_EXPORTS PassThrough<pcl::PCLPointCloud2> : public Filter<pcl::PCLPointCloud2> 00282 // { 00283 // typedef pcl::PCLPointCloud2 PCLPointCloud2; 00284 // typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr; 00285 // typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr; 00286 00287 // using Filter<pcl::PCLPointCloud2>::removed_indices_; 00288 // using Filter<pcl::PCLPointCloud2>::extract_removed_indices_; 00289 00290 // public: 00291 // /** \brief Constructor. */ 00292 // PassThrough (bool extract_removed_indices = false) : 00293 // Filter<pcl::PCLPointCloud2>::Filter (extract_removed_indices), keep_organized_ (false), 00294 // user_filter_value_ (std::numeric_limits<float>::quiet_NaN ()), 00295 // filter_field_name_ (""), filter_limit_min_ (-FLT_MAX), filter_limit_max_ (FLT_MAX), 00296 // filter_limit_negative_ (false) 00297 // { 00298 // filter_name_ = "PassThrough"; 00299 // } 00300 00301 // /** \brief Set whether the filtered points should be kept and set to the 00302 // * value given through \a setUserFilterValue (default: NaN), or removed 00303 // * from the PointCloud, thus potentially breaking its organized 00304 // * structure. By default, points are removed. 00305 // * 00306 // * \param[in] val set to true whether the filtered points should be kept and 00307 // * set to a given user value (default: NaN) 00308 // */ 00309 // inline void 00310 // setKeepOrganized (bool val) 00311 // { 00312 // keep_organized_ = val; 00313 // } 00314 00315 // /** \brief Obtain the value of the internal \a keep_organized_ parameter. */ 00316 // inline bool 00317 // getKeepOrganized () 00318 // { 00319 // return (keep_organized_); 00320 // } 00321 00322 // /** \brief Provide a value that the filtered points should be set to 00323 // * instead of removing them. Used in conjunction with \a 00324 // * setKeepOrganized (). 00325 // * \param[in] val the user given value that the filtered point dimensions should be set to 00326 // */ 00327 // inline void 00328 // setUserFilterValue (float val) 00329 // { 00330 // user_filter_value_ = val; 00331 // } 00332 00333 // /** \brief Provide the name of the field to be used for filtering data. In conjunction with \a setFilterLimits, 00334 // * points having values outside this interval will be discarded. 00335 // * \param[in] field_name the name of the field that contains values used for filtering 00336 // */ 00337 // inline void 00338 // setFilterFieldName (const std::string &field_name) 00339 // { 00340 // filter_field_name_ = field_name; 00341 // } 00342 00343 // /** \brief Get the name of the field used for filtering. */ 00344 // inline std::string const 00345 // getFilterFieldName () 00346 // { 00347 // return (filter_field_name_); 00348 // } 00349 00350 // /** \brief Set the field filter limits. All points having field values outside this interval will be discarded. 00351 // * \param[in] limit_min the minimum allowed field value 00352 // * \param[in] limit_max the maximum allowed field value 00353 // */ 00354 // inline void 00355 // setFilterLimits (const double &limit_min, const double &limit_max) 00356 // { 00357 // filter_limit_min_ = limit_min; 00358 // filter_limit_max_ = limit_max; 00359 // } 00360 00361 // /** \brief Get the field filter limits (min/max) set by the user. The default values are -FLT_MAX, FLT_MAX. 00362 // * \param[out] limit_min the minimum allowed field value 00363 // * \param[out] limit_max the maximum allowed field value 00364 // */ 00365 // inline void 00366 // getFilterLimits (double &limit_min, double &limit_max) 00367 // { 00368 // limit_min = filter_limit_min_; 00369 // limit_max = filter_limit_max_; 00370 // } 00371 00372 // /** \brief Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). 00373 // * Default: false. 00374 // * \param[in] limit_negative return data inside the interval (false) or outside (true) 00375 // */ 00376 // inline void 00377 // setFilterLimitsNegative (const bool limit_negative) 00378 // { 00379 // filter_limit_negative_ = limit_negative; 00380 // } 00381 00382 // inline void 00383 // setLabels (const std::vector<uint_t>& labels) 00384 // { 00385 // labels_ = labels; 00386 // } 00387 00388 // /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). 00389 // * \param[out] limit_negative true if data \b outside the interval [min; max] is to be returned, false otherwise 00390 // */ 00391 // inline void 00392 // getFilterLimitsNegative (bool &limit_negative) 00393 // { 00394 // limit_negative = filter_limit_negative_; 00395 // } 00396 00397 // /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). 00398 // * \return true if data \b outside the interval [min; max] is to be returned, false otherwise 00399 // */ 00400 // inline bool 00401 // getFilterLimitsNegative () 00402 // { 00403 // return (filter_limit_negative_); 00404 // } 00405 00406 // protected: 00407 // void 00408 // applyFilter (PCLPointCloud2 &output); 00409 00410 // private: 00411 // /** \brief Keep the structure of the data organized, by setting the 00412 // * filtered points to the a user given value (NaN by default). 00413 // */ 00414 // bool keep_organized_; 00415 00416 // /** \brief User given value to be set to any filtered point. Casted to 00417 // * the correct field type. 00418 // */ 00419 // float user_filter_value_; 00420 00421 // /** \brief The desired user filter field name. */ 00422 // std::string filter_field_name_; 00423 00424 // /** \brief The minimum allowed filter value a point will be considered from. */ 00425 // double filter_limit_min_; 00426 00427 // /** \brief The maximum allowed filter value a point will be considered from. */ 00428 // double filter_limit_max_; 00429 00430 // /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */ 00431 // bool filter_limit_negative_; 00432 00433 // std::vector<uint_t> labels_; 00434 00435 // }; 00436 } 00437 00438 #endif // PCL_FILTERS_PASSTHROUGH_H_