Public Member Functions | Private Member Functions | Private Attributes
PlanarRemoval Class Reference

#include <planar_removal.h>

List of all members.

Public Member Functions

 PlanarRemoval ()

Private Member Functions

void image_from_sparse_pcl2 (pcl::PointCloud< pcl::PointXYZRGB > cloud, cv::Mat &rgb_image)
void pcl2_sub_callback (const sensor_msgs::PointCloud2::ConstPtr &msg)
void reconfigureCallback (iri_pcl_filters::IriPclFiltersParametersConfig &config, uint32_t level)
void removePlanesXYZRGB (pcl::PointCloud< pcl::PointXYZRGB > cloud, pcl::PointCloud< pcl::PointXYZRGB > &cloud_filtered_rgb, pcl::PointCloud< pcl::PointXYZRGB > &cloud_filtered, pcl::PointCloud< pcl::PointXYZRGB > &cloud_planes)

Private Attributes

double cloud_remaining_proportion_threshold_
ros::Publisher coefficients_pub_
cv_bridge::CvImage cv_image
double distance_threshold_
dynamic_reconfigure::Server
< iri_pcl_filters::IriPclFiltersParametersConfig > 
dyn_reconfig_srv
sensor_msgs::Image image_msg_
image_transport::Publisher image_pub_
image_transport::ImageTransport it_
int max_num_of_planes_removed_
CMutex mutex
ros::NodeHandle nh_
sensor_msgs::PointCloud2 pcl2_filtered_msg_
sensor_msgs::PointCloud2 pcl2_planes_msg_
ros::Publisher pcl2_planes_pub_
ros::Publisher pcl2_pub_
ros::Subscriber pcl2_sub_
pcl::PointCloud< pcl::PointXYZ > pcl_planes_xyz_
pcl::PointCloud< pcl::PointXYZRGB > pcl_planes_xyzrgb_
pcl::PointCloud< pcl::PointXYZ > pcl_xyz_
pcl::PointCloud< pcl::PointXYZ > pcl_xyzrgb2_
pcl::PointCloud< pcl::PointXYZRGB > pcl_xyzrgb_

Detailed Description

Definition at line 55 of file planar_removal.h.


Constructor & Destructor Documentation

Definition at line 6 of file planar_removal.cpp.


Member Function Documentation

void PlanarRemoval::image_from_sparse_pcl2 ( pcl::PointCloud< pcl::PointXYZRGB >  cloud,
cv::Mat &  rgb_image 
) [private]

retrieves the rgb component of the pointcloud and sets it to an opencv2 image

Definition at line 178 of file planar_removal.cpp.

void PlanarRemoval::pcl2_sub_callback ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [private]

Definition at line 140 of file planar_removal.cpp.

void PlanarRemoval::reconfigureCallback ( iri_pcl_filters::IriPclFiltersParametersConfig &  config,
uint32_t  level 
) [private]

Definition at line 40 of file planar_removal.cpp.

void PlanarRemoval::removePlanesXYZRGB ( pcl::PointCloud< pcl::PointXYZRGB >  cloud,
pcl::PointCloud< pcl::PointXYZRGB > &  cloud_filtered_rgb,
pcl::PointCloud< pcl::PointXYZRGB > &  cloud_filtered,
pcl::PointCloud< pcl::PointXYZRGB > &  cloud_planes 
) [private]
Parameters:
cloudinput pcl
cloud_filtered_rgbsets the rgb of the plane inliers points to color (default: black)
cloud_filteredsets the plane inliers points to nan
cloud_panesunorganized point cloud of the segmented plane

Definition at line 53 of file planar_removal.cpp.


Member Data Documentation

Definition at line 62 of file planar_removal.h.

Definition at line 98 of file planar_removal.h.

Definition at line 67 of file planar_removal.h.

Definition at line 61 of file planar_removal.h.

dynamic_reconfigure::Server<iri_pcl_filters::IriPclFiltersParametersConfig> PlanarRemoval::dyn_reconfig_srv [private]

Definition at line 106 of file planar_removal.h.

sensor_msgs::Image PlanarRemoval::image_msg_ [private]

Definition at line 69 of file planar_removal.h.

Definition at line 104 of file planar_removal.h.

Definition at line 99 of file planar_removal.h.

Definition at line 63 of file planar_removal.h.

CMutex PlanarRemoval::mutex [private]

Definition at line 65 of file planar_removal.h.

Definition at line 71 of file planar_removal.h.

sensor_msgs::PointCloud2 PlanarRemoval::pcl2_filtered_msg_ [private]

Definition at line 101 of file planar_removal.h.

sensor_msgs::PointCloud2 PlanarRemoval::pcl2_planes_msg_ [private]

Definition at line 102 of file planar_removal.h.

Definition at line 97 of file planar_removal.h.

Definition at line 96 of file planar_removal.h.

Definition at line 93 of file planar_removal.h.

Definition at line 76 of file planar_removal.h.

Definition at line 77 of file planar_removal.h.

pcl::PointCloud<pcl::PointXYZ> PlanarRemoval::pcl_xyz_ [private]

Definition at line 73 of file planar_removal.h.

pcl::PointCloud<pcl::PointXYZ> PlanarRemoval::pcl_xyzrgb2_ [private]

Definition at line 75 of file planar_removal.h.

pcl::PointCloud<pcl::PointXYZRGB> PlanarRemoval::pcl_xyzrgb_ [private]

Definition at line 74 of file planar_removal.h.


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


iri_pcl_filters
Author(s): Sergi Foix
autogenerated on Fri Dec 6 2013 20:44:42