1 /*
2  * Software License Agreement (BSD License)
3  *
4  *  Point Cloud Library (PCL) - www.pointclouds.org
5  *  Copyright (c) 2009-2011, Willow Garage, Inc.
6  *
7  *  All rights reserved.
8  *
9  *  Redistribution and use in source and binary forms, with or without
10  *  modification, are permitted provided that the following conditions
11  *  are met:
12  *
13  *   * Redistributions of source code must retain the above copyright
14  *     notice, this list of conditions and the following disclaimer.
15  *   * Redistributions in binary form must reproduce the above
16  *     copyright notice, this list of conditions and the following
17  *     disclaimer in the documentation and/or other materials provided
18  *     with the distribution.
19  *   * Neither the name of the copyright holder(s) nor the names of its
20  *     contributors may be used to endorse or promote products derived
21  *     from this software without specific prior written permission.
22  *
23  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  *  POSSIBILITY OF SUCH DAMAGE.
35  *
36  * $Id: crop_box.h 1370 2011-06-19 01:06:01Z jspricke $
37  *
38  */
39 
40 #pragma once
41 
42 #include <pcl/filters/filter_indices.h>
43 
44 namespace pcl
45 {
46   /** \brief CropBox is a filter that allows the user to filter all the data
47     * inside of a given box.
48     *
49     * \author Justin Rosen
50     * \ingroup filters
51     */
52   template<typename PointT>
53   class CropBox : public FilterIndices<PointT>
54   {
55     using Filter<PointT>::getClassName;
56 
57     using PointCloud = typename Filter<PointT>::PointCloud;
58     using PointCloudPtr = typename PointCloud::Ptr;
59     using PointCloudConstPtr = typename PointCloud::ConstPtr;
60 
61     public:
62 
63       using Ptr = shared_ptr<CropBox<PointT> >;
64       using ConstPtr = shared_ptr<const CropBox<PointT> >;
65 
66       /** \brief Constructor.
67         * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false).
68         */
69       CropBox (bool extract_removed_indices = false) :
70         FilterIndices<PointT> (extract_removed_indices),
71         min_pt_ (Eigen::Vector4f (-1, -1, -1, 1)),
72         max_pt_ (Eigen::Vector4f (1, 1, 1, 1)),
73         rotation_ (Eigen::Vector3f::Zero ()),
74         translation_ (Eigen::Vector3f::Zero ()),
75         transform_ (Eigen::Affine3f::Identity ())
76       {
77         filter_name_ = "CropBox";
78       }
79 
80       /** \brief Set the minimum point of the box
81         * \param[in] min_pt the minimum point of the box
82         */
83       inline void
setMin(const Eigen::Vector4f & min_pt)84       setMin (const Eigen::Vector4f &min_pt)
85       {
86         min_pt_ = min_pt;
87       }
88 
89       /** \brief Get the value of the minimum point of the box, as set by the user
90         * \return the value of the internal \a min_pt parameter.
91         */
92       inline Eigen::Vector4f
getMin()93       getMin () const
94       {
95         return (min_pt_);
96       }
97 
98       /** \brief Set the maximum point of the box
99         * \param[in] max_pt the maximum point of the box
100         */
101       inline void
setMax(const Eigen::Vector4f & max_pt)102       setMax (const Eigen::Vector4f &max_pt)
103       {
104         max_pt_ = max_pt;
105       }
106 
107       /** \brief Get the value of the maximum point of the box, as set by the user
108         * \return the value of the internal \a max_pt parameter.
109         */
110       inline Eigen::Vector4f
getMax()111       getMax () const
112       {
113         return (max_pt_);
114       }
115 
116       /** \brief Set a translation value for the box
117         * \param[in] translation the (tx,ty,tz) values that the box should be translated by
118         */
119       inline void
setTranslation(const Eigen::Vector3f & translation)120       setTranslation (const Eigen::Vector3f &translation)
121       {
122         translation_ = translation;
123       }
124 
125       /** \brief Get the value of the box translation parameter as set by the user. */
126       Eigen::Vector3f
getTranslation()127       getTranslation () const
128       {
129         return (translation_);
130       }
131 
132       /** \brief Set a rotation value for the box
133         * \param[in] rotation the (rx,ry,rz) values that the box should be rotated by
134         */
135       inline void
setRotation(const Eigen::Vector3f & rotation)136       setRotation (const Eigen::Vector3f &rotation)
137       {
138         rotation_ = rotation;
139       }
140 
141       /** \brief Get the value of the box rotatation parameter, as set by the user. */
142       inline Eigen::Vector3f
getRotation()143       getRotation () const
144       {
145         return (rotation_);
146       }
147 
148       /** \brief Set a transformation that should be applied to the cloud before filtering
149         * \param[in] transform an affine transformation that needs to be applied to the cloud before filtering
150         */
151       inline void
setTransform(const Eigen::Affine3f & transform)152       setTransform (const Eigen::Affine3f &transform)
153       {
154         transform_ = transform;
155       }
156 
157       /** \brief Get the value of the transformation parameter, as set by the user. */
158       inline Eigen::Affine3f
getTransform()159       getTransform () const
160       {
161         return (transform_);
162       }
163 
164     protected:
165       using PCLBase<PointT>::input_;
166       using PCLBase<PointT>::indices_;
167       using Filter<PointT>::filter_name_;
168       using FilterIndices<PointT>::negative_;
169       using FilterIndices<PointT>::keep_organized_;
170       using FilterIndices<PointT>::user_filter_value_;
171       using FilterIndices<PointT>::extract_removed_indices_;
172       using FilterIndices<PointT>::removed_indices_;
173 
174       /** \brief Sample of point indices
175         * \param[out] indices the resultant point cloud indices
176         */
177       void
178       applyFilter (Indices &indices) override;
179     private:
180       /** \brief The minimum point of the box. */
181       Eigen::Vector4f min_pt_;
182       /** \brief The maximum point of the box. */
183       Eigen::Vector4f max_pt_;
184       /** \brief The 3D rotation for the box. */
185       Eigen::Vector3f rotation_;
186       /** \brief The 3D translation for the box. */
187       Eigen::Vector3f translation_;
188       /** \brief The affine transform applied to the cloud. */
189       Eigen::Affine3f transform_;
190   };
191 
192   //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
193   /** \brief CropBox is a filter that allows the user to filter all the data
194     * inside of a given box.
195     *
196     * \author Justin Rosen
197     * \ingroup filters
198     */
199   template<>
200   class PCL_EXPORTS CropBox<pcl::PCLPointCloud2> : public FilterIndices<pcl::PCLPointCloud2>
201   {
202     using Filter<pcl::PCLPointCloud2>::filter_name_;
203     using Filter<pcl::PCLPointCloud2>::getClassName;
204 
205     using PCLPointCloud2 = pcl::PCLPointCloud2;
206     using PCLPointCloud2Ptr = PCLPointCloud2::Ptr;
207     using PCLPointCloud2ConstPtr = PCLPointCloud2::ConstPtr;
208 
209     public:
210       /** \brief Constructor.
211         * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false).
212         */
213        CropBox (bool extract_removed_indices = false) :
FilterIndices(extract_removed_indices)214         FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices),
215         min_pt_(Eigen::Vector4f (-1, -1, -1, 1)),
216         max_pt_(Eigen::Vector4f (1, 1, 1, 1)),
217         translation_ (Eigen::Vector3f::Zero ()),
218         rotation_ (Eigen::Vector3f::Zero ()),
219         transform_(Eigen::Affine3f::Identity ())
220       {
221         filter_name_ = "CropBox";
222       }
223 
224       /** \brief Set the minimum point of the box
225         * \param[in] min_pt the minimum point of the box
226         */
227       inline void
setMin(const Eigen::Vector4f & min_pt)228       setMin (const Eigen::Vector4f& min_pt)
229       {
230         min_pt_ = min_pt;
231       }
232 
233       /** \brief Get the value of the minimum point of the box, as set by the user
234         * \return the value of the internal \a min_pt parameter.
235         */
236       inline Eigen::Vector4f
getMin()237       getMin () const
238       {
239         return (min_pt_);
240       }
241 
242       /** \brief Set the maximum point of the box
243         * \param[in] max_pt the maximum point of the box
244         */
245       inline void
setMax(const Eigen::Vector4f & max_pt)246       setMax (const Eigen::Vector4f &max_pt)
247       {
248         max_pt_ = max_pt;
249       }
250 
251       /** \brief Get the value of the maxiomum point of the box, as set by the user
252         * \return the value of the internal \a max_pt parameter.
253         */
254       inline Eigen::Vector4f
getMax()255       getMax () const
256       {
257         return (max_pt_);
258       }
259 
260       /** \brief Set a translation value for the box
261         * \param[in] translation the (tx,ty,tz) values that the box should be translated by
262         */
263       inline void
setTranslation(const Eigen::Vector3f & translation)264       setTranslation (const Eigen::Vector3f &translation)
265       {
266         translation_ = translation;
267       }
268 
269       /** \brief Get the value of the box translation parameter as set by the user. */
270       inline Eigen::Vector3f
getTranslation()271       getTranslation () const
272       {
273         return (translation_);
274       }
275 
276       /** \brief Set a rotation value for the box
277         * \param[in] rotation the (rx,ry,rz) values that the box should be rotated by
278         */
279       inline void
setRotation(const Eigen::Vector3f & rotation)280       setRotation (const Eigen::Vector3f &rotation)
281       {
282         rotation_ = rotation;
283       }
284 
285       /** \brief Get the value of the box rotatation parameter, as set by the user. */
286       inline Eigen::Vector3f
getRotation()287       getRotation () const
288       {
289         return (rotation_);
290       }
291 
292       /** \brief Set a transformation that should be applied to the cloud before filtering
293         * \param[in] transform an affine transformation that needs to be applied to the cloud before filtering
294         */
295       inline void
setTransform(const Eigen::Affine3f & transform)296       setTransform (const Eigen::Affine3f &transform)
297       {
298         transform_ = transform;
299       }
300 
301       /** \brief Get the value of the transformation parameter, as set by the user. */
302       inline Eigen::Affine3f
getTransform()303       getTransform () const
304       {
305         return (transform_);
306       }
307 
308     protected:
309       /** \brief Sample of point indices into a separate PointCloud
310         * \param output the resultant point cloud
311         */
312       void
313       applyFilter (PCLPointCloud2 &output) override;
314 
315       /** \brief Sample of point indices
316         * \param indices the resultant point cloud indices
317         */
318       void
319       applyFilter (Indices &indices) override;
320 
321       /** \brief The minimum point of the box. */
322       Eigen::Vector4f min_pt_;
323       /** \brief The maximum point of the box. */
324       Eigen::Vector4f max_pt_;
325       /** \brief The 3D translation for the box. */
326       Eigen::Vector3f translation_;
327       /** \brief The 3D rotation for the box. */
328       Eigen::Vector3f rotation_;
329       /** \brief The affine transform applied to the cloud. */
330       Eigen::Affine3f transform_;
331   };
332 }
333 
334 #ifdef PCL_NO_PRECOMPILE
335 #include <pcl/filters/impl/crop_box.hpp>
336 #endif
337