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 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: crop_box.h 4865 2012-03-01 02:07:13Z rusu $
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>::filter_name_;
00060     using Filter<PointT>::getClassName;
00061     using Filter<PointT>::indices_;
00062     using Filter<PointT>::input_;
00063 
00064     typedef typename Filter<PointT>::PointCloud PointCloud;
00065     typedef typename PointCloud::Ptr PointCloudPtr;
00066     typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00067 
00068     public:
00070       CropBox () :
00071         min_pt_ (Eigen::Vector4f (-1, -1, -1, 1)),
00072         max_pt_ (Eigen::Vector4f (1, 1, 1, 1)),
00073         rotation_ (Eigen::Vector3f::Zero ()),
00074         translation_ (Eigen::Vector3f::Zero ()),
00075         transform_ (Eigen::Affine3f::Identity ())
00076       {
00077         filter_name_ = "CropBox";
00078       }
00079 
00083       inline void
00084       setMin (const Eigen::Vector4f &min_pt)
00085       {
00086         min_pt_ = min_pt;
00087       }
00088 
00092       inline Eigen::Vector4f
00093       getMin () const
00094       {
00095         return (min_pt_);
00096       }
00097 
00101       inline void
00102       setMax (const Eigen::Vector4f &max_pt)
00103       {
00104         max_pt_ = max_pt;
00105       }
00106 
00110       inline Eigen::Vector4f
00111       getMax () const
00112       {
00113         return (max_pt_);
00114       }
00115 
00119       inline void
00120       setTranslation (const Eigen::Vector3f &translation)
00121       {
00122         translation_ = translation;
00123       }
00124 
00126       Eigen::Vector3f
00127       getTranslation () const
00128       {
00129         return (translation_);
00130       }
00131 
00135       inline void
00136       setRotation (const Eigen::Vector3f &rotation)
00137       {
00138         rotation_ = rotation;
00139       }
00140 
00142       inline Eigen::Vector3f
00143       getRotation () const
00144       {
00145         return (rotation_);
00146       }
00147 
00151       inline void
00152       setTransform (const Eigen::Affine3f &transform)
00153       {
00154         transform_ = transform;
00155       }
00156 
00158       inline Eigen::Affine3f
00159       getTransform () const
00160       {
00161         return (transform_);
00162       }
00163 
00164     protected:
00168       void
00169       applyFilter (PointCloud &output);
00170 
00174       void
00175       applyFilter (std::vector<int> &indices);
00176 
00177     private:
00179       Eigen::Vector4f min_pt_;
00181       Eigen::Vector4f max_pt_;
00183       Eigen::Vector3f rotation_;
00185       Eigen::Vector3f translation_;
00187       Eigen::Affine3f transform_;
00188   };
00189 
00191 
00197   template<>
00198   class PCL_EXPORTS CropBox<sensor_msgs::PointCloud2> : public FilterIndices<sensor_msgs::PointCloud2>
00199   {
00200     using Filter<sensor_msgs::PointCloud2>::filter_name_;
00201     using Filter<sensor_msgs::PointCloud2>::getClassName;
00202 
00203     typedef sensor_msgs::PointCloud2 PointCloud2;
00204     typedef PointCloud2::Ptr PointCloud2Ptr;
00205     typedef PointCloud2::ConstPtr PointCloud2ConstPtr;
00206 
00207     public:
00209       CropBox () :
00210         min_pt_(Eigen::Vector4f (-1, -1, -1, 1)),
00211         max_pt_(Eigen::Vector4f (1, 1, 1, 1)),
00212         translation_ (Eigen::Vector3f::Zero ()),
00213         rotation_ (Eigen::Vector3f::Zero ()),
00214         transform_(Eigen::Affine3f::Identity ())
00215       {
00216         filter_name_ = "CropBox";
00217       }
00218 
00222       inline void
00223       setMin (const Eigen::Vector4f& min_pt)
00224       {
00225         min_pt_ = min_pt;
00226       }
00227 
00231       inline Eigen::Vector4f
00232       getMin () const
00233       {
00234         return (min_pt_);
00235       }
00236 
00240       inline void
00241       setMax (const Eigen::Vector4f &max_pt)
00242       {
00243         max_pt_ = max_pt;
00244       }
00245 
00249       inline Eigen::Vector4f
00250       getMax () const
00251       {
00252         return (max_pt_);
00253       }
00254 
00258       inline void
00259       setTranslation (const Eigen::Vector3f &translation)
00260       {
00261         translation_ = translation;
00262       }
00263 
00265       inline Eigen::Vector3f
00266       getTranslation () const
00267       {
00268         return (translation_);
00269       }
00270 
00274       inline void
00275       setRotation (const Eigen::Vector3f &rotation)
00276       {
00277         rotation_ = rotation;
00278       }
00279 
00281       inline Eigen::Vector3f
00282       getRotation () const
00283       {
00284         return (rotation_);
00285       }
00286 
00290       inline void
00291       setTransform (const Eigen::Affine3f &transform)
00292       {
00293         transform_ = transform;
00294       }
00295 
00297       inline Eigen::Affine3f
00298       getTransform () const
00299       {
00300         return (transform_);
00301       }
00302 
00303     protected:
00307       void
00308       applyFilter (PointCloud2 &output);
00309 
00313       void
00314       applyFilter (std::vector<int> &indices);
00315 
00317       Eigen::Vector4f min_pt_;
00319       Eigen::Vector4f max_pt_;
00321       Eigen::Vector3f translation_;
00323       Eigen::Vector3f rotation_;
00325       Eigen::Affine3f transform_;
00326   };
00327 }
00328 
00329 #endif  // PCL_FILTERS_CROP_BOX_H_


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