$search

ROI_Filter< PointT > Class Template Reference

#include <roi_pcl_filter.h>

List of all members.

Public Member Functions

void apply (const PointCloud &cloud_in, PointCloud &cloud_out)
unsigned int getNumInROI (const PointCloud &cloud_in)
 ROI_Filter (double min_x, double max_x, double min_y, double max_y, double min_z, double max_z)
 ROI_Filter ()
void setRoi (Eigen::Matrix< double, 3, 2 > &box)
void setRoi (double min_x, double max_x, double min_y, double max_y, double min_z, double max_z)

Private Types

typedef pcl::PassThrough< PointTPassThrough
typedef pcl::PointCloud< PointTPointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr

Private Attributes

Eigen::Vector4f max
Eigen::Vector4f min
PassThrough pass_x
PassThrough pass_y
PassThrough pass_z

Detailed Description

template<typename PointT>
class ROI_Filter< PointT >

Copyright (c) 2011, Robert Bosch LLC All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

* Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the name of Robert Bosch LLC nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Author:
Christian Bersch

Definition at line 46 of file roi_pcl_filter.h.


Member Typedef Documentation

template<typename PointT>
typedef pcl::PassThrough<PointT> ROI_Filter< PointT >::PassThrough [private]

Definition at line 48 of file roi_pcl_filter.h.

template<typename PointT>
typedef pcl::PointCloud<PointT> ROI_Filter< PointT >::PointCloud [private]

Definition at line 49 of file roi_pcl_filter.h.

template<typename PointT>
typedef PointCloud::ConstPtr ROI_Filter< PointT >::PointCloudConstPtr [private]

Definition at line 51 of file roi_pcl_filter.h.


Constructor & Destructor Documentation

template<typename PointT>
ROI_Filter< PointT >::ROI_Filter (  )  [inline]

Definition at line 59 of file roi_pcl_filter.h.

template<typename PointT>
ROI_Filter< PointT >::ROI_Filter ( double  min_x,
double  max_x,
double  min_y,
double  max_y,
double  min_z,
double  max_z 
) [inline]

Definition at line 60 of file roi_pcl_filter.h.


Member Function Documentation

template<typename PointT>
void ROI_Filter< PointT >::apply ( const PointCloud cloud_in,
PointCloud cloud_out 
) [inline]

Definition at line 99 of file roi_pcl_filter.h.

template<typename PointT>
unsigned int ROI_Filter< PointT >::getNumInROI ( const PointCloud cloud_in  )  [inline]

Definition at line 108 of file roi_pcl_filter.h.

template<typename PointT>
void ROI_Filter< PointT >::setRoi ( Eigen::Matrix< double, 3, 2 > &  box  )  [inline]

Definition at line 78 of file roi_pcl_filter.h.

template<typename PointT>
void ROI_Filter< PointT >::setRoi ( double  min_x,
double  max_x,
double  min_y,
double  max_y,
double  min_z,
double  max_z 
) [inline]

Definition at line 63 of file roi_pcl_filter.h.


Member Data Documentation

template<typename PointT>
Eigen::Vector4f ROI_Filter< PointT >::max [private]

Definition at line 56 of file roi_pcl_filter.h.

template<typename PointT>
Eigen::Vector4f ROI_Filter< PointT >::min [private]

Definition at line 55 of file roi_pcl_filter.h.

template<typename PointT>
PassThrough ROI_Filter< PointT >::pass_x [private]

Definition at line 52 of file roi_pcl_filter.h.

template<typename PointT>
PassThrough ROI_Filter< PointT >::pass_y [private]

Definition at line 53 of file roi_pcl_filter.h.

template<typename PointT>
PassThrough ROI_Filter< PointT >::pass_z [private]

Definition at line 54 of file roi_pcl_filter.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


pr2_interactive_segmentation
Author(s): Dejan Pangercic, Christian Bersch, Sarah Osentoski
autogenerated on Mon Mar 4 11:14:30 2013