37 #ifndef JSK_PCL_ROS_LINE_SEGMENT_DETECTOR_H_
38 #define JSK_PCL_ROS_LINE_SEGMENT_DETECTOR_H_
40 #include <pcl/segmentation/sac_segmentation.h>
42 #include <jsk_topic_tools/diagnostic_nodelet.h>
49 #include <jsk_recognition_msgs/ClusterPointIndices.h>
50 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
51 #include <jsk_pcl_ros/LineSegmentDetectorConfig.h>
52 #include <dynamic_reconfigure/server.h>
53 #include <visualization_msgs/Marker.h>
64 pcl::PointIndices::Ptr indices,
65 pcl::ModelCoefficients::Ptr coefficients,
66 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
68 pcl::ModelCoefficients::Ptr coefficients);
71 visualization_msgs::Marker& marker,
72 const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
73 double minimum_line_length);
84 pcl::PointCloud<pcl::PointXYZ>::Ptr
points_;
90 class LineSegmentDetector:
public jsk_topic_tools::DiagnosticNodelet
109 sensor_msgs::PointCloud2,
110 jsk_recognition_msgs::ClusterPointIndices>
SyncPolicy;
112 sensor_msgs::PointCloud2,
114 typedef pcl::PointXYZ
PointT;
115 typedef jsk_pcl_ros::LineSegmentDetectorConfig
Config;
123 virtual void segment(
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
124 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_msg);
127 const pcl::PointCloud<PointT>::Ptr& cloud,
128 const pcl::PointIndices::Ptr& indices,
129 std::vector<pcl::PointIndices::Ptr>& line_indices,
130 std::vector<pcl::ModelCoefficients::Ptr>& line_coefficients);
132 const std_msgs::Header&
header,
133 const pcl::PointCloud<PointT>::Ptr& cloud,
134 const std::vector<LineSegment::Ptr>& segments);
159 pcl::SACSegmentation<PointT>
seg_;