crop_box.h
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) 2009-2011, 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  * $Id: crop_box.h 1370 2011-06-19 01:06:01Z jspricke $
00037  *
00038  */
00039 
00040 #ifndef PCL_FILTERS_CROP_BOX_H_
00041 #define PCL_FILTERS_CROP_BOX_H_
00042 
00043 #include <pcl/point_types.h>
00044 #include <pcl/filters/filter_indices.h>
00045 #include <pcl/common/transforms.h>
00046 #include <pcl/common/eigen.h>
00047 
00048 namespace pcl
00049 {
00056   template<typename PointT>
00057   class CropBox : public FilterIndices<PointT>
00058   {
00059     using Filter<PointT>::getClassName;
00060 
00061     typedef typename Filter<PointT>::PointCloud PointCloud;
00062     typedef typename PointCloud::Ptr PointCloudPtr;
00063     typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00064 
00065     public:
00066 
00067       typedef boost::shared_ptr< CropBox<PointT> > Ptr;
00068       typedef boost::shared_ptr< const CropBox<PointT> > ConstPtr;
00069 
00073       CropBox (bool extract_removed_indices = false) :
00074         FilterIndices<PointT>::FilterIndices (extract_removed_indices),
00075         min_pt_ (Eigen::Vector4f (-1, -1, -1, 1)),
00076         max_pt_ (Eigen::Vector4f (1, 1, 1, 1)),
00077         rotation_ (Eigen::Vector3f::Zero ()),
00078         translation_ (Eigen::Vector3f::Zero ()),
00079         transform_ (Eigen::Affine3f::Identity ())
00080       {
00081         filter_name_ = "CropBox";
00082       }
00083 
00087       inline void
00088       setMin (const Eigen::Vector4f &min_pt)
00089       {
00090         min_pt_ = min_pt;
00091       }
00092 
00096       inline Eigen::Vector4f
00097       getMin () const
00098       {
00099         return (min_pt_);
00100       }
00101 
00105       inline void
00106       setMax (const Eigen::Vector4f &max_pt)
00107       {
00108         max_pt_ = max_pt;
00109       }
00110 
00114       inline Eigen::Vector4f
00115       getMax () const
00116       {
00117         return (max_pt_);
00118       }
00119 
00123       inline void
00124       setTranslation (const Eigen::Vector3f &translation)
00125       {
00126         translation_ = translation;
00127       }
00128 
00130       Eigen::Vector3f
00131       getTranslation () const
00132       {
00133         return (translation_);
00134       }
00135 
00139       inline void
00140       setRotation (const Eigen::Vector3f &rotation)
00141       {
00142         rotation_ = rotation;
00143       }
00144 
00146       inline Eigen::Vector3f
00147       getRotation () const
00148       {
00149         return (rotation_);
00150       }
00151 
00155       inline void
00156       setTransform (const Eigen::Affine3f &transform)
00157       {
00158         transform_ = transform;
00159       }
00160 
00162       inline Eigen::Affine3f
00163       getTransform () const
00164       {
00165         return (transform_);
00166       }
00167 
00168     protected:
00169       using PCLBase<PointT>::input_;
00170       using PCLBase<PointT>::indices_;
00171       using Filter<PointT>::filter_name_;
00172       using FilterIndices<PointT>::negative_;
00173       using FilterIndices<PointT>::keep_organized_;
00174       using FilterIndices<PointT>::user_filter_value_;
00175       using FilterIndices<PointT>::extract_removed_indices_;
00176       using FilterIndices<PointT>::removed_indices_;
00177 
00181       void
00182       applyFilter (PointCloud &output);
00183 
00187       void
00188       applyFilter (std::vector<int> &indices);
00189 
00190     private:
00192       Eigen::Vector4f min_pt_;
00194       Eigen::Vector4f max_pt_;
00196       Eigen::Vector3f rotation_;
00198       Eigen::Vector3f translation_;
00200       Eigen::Affine3f transform_;
00201   };
00202 
00204 
00210   template<>
00211   class PCL_EXPORTS CropBox<pcl::PCLPointCloud2> : public FilterIndices<pcl::PCLPointCloud2>
00212   {
00213     using Filter<pcl::PCLPointCloud2>::filter_name_;
00214     using Filter<pcl::PCLPointCloud2>::getClassName;
00215 
00216     typedef pcl::PCLPointCloud2 PCLPointCloud2;
00217     typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr;
00218     typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr;
00219 
00220     public:
00224        CropBox (bool extract_removed_indices = false) :
00225         FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices),
00226         min_pt_(Eigen::Vector4f (-1, -1, -1, 1)),
00227         max_pt_(Eigen::Vector4f (1, 1, 1, 1)),
00228         translation_ (Eigen::Vector3f::Zero ()),
00229         rotation_ (Eigen::Vector3f::Zero ()),
00230         transform_(Eigen::Affine3f::Identity ())
00231       {
00232         filter_name_ = "CropBox";
00233       }
00234 
00238       inline void
00239       setMin (const Eigen::Vector4f& min_pt)
00240       {
00241         min_pt_ = min_pt;
00242       }
00243 
00247       inline Eigen::Vector4f
00248       getMin () const
00249       {
00250         return (min_pt_);
00251       }
00252 
00256       inline void
00257       setMax (const Eigen::Vector4f &max_pt)
00258       {
00259         max_pt_ = max_pt;
00260       }
00261 
00265       inline Eigen::Vector4f
00266       getMax () const
00267       {
00268         return (max_pt_);
00269       }
00270 
00274       inline void
00275       setTranslation (const Eigen::Vector3f &translation)
00276       {
00277         translation_ = translation;
00278       }
00279 
00281       inline Eigen::Vector3f
00282       getTranslation () const
00283       {
00284         return (translation_);
00285       }
00286 
00290       inline void
00291       setRotation (const Eigen::Vector3f &rotation)
00292       {
00293         rotation_ = rotation;
00294       }
00295 
00297       inline Eigen::Vector3f
00298       getRotation () const
00299       {
00300         return (rotation_);
00301       }
00302 
00306       inline void
00307       setTransform (const Eigen::Affine3f &transform)
00308       {
00309         transform_ = transform;
00310       }
00311 
00313       inline Eigen::Affine3f
00314       getTransform () const
00315       {
00316         return (transform_);
00317       }
00318 
00319     protected:
00323       void
00324       applyFilter (PCLPointCloud2 &output);
00325 
00329       void
00330       applyFilter (std::vector<int> &indices);
00331 
00333       Eigen::Vector4f min_pt_;
00335       Eigen::Vector4f max_pt_;
00337       Eigen::Vector3f translation_;
00339       Eigen::Vector3f rotation_;
00341       Eigen::Affine3f transform_;
00342   };
00343 }
00344 
00345 #ifdef PCL_NO_PRECOMPILE
00346 #include <pcl/filters/impl/crop_box.hpp>
00347 #endif
00348 
00349 #endif  // PCL_FILTERS_CROP_BOX_H_


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