#include <organized_multi_plane_segmentation.h>
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 ®ions, 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) |
Private Member Functions | |
virtual void | onInit () |
Definition at line 94 of file organized_multi_plane_segmentation.h.
typedef jsk_pcl_ros::OrganizedMultiPlaneSegmentationConfig jsk_pcl_ros::OrganizedMultiPlaneSegmentation::Config |
Definition at line 134 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 133 of file organized_multi_plane_segmentation.h.
typedef pcl::PointXYZRGBA jsk_pcl_ros::OrganizedMultiPlaneSegmentation::PointT |
Definition at line 130 of file organized_multi_plane_segmentation.h.
|
protectedvirtual |
Definition at line 347 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 207 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 230 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 745 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 173 of file organized_multi_plane_segmentation_nodelet.cpp.
|
privatevirtual |
Definition at line 97 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 320 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 334 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 542 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 463 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 510 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 687 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 780 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 606 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 437 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 196 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 202 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 809 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 871 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protectedvirtual |
Definition at line 920 of file organized_multi_plane_segmentation_nodelet.cpp.
|
protected |
Definition at line 239 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 250 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 222 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 238 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 243 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 242 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 271 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 247 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 229 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 235 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 240 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 251 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 246 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 241 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 248 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 245 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 244 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 237 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 228 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 231 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 233 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 224 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 249 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 221 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 221 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 221 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 270 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 230 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 234 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 222 of file organized_multi_plane_segmentation.h.
|
protected |
Previous checked status of connection.
Definition at line 257 of file organized_multi_plane_segmentation.h.
|
protected |
Previous checked status of connection for plane segmentation.
Definition at line 262 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 222 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 225 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 252 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 267 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 268 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 232 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 223 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 223 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 223 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 227 of file organized_multi_plane_segmentation.h.
|
protected |
Definition at line 226 of file organized_multi_plane_segmentation.h.