All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines
Classes | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Private Attributes
pcl_cloud_algos::GlobalRSD Class Reference

#include <global_rsd.h>

Inheritance diagram for pcl_cloud_algos::GlobalRSD:
Inheritance graph
[legend]

List of all members.

Classes

struct  QueryPoint

Public Types

typedef sensor_msgs::PointCloud2 InputType
typedef pcl::KdTree
< pcl::PointNormal >::Ptr 
KdTreePtr
typedef sensor_msgs::PointCloud2 OutputType

Public Member Functions

ros::Publisher createPublisher (ros::NodeHandle &nh)
 GlobalRSD ()
void init (ros::NodeHandle &)
boost::shared_ptr< const
OutputType
output ()
void post ()
void pre ()
std::string process (const boost::shared_ptr< const InputType > &)
std::vector< std::stringprovides ()
std::vector< std::stringrequires ()
void setOctree (pcl::PointCloud< pcl::PointNormal > pointcloud_msg, double octree_res, int initial_label, double laser_offset=0, double octree_maxrange=-1)
int setSurfaceType (pcl::PointCloud< pcl::PointNormal > cloud, std::vector< int > *indices, std::vector< int > *neighbors, double max_dist)
 : taken from 16.06.2010 version of EstimateMinMaxRadius.cc
 ~GlobalRSD ()

Static Public Member Functions

static std::string default_input_topic ()
static std::string default_node_name ()
static std::string default_output_topic ()

Public Attributes

pcl::PointCloud< pcl::PointNormalcloud_centroids_
pcl::PointCloud< pcl::PointNormalcloud_vrsd_
double max_min_radius_diff_
double max_radius_noise_
double min_radius_edge_
double min_radius_noise_
double min_radius_plane_
int min_voxel_pts_
int point_label_
bool publish_cloud_centroids_
bool publish_cloud_vrsd_
bool publish_octree_
int step_
double width_

Private Attributes

pcl::PointCloud
< pcl::GRSDSignature21
cloud_grsd_
ros::NodeHandle nh_
int nr_bins_
octomap::OcTreePCLoctree_
ros::Publisher octree_binary_publisher_
pcl_ros::Publisher
< pcl::PointNormal
pub_cloud_centroids_
pcl_ros::Publisher
< pcl::PointNormal
pub_cloud_vrsd_

Detailed Description

Definition at line 59 of file global_rsd.h.


Member Typedef Documentation

typedef sensor_msgs::PointCloud2 pcl_cloud_algos::GlobalRSD::InputType

Reimplemented from pcl_cloud_algos::CloudAlgo.

Definition at line 65 of file global_rsd.h.

Definition at line 66 of file global_rsd.h.

typedef sensor_msgs::PointCloud2 pcl_cloud_algos::GlobalRSD::OutputType

Reimplemented from pcl_cloud_algos::CloudAlgo.

Definition at line 64 of file global_rsd.h.


Constructor & Destructor Documentation

Definition at line 114 of file global_rsd.h.

Definition at line 127 of file global_rsd.h.


Member Function Documentation

Implements pcl_cloud_algos::CloudAlgo.

Definition at line 131 of file global_rsd.h.

Reimplemented from pcl_cloud_algos::CloudAlgo.

Definition at line 87 of file global_rsd.h.

Reimplemented from pcl_cloud_algos::CloudAlgo.

Definition at line 95 of file global_rsd.h.

Reimplemented from pcl_cloud_algos::CloudAlgo.

Definition at line 91 of file global_rsd.h.

void GlobalRSD::init ( ros::NodeHandle nh) [virtual]

Implements pcl_cloud_algos::CloudAlgo.

Definition at line 6 of file global_rsd.cpp.

boost::shared_ptr< const GlobalRSD::OutputType > GlobalRSD::output ( )

Reimplemented from pcl_cloud_algos::CloudAlgo.

Definition at line 325 of file global_rsd.cpp.

void GlobalRSD::post ( ) [virtual]

Implements pcl_cloud_algos::CloudAlgo.

Definition at line 30 of file global_rsd.cpp.

void GlobalRSD::pre ( ) [virtual]

Implements pcl_cloud_algos::CloudAlgo.

Definition at line 13 of file global_rsd.cpp.

std::string GlobalRSD::process ( const boost::shared_ptr< const InputType > &  )

: will be overwritten and need to be resized afterwards

: passing the pointer here is OK as kdTree and cloud_vrsd_ have the same scope (+ for KdTreeANN it doesn't matter)

Iterate over all cells

TODO: just start for from it_i+1

Outputting result in libSVM format

Definition at line 66 of file global_rsd.cpp.

std::vector< std::string > GlobalRSD::provides ( ) [virtual]

Implements pcl_cloud_algos::CloudAlgo.

Definition at line 47 of file global_rsd.cpp.

std::vector< std::string > GlobalRSD::requires ( ) [virtual]

Implements pcl_cloud_algos::CloudAlgo.

Definition at line 35 of file global_rsd.cpp.

void pcl_cloud_algos::GlobalRSD::setOctree ( pcl::PointCloud< pcl::PointNormal pointcloud_msg,
double  octree_res,
int  initial_label,
double  laser_offset = 0,
double  octree_maxrange = -1 
) [inline]

Definition at line 254 of file global_rsd.h.

int pcl_cloud_algos::GlobalRSD::setSurfaceType ( pcl::PointCloud< pcl::PointNormal cloud,
std::vector< int > *  indices,
std::vector< int > *  neighbors,
double  max_dist 
) [inline]

: taken from 16.06.2010 version of EstimateMinMaxRadius.cc

considering small cylinders to be edges

Definition at line 149 of file global_rsd.h.


Member Data Documentation

Definition at line 82 of file global_rsd.h.

Definition at line 340 of file global_rsd.h.

Definition at line 83 of file global_rsd.h.

Definition at line 79 of file global_rsd.h.

Definition at line 78 of file global_rsd.h.

Definition at line 77 of file global_rsd.h.

Definition at line 78 of file global_rsd.h.

Definition at line 76 of file global_rsd.h.

Definition at line 72 of file global_rsd.h.

Definition at line 328 of file global_rsd.h.

Definition at line 336 of file global_rsd.h.

Definition at line 343 of file global_rsd.h.

Definition at line 333 of file global_rsd.h.

Definition at line 68 of file global_rsd.h.

Definition at line 332 of file global_rsd.h.

Definition at line 330 of file global_rsd.h.

Definition at line 73 of file global_rsd.h.

Definition at line 74 of file global_rsd.h.

Definition at line 80 of file global_rsd.h.

Definition at line 70 of file global_rsd.h.

Definition at line 69 of file global_rsd.h.


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


pcl_cloud_algos
Author(s): Nico Blodow, Dejan Pangercic, Zoltan-Csaba Marton
autogenerated on Sun Oct 6 2013 12:05:19