#include <region_growing_multiple_plane_segmentation.h>
◆ Config
◆ NormalSyncPolicy
◆ PointT
◆ RegionGrowingMultiplePlaneSegmentation()
jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::RegionGrowingMultiplePlaneSegmentation |
( |
| ) |
|
|
inline |
◆ ~RegionGrowingMultiplePlaneSegmentation()
jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::~RegionGrowingMultiplePlaneSegmentation |
( |
| ) |
|
|
virtual |
◆ configCallback()
void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ onInit()
void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ ransacEstimation()
void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::ransacEstimation |
( |
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & |
cloud, |
|
|
const pcl::PointIndices::Ptr & |
indices, |
|
|
pcl::PointIndices & |
inliers, |
|
|
pcl::ModelCoefficients & |
coefficient |
|
) |
| |
|
protectedvirtual |
◆ regionGrowingFunction()
static bool jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::regionGrowingFunction |
( |
const pcl::PointXYZRGBNormal & |
a, |
|
|
const pcl::PointXYZRGBNormal & |
b, |
|
|
float |
distance |
|
) |
| |
|
inlinestaticprotected |
◆ segment()
void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::segment |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg, |
|
|
const sensor_msgs::PointCloud2::ConstPtr & |
normal_msg |
|
) |
| |
|
protectedvirtual |
◆ setCondifionFunctionParameter()
static void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::setCondifionFunctionParameter |
( |
const double |
angular_threshold, |
|
|
const double |
distance_threshold |
|
) |
| |
|
inlinestaticprotected |
◆ subscribe()
void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ angular_threshold_
double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::angular_threshold_ |
|
protected |
◆ cluster_tolerance_
double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::cluster_tolerance_ |
|
protected |
◆ distance_threshold_
double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::distance_threshold_ |
|
protected |
◆ done_initialization_
bool jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::done_initialization_ |
|
protected |
◆ global_angular_threshold
double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::global_angular_threshold = 0.0 |
|
staticprotected |
◆ global_custom_condigion_function_mutex
boost::mutex jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::global_custom_condigion_function_mutex |
|
staticprotected |
◆ global_distance_threshold
double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::global_distance_threshold = 0.0 |
|
staticprotected |
◆ max_area_
double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::max_area_ |
|
protected |
◆ max_curvature_
double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::max_curvature_ |
|
protected |
◆ max_size_
int jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::max_size_ |
|
protected |
◆ min_area_
double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::min_area_ |
|
protected |
◆ min_size_
int jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::min_size_ |
|
protected |
◆ mutex_
boost::mutex jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::mutex_ |
|
protected |
◆ pub_average_time_
ros::Publisher jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::pub_average_time_ |
|
protected |
◆ pub_clustering_result_
ros::Publisher jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::pub_clustering_result_ |
|
protected |
◆ pub_coefficients_
ros::Publisher jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::pub_coefficients_ |
|
protected |
◆ pub_inliers_
ros::Publisher jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::pub_inliers_ |
|
protected |
◆ pub_latest_time_
ros::Publisher jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::pub_latest_time_ |
|
protected |
◆ pub_polygons_
ros::Publisher jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::pub_polygons_ |
|
protected |
◆ ransac_refine_max_iterations_
int jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::ransac_refine_max_iterations_ |
|
protected |
◆ ransac_refine_outlier_distance_threshold_
double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::ransac_refine_outlier_distance_threshold_ |
|
protected |
◆ srv_
◆ sub_input_
◆ sub_normal_
◆ sync_
◆ timer_
The documentation for this class was generated from the following files: