Public Member Functions | Private Attributes | List of all members
points_from_volume< T > Class Template Reference

#include <points_from_volume.h>

Public Member Functions

t_func_output convexhull_function (pcl::PointCloud< T > &pc_in, double positive_offset, double negative_offset, bool flag_in_out)
 Extract points from the pcl that are inside the convexhull. More...
 
pcl::PointCloud< T > get_pc_in_volume ()
 Points in the desired volume. More...
 
 points_from_volume ()
 
t_func_output set_convex_hull (pcl::PointCloud< T > &pc_in)
 Set the convexhull. More...
 
t_func_output set_convex_hull (const sensor_msgs::PointCloud2ConstPtr &pcmsg_in)
 Set the convexhull. More...
 
 ~points_from_volume ()
 

Private Attributes

pcl::PointCloud< T > convex_hull
 
bool flag_convexhull_set
 
pcl::PointCloud< T > pc_in_volume
 

Detailed Description

template<class T>
class points_from_volume< T >

Definition at line 59 of file points_from_volume.h.

Constructor & Destructor Documentation

template<class T>
points_from_volume< T >::points_from_volume ( )
inline

Definition at line 64 of file points_from_volume.h.

template<class T>
points_from_volume< T >::~points_from_volume ( )
inline

Definition at line 69 of file points_from_volume.h.

Member Function Documentation

template<class T>
t_func_output points_from_volume< T >::convexhull_function ( pcl::PointCloud< T > &  pc_in,
double  positive_offset,
double  negative_offset,
bool  flag_in_out 
)
inline

Extract points from the pcl that are inside the convexhull.

There is a need to set some convexhull parameters, like the offsets (positive and negative) and the flag which defines if the points are extrated from the inside(flag=false) or the outside(flag=true) of the hull

Parameters
pc_in_volume
positive_offset
negative_offset
flag_in_out
Returns
t_func_output

Definition at line 129 of file points_from_volume.h.

template<class T>
pcl::PointCloud<T> points_from_volume< T >::get_pc_in_volume ( )
inline

Points in the desired volume.

Parameters
void
Returns
pc_in_volume

Definition at line 114 of file points_from_volume.h.

template<class T>
t_func_output points_from_volume< T >::set_convex_hull ( pcl::PointCloud< T > &  pc_in)
inline

Set the convexhull.

Copy the points from a point cloud to the convexhull

Parameters
pcl::PointCloud<T>&pc_in
Returns
t_func_output

Definition at line 83 of file points_from_volume.h.

template<class T>
t_func_output points_from_volume< T >::set_convex_hull ( const sensor_msgs::PointCloud2ConstPtr &  pcmsg_in)
inline

Set the convexhull.

Copy the points from a point cloud to the convexhull

Parameters
constsensor_msgs::PointCloud2ConstPtr& pcmsg_in
Returns
set_convex_hull(pc_in);

Definition at line 100 of file points_from_volume.h.

Member Data Documentation

template<class T>
pcl::PointCloud<T> points_from_volume< T >::convex_hull
private

Definition at line 197 of file points_from_volume.h.

template<class T>
bool points_from_volume< T >::flag_convexhull_set
private

Definition at line 196 of file points_from_volume.h.

template<class T>
pcl::PointCloud<T> points_from_volume< T >::pc_in_volume
private

Definition at line 195 of file points_from_volume.h.


The documentation for this class was generated from the following file:


points_from_volume
Author(s): Joel Pereira
autogenerated on Mon Mar 2 2015 01:32:40