Public Types | Protected Member Functions | Protected Attributes | Private Member Functions | List of all members
jsk_pcl_ros::OrganizedMultiPlaneSegmentation Class Reference

#include <organized_multi_plane_segmentation.h>

Inheritance diagram for jsk_pcl_ros::OrganizedMultiPlaneSegmentation:
Inheritance graph
[legend]

Public Types

typedef jsk_pcl_ros::OrganizedMultiPlaneSegmentationConfig Config
 
typedef std::vector< pcl::PlanarRegion< PointT >, Eigen::aligned_allocator< pcl::PlanarRegion< PointT > > > PlanarRegionVector
 
typedef pcl::PointXYZRGBA PointT
 

Protected Member Functions

virtual void buildConnectedPlanes (const pcl::PointCloud< PointT >::Ptr &input, const std_msgs::Header &header, const std::vector< pcl::PointIndices > &inlier_indices, const std::vector< pcl::PointIndices > &boundary_indices, const std::vector< pcl::ModelCoefficients > &model_coefficients, const jsk_recognition_utils::IntegerGraphMap &connection_map, std::vector< pcl::PointIndices > &output_indices, std::vector< pcl::ModelCoefficients > &output_coefficients, std::vector< pcl::PointCloud< PointT > > &output_boundary_clouds)
 
virtual void configCallback (Config &config, uint32_t level)
 
virtual void connectPlanesMap (const pcl::PointCloud< PointT >::Ptr &input, const std::vector< pcl::ModelCoefficients > &model_coefficients, const std::vector< pcl::PointIndices > &boundary_indices, jsk_recognition_utils::IntegerGraphMap &connection_map)
 
virtual void estimateNormal (pcl::PointCloud< PointT >::Ptr input, pcl::PointCloud< pcl::Normal >::Ptr output)
 
virtual void forceToDirectOrigin (const std::vector< pcl::ModelCoefficients > &coefficients, std::vector< pcl::ModelCoefficients > &output_coefficients)
 
virtual void pclIndicesArrayToClusterPointIndices (const std::vector< pcl::PointIndices > &inlier_indices, const std_msgs::Header &header, jsk_recognition_msgs::ClusterPointIndices &output_indices)
 
virtual void pointCloudToPolygon (const pcl::PointCloud< PointT > &input, geometry_msgs::Polygon &polygon)
 
virtual void publishMarkerOfConnection (jsk_recognition_utils::IntegerGraphMap connection_map, const pcl::PointCloud< PointT >::Ptr cloud, const std::vector< pcl::PointIndices > &inliers, const std_msgs::Header &header)
 
virtual void publishSegmentationInformation (const std_msgs::Header &header, const pcl::PointCloud< PointT >::Ptr input, ros::Publisher &indices_pub, ros::Publisher &polygon_pub, ros::Publisher &coefficients_pub, const std::vector< pcl::PointIndices > &inlier_indices, const std::vector< pcl::PointCloud< PointT > > &boundaries, const std::vector< pcl::ModelCoefficients > &model_coefficients)
 
virtual void publishSegmentationInformation (const std_msgs::Header &header, const pcl::PointCloud< PointT >::Ptr input, ros::Publisher &indices_pub, ros::Publisher &polygon_pub, ros::Publisher &coefficients_pub, const std::vector< pcl::PointIndices > &inlier_indices, const std::vector< pcl::PointIndices > &boundary_indices, const std::vector< pcl::ModelCoefficients > &model_coefficients)
 
virtual void refineBasedOnRANSAC (const pcl::PointCloud< PointT >::Ptr input, const std::vector< pcl::PointIndices > &input_indices, const std::vector< pcl::ModelCoefficients > &input_coefficients, std::vector< pcl::PointIndices > &output_indices, std::vector< pcl::ModelCoefficients > &output_coefficients, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &output_boundaries)
 
virtual void segment (const sensor_msgs::PointCloud2::ConstPtr &msg)
 
virtual void segmentFromNormals (pcl::PointCloud< PointT >::Ptr input, pcl::PointCloud< pcl::Normal >::Ptr normal, const std_msgs::Header &header)
 
