Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 #ifndef PCL_BOX_CLIPPER3D_H_
00039 #define PCL_BOX_CLIPPER3D_H_
00040 #include "clipper3D.h"
00041 
00042 namespace pcl
00043 {
00050   template<typename PointT>
00051   class BoxClipper3D : public Clipper3D<PointT>
00052   {
00053     public:
00054 
00055       typedef boost::shared_ptr< BoxClipper3D<PointT> > Ptr;
00056       typedef boost::shared_ptr< const BoxClipper3D<PointT> > ConstPtr;
00057 
00058 
00064       BoxClipper3D (const Eigen::Affine3f& transformation);
00065 
00072       BoxClipper3D (const Eigen::Vector3f& rodrigues, const Eigen::Vector3f& translation, const Eigen::Vector3f& box_size);
00073 
00078       void setTransformation (const Eigen::Affine3f& transformation);
00079 
00086       void setTransformation (const Eigen::Vector3f& rodrigues, const Eigen::Vector3f& translation, const Eigen::Vector3f& box_size);
00087 
00091       virtual ~BoxClipper3D () throw ();
00092 
00093       virtual bool
00094       clipPoint3D (const PointT& point) const;
00095 
00096       virtual bool
00097       clipLineSegment3D (PointT& from, PointT& to) const;
00098 
00099       virtual void
00100       clipPlanarPolygon3D (std::vector<PointT>& polygon) const;
00101 
00102       virtual void
00103       clipPlanarPolygon3D (const std::vector<PointT>& polygon, std::vector<PointT>& clipped_polygon) const;
00104 
00105       virtual void
00106       clipPointCloud3D (const pcl::PointCloud<PointT> &cloud_in, std::vector<int>& clipped, const std::vector<int>& indices = std::vector<int> ()) const;
00107 
00108       virtual Clipper3D<PointT>*
00109       clone () const;
00110 
00111     protected:
00112       float getDistance (const PointT& point) const;
00113       void transformPoint (const PointT& pointIn, PointT& pointOut) const;
00114     private:
00118       Eigen::Affine3f transformation_;
00119 
00120     public:
00121       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00122   };
00123 }
00124 
00125 #ifdef PCL_NO_PRECOMPILE
00126 #include <pcl/filters/impl/box_clipper3D.hpp>
00127 #endif
00128 
00129 #endif // PCL_BOX_CLIPPER3D_H_