Public Types | Protected Member Functions | Protected Attributes | Private Member Functions
jsk_pcl_ros::OrganizedMultiPlaneSegmentation Class Reference

#include <organized_multi_plane_segmentation.h>

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

List of all members.

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::Updater
diagnostic_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_
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 62 of file organized_multi_plane_segmentation.h.


Member Typedef Documentation

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

Definition at line 70 of file organized_multi_plane_segmentation.h.

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

Definition at line 69 of file organized_multi_plane_segmentation.h.

Definition at line 66 of file organized_multi_plane_segmentation.h.


Member Function Documentation

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 
) [protected, virtual]
void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]
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 
) [protected, virtual]
void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::estimateNormal ( pcl::PointCloud< PointT >::Ptr  input,
pcl::PointCloud< pcl::Normal >::Ptr  output 
) [protected, virtual]
void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::forceToDirectOrigin ( const std::vector< pcl::ModelCoefficients > &  coefficients,
std::vector< pcl::ModelCoefficients > &  output_coefficients 
) [protected, virtual]
void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::onInit ( void  ) [private, virtual]
void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::pclIndicesArrayToClusterPointIndices ( const std::vector< pcl::PointIndices > &  inlier_indices,
const std_msgs::Header header,
jsk_recognition_msgs::ClusterPointIndices &  output_indices 
) [protected, virtual]
void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::pointCloudToPolygon ( const pcl::PointCloud< PointT > &  input,
geometry_msgs::Polygon &  polygon 
) [protected, virtual]
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 
) [protected, virtual]
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 
) [protected, virtual]
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 
) [protected, virtual]
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 
) [protected, virtual]
void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::segment ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [protected, virtual]
void jsk_pcl_ros::OrganizedMultiPlaneSegmentation::segmentFromNormals ( pcl::PointCloud< PointT >::Ptr  input,
pcl::PointCloud< pcl::Normal >::Ptr  normal,
const std_msgs::Header header 
) [protected, virtual]
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 
) [protected, virtual]

Member Data Documentation

Definition at line 175 of file organized_multi_plane_segmentation.h.

Definition at line 186 of file organized_multi_plane_segmentation.h.

Definition at line 158 of file organized_multi_plane_segmentation.h.

Definition at line 174 of file organized_multi_plane_segmentation.h.

Definition at line 179 of file organized_multi_plane_segmentation.h.

Definition at line 178 of file organized_multi_plane_segmentation.h.

Definition at line 197 of file organized_multi_plane_segmentation.h.

Definition at line 183 of file organized_multi_plane_segmentation.h.

Definition at line 165 of file organized_multi_plane_segmentation.h.

Definition at line 171 of file organized_multi_plane_segmentation.h.

Definition at line 176 of file organized_multi_plane_segmentation.h.

Definition at line 187 of file organized_multi_plane_segmentation.h.

Definition at line 182 of file organized_multi_plane_segmentation.h.

Definition at line 177 of file organized_multi_plane_segmentation.h.

Definition at line 184 of file organized_multi_plane_segmentation.h.

Definition at line 181 of file organized_multi_plane_segmentation.h.

Definition at line 180 of file organized_multi_plane_segmentation.h.

Definition at line 173 of file organized_multi_plane_segmentation.h.

Definition at line 164 of file organized_multi_plane_segmentation.h.

Definition at line 167 of file organized_multi_plane_segmentation.h.

Definition at line 169 of file organized_multi_plane_segmentation.h.

Definition at line 160 of file organized_multi_plane_segmentation.h.

Definition at line 185 of file organized_multi_plane_segmentation.h.

Definition at line 157 of file organized_multi_plane_segmentation.h.

Definition at line 157 of file organized_multi_plane_segmentation.h.

Definition at line 157 of file organized_multi_plane_segmentation.h.

Definition at line 196 of file organized_multi_plane_segmentation.h.

Definition at line 166 of file organized_multi_plane_segmentation.h.

Definition at line 170 of file organized_multi_plane_segmentation.h.

Definition at line 158 of file organized_multi_plane_segmentation.h.

Definition at line 158 of file organized_multi_plane_segmentation.h.

Definition at line 161 of file organized_multi_plane_segmentation.h.

Definition at line 188 of file organized_multi_plane_segmentation.h.

Definition at line 193 of file organized_multi_plane_segmentation.h.

Definition at line 194 of file organized_multi_plane_segmentation.h.

Definition at line 168 of file organized_multi_plane_segmentation.h.

Definition at line 159 of file organized_multi_plane_segmentation.h.

Definition at line 159 of file organized_multi_plane_segmentation.h.

Definition at line 159 of file organized_multi_plane_segmentation.h.

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

Definition at line 163 of file organized_multi_plane_segmentation.h.

Definition at line 162 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 Jul 2 2019 19:41:47