#include <line_segment_detector.h>
| Public Types | |
| typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > | ApproximateSyncPolicy | 
| typedef jsk_pcl_ros::LineSegmentDetectorConfig | Config | 
| typedef pcl::PointXYZ | PointT | 
| typedef message_filters::sync_policies::ExactTime < sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > | SyncPolicy | 
| Public Member Functions | |
| LineSegmentDetector () | |
| ~LineSegmentDetector () | |
| Protected Member Functions | |
| virtual void | configCallback (Config &config, uint32_t level) | 
| virtual void | onInit () | 
| virtual void | publishResult (const std_msgs::Header &header, const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< LineSegment::Ptr > &segments) | 
| virtual void | segment (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &cluster_msg) | 
| virtual void | segmentLines (const pcl::PointCloud< PointT >::Ptr &cloud, const pcl::PointIndices::Ptr &indices, std::vector< pcl::PointIndices::Ptr > &line_indices, std::vector< pcl::ModelCoefficients::Ptr > &line_coefficients) | 
| virtual void | subscribe () | 
| virtual void | unsubscribe () | 
| Protected Attributes | |
| bool | approximate_sync_ | 
| boost::shared_ptr < message_filters::Synchronizer < ApproximateSyncPolicy > > | async_ | 
| boost::recursive_mutex | config_mutex_ | 
| double | line_width_ | 
| int | max_iterations_ | 
| int | min_indices_ | 
| double | min_length_ | 
| boost::mutex | mutex_ | 
| double | outlier_threshold_ | 
| ros::Publisher | pub_coefficients_ | 
| ros::Publisher | pub_indices_ | 
| ros::Publisher | pub_line_marker_ | 
| pcl::SACSegmentation< PointT > | seg_ | 
| boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ | 
| message_filters::Subscriber < jsk_recognition_msgs::ClusterPointIndices > | sub_indices_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_input_ | 
| boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ | 
Definition at line 90 of file line_segment_detector.h.
| typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices> jsk_pcl_ros::LineSegmentDetector::ApproximateSyncPolicy | 
Definition at line 106 of file line_segment_detector.h.
| typedef jsk_pcl_ros::LineSegmentDetectorConfig jsk_pcl_ros::LineSegmentDetector::Config | 
Definition at line 108 of file line_segment_detector.h.
| typedef pcl::PointXYZ jsk_pcl_ros::LineSegmentDetector::PointT | 
Definition at line 107 of file line_segment_detector.h.
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices> jsk_pcl_ros::LineSegmentDetector::SyncPolicy | 
Definition at line 103 of file line_segment_detector.h.
Definition at line 93 of file line_segment_detector.h.
Definition at line 96 of file line_segment_detector.h.
| void jsk_pcl_ros::LineSegmentDetector::configCallback | ( | Config & | config, | 
| uint32_t | level | ||
| ) |  [protected, virtual] | 
Definition at line 156 of file line_segment_detector_nodelet.cpp.
| void jsk_pcl_ros::LineSegmentDetector::onInit | ( | void | ) |  [protected, virtual] | 
Definition at line 132 of file line_segment_detector_nodelet.cpp.
| void jsk_pcl_ros::LineSegmentDetector::publishResult | ( | const std_msgs::Header & | header, | 
| const pcl::PointCloud< PointT >::Ptr & | cloud, | ||
| const std::vector< LineSegment::Ptr > & | segments | ||
| ) |  [protected, virtual] | 
Definition at line 203 of file line_segment_detector_nodelet.cpp.
| void jsk_pcl_ros::LineSegmentDetector::segment | ( | const sensor_msgs::PointCloud2::ConstPtr & | cloud_msg, | 
| const jsk_recognition_msgs::ClusterPointIndices::ConstPtr & | cluster_msg | ||
| ) |  [protected, virtual] | 
Definition at line 277 of file line_segment_detector_nodelet.cpp.
| void jsk_pcl_ros::LineSegmentDetector::segmentLines | ( | const pcl::PointCloud< PointT >::Ptr & | cloud, | 
| const pcl::PointIndices::Ptr & | indices, | ||
| std::vector< pcl::PointIndices::Ptr > & | line_indices, | ||
| std::vector< pcl::ModelCoefficients::Ptr > & | line_coefficients | ||
| ) |  [protected, virtual] | 
Definition at line 242 of file line_segment_detector_nodelet.cpp.
| void jsk_pcl_ros::LineSegmentDetector::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 179 of file line_segment_detector_nodelet.cpp.
| void jsk_pcl_ros::LineSegmentDetector::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 197 of file line_segment_detector_nodelet.cpp.
| bool jsk_pcl_ros::LineSegmentDetector::approximate_sync_  [protected] | 
Definition at line 145 of file line_segment_detector.h.
| boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > jsk_pcl_ros::LineSegmentDetector::async_  [protected] | 
Definition at line 135 of file line_segment_detector.h.
| boost::recursive_mutex jsk_pcl_ros::LineSegmentDetector::config_mutex_  [protected] | 
Definition at line 140 of file line_segment_detector.h.
| double jsk_pcl_ros::LineSegmentDetector::line_width_  [protected] | 
Definition at line 150 of file line_segment_detector.h.
| int jsk_pcl_ros::LineSegmentDetector::max_iterations_  [protected] | 
Definition at line 147 of file line_segment_detector.h.
| int jsk_pcl_ros::LineSegmentDetector::min_indices_  [protected] | 
Definition at line 148 of file line_segment_detector.h.
| double jsk_pcl_ros::LineSegmentDetector::min_length_  [protected] | 
Definition at line 149 of file line_segment_detector.h.
| boost::mutex jsk_pcl_ros::LineSegmentDetector::mutex_  [protected] | 
Definition at line 139 of file line_segment_detector.h.
| double jsk_pcl_ros::LineSegmentDetector::outlier_threshold_  [protected] | 
Definition at line 146 of file line_segment_detector.h.
Definition at line 133 of file line_segment_detector.h.
Definition at line 132 of file line_segment_detector.h.
Definition at line 131 of file line_segment_detector.h.
Definition at line 152 of file line_segment_detector.h.
| boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::LineSegmentDetector::srv_  [protected] | 
Definition at line 138 of file line_segment_detector.h.
| message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> jsk_pcl_ros::LineSegmentDetector::sub_indices_  [protected] | 
Definition at line 137 of file line_segment_detector.h.
| message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::LineSegmentDetector::sub_input_  [protected] | 
Definition at line 136 of file line_segment_detector.h.
| boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::LineSegmentDetector::sync_  [protected] | 
Definition at line 134 of file line_segment_detector.h.