c_polygon_representation Class Reference
[C_polygon_representation]

#include <c_polygon_representation.h>

List of all members.

Public Member Functions

 c_polygon_representation (const char *name, ros::NodeHandle *node)
 Constructor. Allocate space for Ptr objecs.
void compute_convex_hull (void)
void compute_convex_hull_inliers (pcl::PointCloud< PointT > *input_cloud, pcl::PointCloud< pcl::Normal > *input_normals)
void compute_plane_candidate_from_pc (pcl::PointCloud< PointT > *input_cloud, pcl::PointCloud< pcl::Normal > *input_normals, double DistanceThreshold=0.5, double NormalDistanceWeight=0.5, int MaxIterations=1000)
int indices_extraction (pcl::PointIndices::Ptr ind, pcl::PointCloud< PointT > *input_cloud, pcl::PointCloud< PointT > *remove_cloud, pcl::PointCloud< PointT >::Ptr copy_cloud, pcl::PointCloud< pcl::Normal > *input_normals, pcl::PointCloud< pcl::Normal > *remove_normals)
void project_cloud_to_plane (pcl::PointCloud< PointT >::Ptr input_cloud)
void project_raw_cloud_to_plane (void)
void publish_additional_cloud (void)
void publish_convex_hull_cloud (void)
void publish_polygon_point_cloud (t_polygon_point_cloud *ppc)
void publish_projected_cloud (void)
void publish_raw_cloud (void)
void segment_plane_from_point_cloud (pcl::PointCloud< PointT > *input_cloud, double DistanceThreshold, int MaxIterations)
 ~c_polygon_representation ()
 Destructor. free space of Ptr objecs.

Public Attributes

t_polygon_point_cloud additional
pcl::ModelCoefficients::Ptr coefficients
t_polygon_point_cloud convex_hull
pcl::PointIndices::Ptr indices
t_polygon_point_cloud projected
t_polygon_point_cloud raw

Private Member Functions

void allocate_space (void)
void set_names (const char *s)
 set names

Private Attributes

sensor_msgs::PointCloud2 cloud_msg
char polygon_name [1024]
ros::NodeHandle * rosnode

Detailed Description

Definition at line 123 of file c_polygon_representation.h.


Member Function Documentation

void c_polygon_representation::compute_convex_hull ( void   )  [inline]

Definition at line 224 of file c_polygon_representation.h.

void c_polygon_representation::compute_convex_hull_inliers ( pcl::PointCloud< PointT > *  input_cloud,
pcl::PointCloud< pcl::Normal > *  input_normals 
) [inline]

Definition at line 239 of file c_polygon_representation.h.

int c_polygon_representation::indices_extraction ( pcl::PointIndices::Ptr  ind,
pcl::PointCloud< PointT > *  input_cloud,
pcl::PointCloud< PointT > *  remove_cloud,
pcl::PointCloud< PointT >::Ptr  copy_cloud,
pcl::PointCloud< pcl::Normal > *  input_normals,
pcl::PointCloud< pcl::Normal > *  remove_normals 
) [inline]

Definition at line 154 of file c_polygon_representation.h.

void c_polygon_representation::project_cloud_to_plane ( pcl::PointCloud< PointT >::Ptr  input_cloud  )  [inline]

Definition at line 212 of file c_polygon_representation.h.

void c_polygon_representation::project_raw_cloud_to_plane ( void   )  [inline]

Definition at line 207 of file c_polygon_representation.h.

void c_polygon_representation::publish_additional_cloud ( void   )  [inline]

Definition at line 136 of file c_polygon_representation.h.

void c_polygon_representation::publish_convex_hull_cloud ( void   )  [inline]

Definition at line 135 of file c_polygon_representation.h.

void c_polygon_representation::publish_polygon_point_cloud ( t_polygon_point_cloud ppc  )  [inline]

Fill some required stuff

Definition at line 138 of file c_polygon_representation.h.

void c_polygon_representation::publish_projected_cloud ( void   )  [inline]

Definition at line 134 of file c_polygon_representation.h.

void c_polygon_representation::publish_raw_cloud ( void   )  [inline]

Definition at line 133 of file c_polygon_representation.h.

void c_polygon_representation::set_names ( const char *  s  )  [inline, private]

set names

Definition at line 360 of file c_polygon_representation.h.


Member Data Documentation

Definition at line 338 of file c_polygon_representation.h.

sensor_msgs::PointCloud2 c_polygon_representation::cloud_msg [private]

Definition at line 348 of file c_polygon_representation.h.

pcl::ModelCoefficients::Ptr c_polygon_representation::coefficients

Definition at line 336 of file c_polygon_representation.h.

Definition at line 338 of file c_polygon_representation.h.

pcl::PointIndices::Ptr c_polygon_representation::indices

Definition at line 337 of file c_polygon_representation.h.

Definition at line 347 of file c_polygon_representation.h.

Definition at line 338 of file c_polygon_representation.h.

Definition at line 338 of file c_polygon_representation.h.

ros::NodeHandle* c_polygon_representation::rosnode [private]

Definition at line 346 of file c_polygon_representation.h.


The documentation for this class was generated from the following files:
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Defines


polygon_primitives_extraction
Author(s): Miguel Oliveira
autogenerated on Wed Jul 23 04:35:24 2014