#include <points_from_volume.h>
template<class T>
class points_from_volume< T >
Definition at line 59 of file points_from_volume.h.
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.
Set the convexhull.
Copy the points from a point cloud to the convexhull
- Parameters
-
- Returns
- t_func_output
Definition at line 83 of file points_from_volume.h.
Set the convexhull.
Copy the points from a point cloud to the convexhull
- Parameters
-
const | sensor_msgs::PointCloud2ConstPtr& pcmsg_in |
- Returns
- set_convex_hull(pc_in);
Definition at line 100 of file points_from_volume.h.
The documentation for this class was generated from the following file: