#include <hinted_plane_detector.h>
| Public Types | |
| typedef HintedPlaneDetectorConfig | Config | 
| typedef message_filters::sync_policies::ExactTime < sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | SyncPolicy | 
| Public Member Functions | |
| HintedPlaneDetector () | |
| Protected Member Functions | |
| virtual void | configCallback (Config &config, uint32_t level) | 
| virtual void | densityFilter (const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, pcl::PointIndices &output) | 
| virtual void | detect (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &hint_cloud_msg) | 
| virtual bool | detectHintPlane (pcl::PointCloud< pcl::PointXYZ >::Ptr hint_cloud, jsk_recognition_utils::ConvexPolygon::Ptr &convex) | 
| virtual bool | detectLargerPlane (pcl::PointCloud< pcl::PointNormal >::Ptr input_cloud, jsk_recognition_utils::ConvexPolygon::Ptr hint_convex) | 
| virtual void | euclideanFilter (const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex, pcl::PointIndices &output) | 
| virtual pcl::PointIndices::Ptr | getBestCluster (pcl::PointCloud< pcl::PointNormal >::Ptr input_cloud, const std::vector< pcl::PointIndices > &cluster_indices, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex) | 
| virtual void | hintFilter (const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex, pcl::PointIndices &output) | 
| virtual void | onInit () | 
| virtual void | planeFilter (const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, const Eigen::Vector3f &normal, pcl::PointIndices &output, pcl::ModelCoefficients &coefficients) | 
| virtual void | publishPolygon (const jsk_recognition_utils::ConvexPolygon::Ptr convex, ros::Publisher &pub_polygon, ros::Publisher &pub_polygon_array, const pcl::PCLHeader &header) | 
| virtual void | subscribe () | 
| virtual void | unsubscribe () | 
| Protected Attributes | |
| int | density_num_ | 
| double | density_radius_ | 
| bool | enable_density_filtering_ | 
| bool | enable_distance_filtering_ | 
| bool | enable_euclidean_filtering_ | 
| bool | enable_normal_filtering_ | 
| double | eps_angle_ | 
| int | euclidean_clustering_filter_min_size_ | 
| double | euclidean_clustering_filter_tolerance_ | 
| int | hint_max_iteration_ | 
| int | hint_min_size_ | 
| double | hint_outlier_threashold_ | 
| int | max_iteration_ | 
| int | min_size_ | 
| boost::mutex | mutex_ | 
| double | normal_filter_eps_angle_ | 
| double | outlier_threashold_ | 
| ros::Publisher | pub_coefficients_ | 
| ros::Publisher | pub_density_filtered_indices_ | 
| ros::Publisher | pub_euclidean_filtered_indices_ | 
| ros::Publisher | pub_hint_coefficients_ | 
| ros::Publisher | pub_hint_filtered_indices_ | 
| ros::Publisher | pub_hint_inliers_ | 
| ros::Publisher | pub_hint_polygon_ | 
| ros::Publisher | pub_hint_polygon_array_ | 
| ros::Publisher | pub_inliers_ | 
| ros::Publisher | pub_plane_filtered_indices_ | 
| ros::Publisher | pub_polygon_ | 
| ros::Publisher | pub_polygon_array_ | 
| boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_cloud_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_hint_cloud_ | 
| boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ | 
Definition at line 56 of file hinted_plane_detector.h.
| typedef HintedPlaneDetectorConfig jsk_pcl_ros::HintedPlaneDetector::Config | 
Definition at line 59 of file hinted_plane_detector.h.
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> jsk_pcl_ros::HintedPlaneDetector::SyncPolicy | 
Definition at line 62 of file hinted_plane_detector.h.
Definition at line 63 of file hinted_plane_detector.h.
| void jsk_pcl_ros::HintedPlaneDetector::configCallback | ( | Config & | config, | 
| uint32_t | level | ||
| ) |  [protected, virtual] | 
Definition at line 103 of file hinted_plane_detector_nodelet.cpp.
| void jsk_pcl_ros::HintedPlaneDetector::densityFilter | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr | cloud, | 
| const pcl::PointIndices::Ptr | indices, | ||
| pcl::PointIndices & | output | ||
| ) |  [protected, virtual] | 
Definition at line 177 of file hinted_plane_detector_nodelet.cpp.
| void jsk_pcl_ros::HintedPlaneDetector::detect | ( | const sensor_msgs::PointCloud2::ConstPtr & | cloud_msg, | 
| const sensor_msgs::PointCloud2::ConstPtr & | hint_cloud_msg | ||
| ) |  [protected, virtual] | 
Definition at line 125 of file hinted_plane_detector_nodelet.cpp.
| bool jsk_pcl_ros::HintedPlaneDetector::detectHintPlane | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr | hint_cloud, | 
| jsk_recognition_utils::ConvexPolygon::Ptr & | convex | ||
| ) |  [protected, virtual] | 
Definition at line 365 of file hinted_plane_detector_nodelet.cpp.
| bool jsk_pcl_ros::HintedPlaneDetector::detectLargerPlane | ( | pcl::PointCloud< pcl::PointNormal >::Ptr | input_cloud, | 
| jsk_recognition_utils::ConvexPolygon::Ptr | hint_convex | ||
| ) |  [protected, virtual] | 
Definition at line 291 of file hinted_plane_detector_nodelet.cpp.
| void jsk_pcl_ros::HintedPlaneDetector::euclideanFilter | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr | cloud, | 
| const pcl::PointIndices::Ptr | indices, | ||
| const jsk_recognition_utils::ConvexPolygon::Ptr | hint_convex, | ||
| pcl::PointIndices & | output | ||
| ) |  [protected, virtual] | 
Definition at line 208 of file hinted_plane_detector_nodelet.cpp.
| pcl::PointIndices::Ptr jsk_pcl_ros::HintedPlaneDetector::getBestCluster | ( | pcl::PointCloud< pcl::PointNormal >::Ptr | input_cloud, | 
| const std::vector< pcl::PointIndices > & | cluster_indices, | ||
| const jsk_recognition_utils::ConvexPolygon::Ptr | hint_convex | ||
| ) |  [protected, virtual] | 
Definition at line 152 of file hinted_plane_detector_nodelet.cpp.
| void jsk_pcl_ros::HintedPlaneDetector::hintFilter | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr | cloud, | 
| const jsk_recognition_utils::ConvexPolygon::Ptr | hint_convex, | ||
| pcl::PointIndices & | output | ||
| ) |  [protected, virtual] | 
Definition at line 243 of file hinted_plane_detector_nodelet.cpp.
| void jsk_pcl_ros::HintedPlaneDetector::onInit | ( | void | ) |  [protected, virtual] | 
Definition at line 52 of file hinted_plane_detector_nodelet.cpp.
| void jsk_pcl_ros::HintedPlaneDetector::planeFilter | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr | cloud, | 
| const pcl::PointIndices::Ptr | indices, | ||
| const Eigen::Vector3f & | normal, | ||
| pcl::PointIndices & | output, | ||
| pcl::ModelCoefficients & | coefficients | ||
| ) |  [protected, virtual] | 
Definition at line 266 of file hinted_plane_detector_nodelet.cpp.
| void jsk_pcl_ros::HintedPlaneDetector::publishPolygon | ( | const jsk_recognition_utils::ConvexPolygon::Ptr | convex, | 
| ros::Publisher & | pub_polygon, | ||
| ros::Publisher & | pub_polygon_array, | ||
| const pcl::PCLHeader & | header | ||
| ) |  [protected, virtual] | 
Definition at line 348 of file hinted_plane_detector_nodelet.cpp.
| void jsk_pcl_ros::HintedPlaneDetector::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 87 of file hinted_plane_detector_nodelet.cpp.
| void jsk_pcl_ros::HintedPlaneDetector::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 97 of file hinted_plane_detector_nodelet.cpp.
| int jsk_pcl_ros::HintedPlaneDetector::density_num_  [protected] | 
Definition at line 146 of file hinted_plane_detector.h.
| double jsk_pcl_ros::HintedPlaneDetector::density_radius_  [protected] | 
Definition at line 145 of file hinted_plane_detector.h.
| bool jsk_pcl_ros::HintedPlaneDetector::enable_density_filtering_  [protected] | 
Definition at line 144 of file hinted_plane_detector.h.
| bool jsk_pcl_ros::HintedPlaneDetector::enable_distance_filtering_  [protected] | 
Definition at line 143 of file hinted_plane_detector.h.
| bool jsk_pcl_ros::HintedPlaneDetector::enable_euclidean_filtering_  [protected] | 
Definition at line 141 of file hinted_plane_detector.h.
| bool jsk_pcl_ros::HintedPlaneDetector::enable_normal_filtering_  [protected] | 
Definition at line 142 of file hinted_plane_detector.h.
| double jsk_pcl_ros::HintedPlaneDetector::eps_angle_  [protected] | 
Definition at line 137 of file hinted_plane_detector.h.
Definition at line 140 of file hinted_plane_detector.h.
| double jsk_pcl_ros::HintedPlaneDetector::euclidean_clustering_filter_tolerance_  [protected] | 
Definition at line 139 of file hinted_plane_detector.h.
| int jsk_pcl_ros::HintedPlaneDetector::hint_max_iteration_  [protected] | 
Definition at line 132 of file hinted_plane_detector.h.
| int jsk_pcl_ros::HintedPlaneDetector::hint_min_size_  [protected] | 
Definition at line 133 of file hinted_plane_detector.h.
| double jsk_pcl_ros::HintedPlaneDetector::hint_outlier_threashold_  [protected] | 
Definition at line 131 of file hinted_plane_detector.h.
| int jsk_pcl_ros::HintedPlaneDetector::max_iteration_  [protected] | 
Definition at line 134 of file hinted_plane_detector.h.
| int jsk_pcl_ros::HintedPlaneDetector::min_size_  [protected] | 
Definition at line 135 of file hinted_plane_detector.h.
| boost::mutex jsk_pcl_ros::HintedPlaneDetector::mutex_  [protected] | 
Definition at line 126 of file hinted_plane_detector.h.
| double jsk_pcl_ros::HintedPlaneDetector::normal_filter_eps_angle_  [protected] | 
Definition at line 138 of file hinted_plane_detector.h.
| double jsk_pcl_ros::HintedPlaneDetector::outlier_threashold_  [protected] | 
Definition at line 136 of file hinted_plane_detector.h.
Definition at line 120 of file hinted_plane_detector.h.
Definition at line 123 of file hinted_plane_detector.h.
Definition at line 124 of file hinted_plane_detector.h.
Definition at line 116 of file hinted_plane_detector.h.
Definition at line 121 of file hinted_plane_detector.h.
Definition at line 115 of file hinted_plane_detector.h.
Definition at line 113 of file hinted_plane_detector.h.
Definition at line 114 of file hinted_plane_detector.h.
Definition at line 119 of file hinted_plane_detector.h.
Definition at line 122 of file hinted_plane_detector.h.
Definition at line 118 of file hinted_plane_detector.h.
Definition at line 117 of file hinted_plane_detector.h.
| boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::HintedPlaneDetector::srv_  [protected] | 
Definition at line 125 of file hinted_plane_detector.h.
| message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::HintedPlaneDetector::sub_cloud_  [protected] | 
Definition at line 111 of file hinted_plane_detector.h.
| message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::HintedPlaneDetector::sub_hint_cloud_  [protected] | 
Definition at line 112 of file hinted_plane_detector.h.
| boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::HintedPlaneDetector::sync_  [protected] | 
Definition at line 110 of file hinted_plane_detector.h.