virtual void segmentOrganizedMultiPlanes (pcl::PointCloud< PointT >::Ptr input, pcl::PointCloud< pcl::Normal >::Ptr normal, PlanarRegionVector &regions, std::vector< pcl::ModelCoefficients > &model_coefficients, std::vector< pcl::PointIndices > &inlier_indices, pcl::PointCloud< pcl::Label >::Ptr &labels, std::vector< pcl::PointIndices > &label_indices, std::vector< pcl::PointIndices > &boundary_indices)
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 
virtual void updateDiagnosticNormalEstimation (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
virtual void updateDiagnosticPlaneSegmentation (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
virtual void updateDiagnostics (const ros::TimerEvent &event)
 

Protected Attributes

double angular_threshold_
 
bool border_policy_ignore_
 
ros::Publisher coefficients_pub_
 
double concave_alpha_
 
double connect_distance_threshold_
 
double connect_plane_angle_threshold_
 
jsk_recognition_utils::Counter connected_plane_num_counter_
 
bool depth_dependent_smoothing_
 
boost::shared_ptr< diagnostic_updater::Updaterdiagnostic_updater_
 
ros::Timer diagnostics_timer_
 
double distance_threshold_
 
bool estimate_normal_
 
int estimation_method_
 
double max_curvature_
 
double max_depth_change_factor_
 
double max_refined_area_threshold_
 
double min_refined_area_threshold_
 
int min_size_
 
boost::mutex mutex_
 
jsk_topic_tools::TimeAccumulator normal_estimation_time_acc_
 
jsk_topic_tools::VitalChecker::Ptr normal_estimation_vital_checker_
 
ros::Publisher normal_pub_
 
double normal_smoothing_size_
 
ros::Publisher org_coefficients_pub_
 
ros::Publisher org_polygon_pub_
 
ros::Publisher org_pub_
 
jsk_recognition_utils::Counter original_plane_num_counter_
 
jsk_topic_tools::TimeAccumulator plane_segmentation_time_acc_
 
jsk_topic_tools::VitalChecker::Ptr plane_segmentation_vital_checker_
 
ros::Publisher polygon_pub_
 
jsk_topic_tools::ConnectionStatus previous_checked_connection_status_for_normal_
 Previous checked status of connection. More...
 
jsk_topic_tools::ConnectionStatus previous_checked_connection_status_for_plane_
 Previous checked status of connection for plane segmentation. More...
 
ros::Publisher pub_
 
ros::Publisher pub_connection_marker_
 
bool publish_normal_
 
bool ransac_refine_coefficients_
 
double ransac_refine_outlier_distance_threshold_
 
jsk_topic_tools::TimeAccumulator ransac_refinement_time_acc_
 
ros::Publisher refined_coefficients_pub_
 
ros::Publisher refined_polygon_pub_
 
ros::Publisher refined_pub_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
ros::Subscriber sub_
 

Private Member Functions

virtual void onInit ()
 

Detailed Description

Definition at line 94 of file organized_multi_plane_segmentation.h.

Member Typedef Documentation

◆ Config

typedef jsk_pcl_ros::OrganizedMultiPlaneSegmentationConfig jsk_pcl_ros::OrganizedMultiPlaneSegmentation::Config

Definition at line 134 of file organized_multi_plane_segmentation.h.

◆ PlanarRegionVector

typedef std::vector<pcl::PlanarRegion<PointT>, Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > > jsk_pcl_ros::OrganizedMultiPlaneSegmentation::PlanarRegionVector

Definition at line 133 of file organized_multi_plane_segmentation.h.

◆ PointT

Definition at line 130 of file organized_multi_plane_segmentation.h.

Member Function Documentation

◆ buildConnectedPlanes()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::buildConnectedPlanes ( const pcl::PointCloud< PointT >::Ptr &  input,
const std_msgs::Header header,
const std::vector< pcl::PointIndices > &  inlier_indices,
const std::vector< pcl::PointIndices > &  boundary_indices,
const std::vector< pcl::ModelCoefficients > &  model_coefficients,
const jsk_recognition_utils::IntegerGraphMap connection_map,
std::vector< pcl::PointIndices > &  output_indices,
std::vector< pcl::ModelCoefficients > &  output_coefficients,
std::vector< pcl::PointCloud< PointT > > &  output_boundary_clouds 
)
protectedvirtual

◆ configCallback()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

◆ connectPlanesMap()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::connectPlanesMap ( const pcl::PointCloud< PointT >::Ptr &  input,
const std::vector< pcl::ModelCoefficients > &  model_coefficients,
const std::vector< pcl::PointIndices > &  boundary_indices,
jsk_recognition_utils::IntegerGraphMap connection_map 
)
protectedvirtual

◆ estimateNormal()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::estimateNormal ( pcl::PointCloud< PointT >::Ptr  input,
pcl::PointCloud< pcl::Normal >::Ptr  output 
)
protectedvirtual

◆ forceToDirectOrigin()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::forceToDirectOrigin ( const std::vector< pcl::ModelCoefficients > &  coefficients,
std::vector< pcl::ModelCoefficients > &  output_coefficients 
)
protectedvirtual

◆ onInit()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::onInit ( )
privatevirtual

◆ pclIndicesArrayToClusterPointIndices()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::pclIndicesArrayToClusterPointIndices ( const std::vector< pcl::PointIndices > &  inlier_indices,
const std_msgs::Header header,
jsk_recognition_msgs::ClusterPointIndices &  output_indices 
)
protectedvirtual

◆ pointCloudToPolygon()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::pointCloudToPolygon ( const pcl::PointCloud< PointT > &  input,
geometry_msgs::Polygon &  polygon 
)
protectedvirtual

◆ publishMarkerOfConnection()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::publishMarkerOfConnection ( jsk_recognition_utils::IntegerGraphMap  connection_map,
const pcl::PointCloud< PointT >::Ptr  cloud,
const std::vector< pcl::PointIndices > &  inliers,
const std_msgs::Header header 
)
protectedvirtual

◆ publishSegmentationInformation() [1/2]

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::publishSegmentationInformation ( const std_msgs::Header header,
const pcl::PointCloud< PointT >::Ptr  input,
ros::Publisher indices_pub,
ros::Publisher polygon_pub,
ros::Publisher coefficients_pub,
const std::vector< pcl::PointIndices > &  inlier_indices,
const std::vector< pcl::PointCloud< PointT > > &  boundaries,
const std::vector< pcl::ModelCoefficients > &  model_coefficients 
)
protectedvirtual

◆ publishSegmentationInformation() [2/2]

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::publishSegmentationInformation ( const std_msgs::Header header,
const pcl::PointCloud< PointT >::Ptr  input,
ros::Publisher indices_pub,
ros::Publisher polygon_pub,
ros::Publisher coefficients_pub,
const std::vector< pcl::PointIndices > &  inlier_indices,
const std::vector< pcl::PointIndices > &  boundary_indices,
const std::vector< pcl::ModelCoefficients > &  model_coefficients 
)
protectedvirtual

◆ refineBasedOnRANSAC()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::refineBasedOnRANSAC ( const pcl::PointCloud< PointT >::Ptr  input,
const std::vector< pcl::PointIndices > &  input_indices,
const std::vector< pcl::ModelCoefficients > &  input_coefficients,
std::vector< pcl::PointIndices > &  output_indices,
std::vector< pcl::ModelCoefficients > &  output_coefficients,
std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &  output_boundaries 
)
protectedvirtual

◆ segment()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::segment ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual

◆ segmentFromNormals()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::segmentFromNormals ( pcl::PointCloud< PointT >::Ptr  input,
pcl::PointCloud< pcl::Normal >::Ptr  normal,
const std_msgs::Header header 
)
protectedvirtual

◆ segmentOrganizedMultiPlanes()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::segmentOrganizedMultiPlanes ( pcl::PointCloud< PointT >::Ptr  input,
pcl::PointCloud< pcl::Normal >::Ptr  normal,
PlanarRegionVector regions,
std::vector< pcl::ModelCoefficients > &  model_coefficients,
std::vector< pcl::PointIndices > &  inlier_indices,
pcl::PointCloud< pcl::Label >::Ptr &  labels,
std::vector< pcl::PointIndices > &  label_indices,
std::vector< pcl::PointIndices > &  boundary_indices 
)
protectedvirtual

◆ subscribe()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::subscribe ( )
protectedvirtual

◆ unsubscribe()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::unsubscribe ( )
protectedvirtual

◆ updateDiagnosticNormalEstimation()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::updateDiagnosticNormalEstimation ( diagnostic_updater::DiagnosticStatusWrapper stat)
protectedvirtual

◆ updateDiagnosticPlaneSegmentation()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::updateDiagnosticPlaneSegmentation ( diagnostic_updater::DiagnosticStatusWrapper stat)
protectedvirtual

◆ updateDiagnostics()

void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::updateDiagnostics ( const ros::TimerEvent event)
protectedvirtual

Member Data Documentation

◆ angular_threshold_

double jsk_pcl_ros::OrganizedMultiPlaneSegmentation::angular_threshold_
protected

Definition at line 239 of file organized_multi_plane_segmentation.h.

◆ border_policy_ignore_

bool jsk_pcl_ros::OrganizedMultiPlaneSegmentation::border_policy_ignore_
protected

Definition at line 250 of file organized_multi_plane_segmentation.h.

◆ coefficients_pub_

ros::Publisher jsk_pcl_ros::OrganizedMultiPlaneSegmentation::coefficients_pub_
protected

Definition at line 222 of file organized_multi_plane_segmentation.h.

◆ concave_alpha_

double jsk_pcl_ros::OrganizedMultiPlaneSegmentation::concave_alpha_
protected

Definition at line 238 of file organized_multi_plane_segmentation.h.

◆ connect_distance_threshold_

double jsk_pcl_ros::OrganizedMultiPlaneSegmentation::connect_distance_threshold_
protected

Definition at line 243 of file organized_multi_plane_segmentation.h.

◆ connect_plane_angle_threshold_

double jsk_pcl_ros::OrganizedMultiPlaneSegmentation::connect_plane_angle_threshold_
protected

Definition at line 242 of file organized_multi_plane_segmentation.h.

◆ connected_plane_num_counter_

jsk_recognition_utils::Counter jsk_pcl_ros::OrganizedMultiPlaneSegmentation::connected_plane_num_counter_
protected

Definition at line 271 of file organized_multi_plane_segmentation.h.

◆ depth_dependent_smoothing_

bool jsk_pcl_ros::OrganizedMultiPlaneSegmentation::depth_dependent_smoothing_
protected

Definition at line 247 of file organized_multi_plane_segmentation.h.

◆ diagnostic_updater_

boost::shared_ptr<diagnostic_updater::Updater> jsk_pcl_ros::OrganizedMultiPlaneSegmentation::diagnostic_updater_
protected

Definition at line 229 of file organized_multi_plane_segmentation.h.

◆ diagnostics_timer_

ros::Timer jsk_pcl_ros::OrganizedMultiPlaneSegmentation::diagnostics_timer_
protected

Definition at line 235 of file organized_multi_plane_segmentation.h.

◆ distance_threshold_

double jsk_pcl_ros::OrganizedMultiPlaneSegmentation::distance_threshold_
protected

Definition at line 240 of file organized_multi_plane_segmentation.h.

◆ estimate_normal_

bool jsk_pcl_ros::OrganizedMultiPlaneSegmentation::estimate_normal_
protected

Definition at line 251 of file organized_multi_plane_segmentation.h.

◆ estimation_method_

int jsk_pcl_ros::OrganizedMultiPlaneSegmentation::estimation_method_
protected

Definition at line 246 of file organized_multi_plane_segmentation.h.

◆ max_curvature_

double jsk_pcl_ros::OrganizedMultiPlaneSegmentation::max_curvature_
protected

Definition at line 241 of file organized_multi_plane_segmentation.h.

◆ max_depth_change_factor_

double jsk_pcl_ros::OrganizedMultiPlaneSegmentation::max_depth_change_factor_
protected

Definition at line 248 of file organized_multi_plane_segmentation.h.

◆ max_refined_area_threshold_

double jsk_pcl_ros::OrganizedMultiPlaneSegmentation::max_refined_area_threshold_
protected

Definition at line 245 of file organized_multi_plane_segmentation.h.

◆ min_refined_area_threshold_

double jsk_pcl_ros::OrganizedMultiPlaneSegmentation::min_refined_area_threshold_
protected

Definition at line 244 of file organized_multi_plane_segmentation.h.

◆ min_size_

int jsk_pcl_ros::OrganizedMultiPlaneSegmentation::min_size_
protected

Definition at line 237 of file organized_multi_plane_segmentation.h.

◆ mutex_

boost::mutex jsk_pcl_ros::OrganizedMultiPlaneSegmentation::mutex_
protected

Definition at line 228 of file organized_multi_plane_segmentation.h.

◆ normal_estimation_time_acc_

jsk_topic_tools::TimeAccumulator jsk_pcl_ros::OrganizedMultiPlaneSegmentation::normal_estimation_time_acc_
protected

Definition at line 231 of file organized_multi_plane_segmentation.h.

◆ normal_estimation_vital_checker_

jsk_topic_tools::VitalChecker::Ptr jsk_pcl_ros::OrganizedMultiPlaneSegmentation::normal_estimation_vital_checker_
protected

Definition at line 233 of file organized_multi_plane_segmentation.h.

◆ normal_pub_

ros::Publisher jsk_pcl_ros::OrganizedMultiPlaneSegmentation::normal_pub_
protected

Definition at line 224 of file organized_multi_plane_segmentation.h.

◆ normal_smoothing_size_

double jsk_pcl_ros::OrganizedMultiPlaneSegmentation::normal_smoothing_size_
protected

Definition at line 249 of file organized_multi_plane_segmentation.h.

◆ org_coefficients_pub_

ros::Publisher jsk_pcl_ros::OrganizedMultiPlaneSegmentation::org_coefficients_pub_
protected

Definition at line 221 of file organized_multi_plane_segmentation.h.

◆ org_polygon_pub_

ros::Publisher jsk_pcl_ros::OrganizedMultiPlaneSegmentation::org_polygon_pub_
protected

Definition at line 221 of file organized_multi_plane_segmentation.h.

◆ org_pub_

ros::Publisher jsk_pcl_ros::OrganizedMultiPlaneSegmentation::org_pub_
protected

Definition at line 221 of file organized_multi_plane_segmentation.h.

◆ original_plane_num_counter_

jsk_recognition_utils::Counter jsk_pcl_ros::OrganizedMultiPlaneSegmentation::original_plane_num_counter_
protected

Definition at line 270 of file organized_multi_plane_segmentation.h.

◆ plane_segmentation_time_acc_

jsk_topic_tools::TimeAccumulator jsk_pcl_ros::OrganizedMultiPlaneSegmentation::plane_segmentation_time_acc_
protected

Definition at line 230 of file organized_multi_plane_segmentation.h.

◆ plane_segmentation_vital_checker_

jsk_topic_tools::VitalChecker::Ptr jsk_pcl_ros::OrganizedMultiPlaneSegmentation::plane_segmentation_vital_checker_
protected

Definition at line 234 of file organized_multi_plane_segmentation.h.

◆ polygon_pub_

ros::Publisher jsk_pcl_ros::OrganizedMultiPlaneSegmentation::polygon_pub_
protected

Definition at line 222 of file organized_multi_plane_segmentation.h.

◆ previous_checked_connection_status_for_normal_

jsk_topic_tools::ConnectionStatus jsk_pcl_ros::OrganizedMultiPlaneSegmentation::previous_checked_connection_status_for_normal_
protected

Previous checked status of connection.

Definition at line 257 of file organized_multi_plane_segmentation.h.

◆ previous_checked_connection_status_for_plane_

jsk_topic_tools::ConnectionStatus jsk_pcl_ros::OrganizedMultiPlaneSegmentation::previous_checked_connection_status_for_plane_
protected

Previous checked status of connection for plane segmentation.

Definition at line 262 of file organized_multi_plane_segmentation.h.

◆ pub_

ros::Publisher jsk_pcl_ros::OrganizedMultiPlaneSegmentation::pub_
protected

Definition at line 222 of file organized_multi_plane_segmentation.h.

◆ pub_connection_marker_

ros::Publisher jsk_pcl_ros::OrganizedMultiPlaneSegmentation::pub_connection_marker_
protected

Definition at line 225 of file organized_multi_plane_segmentation.h.

◆ publish_normal_

bool jsk_pcl_ros::OrganizedMultiPlaneSegmentation::publish_normal_
protected

Definition at line 252 of file organized_multi_plane_segmentation.h.

◆ ransac_refine_coefficients_

bool jsk_pcl_ros::OrganizedMultiPlaneSegmentation::ransac_refine_coefficients_
protected

Definition at line 267 of file organized_multi_plane_segmentation.h.

◆ ransac_refine_outlier_distance_threshold_

double jsk_pcl_ros::OrganizedMultiPlaneSegmentation::ransac_refine_outlier_distance_threshold_
protected

Definition at line 268 of file organized_multi_plane_segmentation.h.

◆ ransac_refinement_time_acc_

jsk_topic_tools::TimeAccumulator jsk_pcl_ros::OrganizedMultiPlaneSegmentation::ransac_refinement_time_acc_
protected

Definition at line 232 of file organized_multi_plane_segmentation.h.

◆ refined_coefficients_pub_

ros::Publisher jsk_pcl_ros::OrganizedMultiPlaneSegmentation::refined_coefficients_pub_
protected

Definition at line 223 of file organized_multi_plane_segmentation.h.

◆ refined_polygon_pub_

ros::Publisher jsk_pcl_ros::OrganizedMultiPlaneSegmentation::refined_polygon_pub_
protected

Definition at line 223 of file organized_multi_plane_segmentation.h.

◆ refined_pub_

ros::Publisher jsk_pcl_ros::OrganizedMultiPlaneSegmentation::refined_pub_
protected

Definition at line 223 of file organized_multi_plane_segmentation.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::OrganizedMultiPlaneSegmentation::srv_
protected

Definition at line 227 of file organized_multi_plane_segmentation.h.

◆ sub_

ros::Subscriber jsk_pcl_ros::OrganizedMultiPlaneSegmentation::sub_
protected

Definition at line 226 of file organized_multi_plane_segmentation.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:46