Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef JSK_PCL_ROS_LINE_SEGMENT_DETECTOR_H_
00038 #define JSK_PCL_ROS_LINE_SEGMENT_DETECTOR_H_
00039
00040 #include <jsk_topic_tools/diagnostic_nodelet.h>
00041 #include <message_filters/subscriber.h>
00042 #include <message_filters/time_synchronizer.h>
00043 #include <message_filters/synchronizer.h>
00044
00045 #include <jsk_recognition_msgs/ClusterPointIndices.h>
00046 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
00047 #include <jsk_pcl_ros/LineSegmentDetectorConfig.h>
00048 #include <dynamic_reconfigure/server.h>
00049 #include <visualization_msgs/Marker.h>
00050 #include "jsk_pcl_ros/geo_util.h"
00051
00052 namespace jsk_pcl_ros
00053 {
00054
00055 class LineSegment
00056 {
00057 public:
00058 typedef boost::shared_ptr<LineSegment> Ptr;
00059 LineSegment(const std_msgs::Header& input_header,
00060 pcl::PointIndices::Ptr indices,
00061 pcl::ModelCoefficients::Ptr coefficients,
00062 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
00063 LineSegment(pcl::PointIndices::Ptr indices,
00064 pcl::ModelCoefficients::Ptr coefficients);
00065 virtual ~LineSegment();
00066 virtual void addMarkerLine(
00067 visualization_msgs::Marker& marker,
00068 const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud);
00069
00070 virtual Line::Ptr toSegment();
00071 pcl::PointIndices::Ptr getIndices() { return indices_; }
00072 pcl::ModelCoefficients::Ptr getCoefficients() { return coefficients_; }
00073 pcl::PointCloud<pcl::PointXYZ>::Ptr getPoints() { return points_; }
00074 pcl::PointCloud<pcl::PointXYZ>::Ptr getRawPoints() { return raw_points_; }
00075 std_msgs::Header header;
00076 protected:
00077 pcl::PointIndices::Ptr indices_;
00078 pcl::ModelCoefficients::Ptr coefficients_;
00079 pcl::PointCloud<pcl::PointXYZ>::Ptr points_;
00080 pcl::PointCloud<pcl::PointXYZ>::Ptr raw_points_;
00081 private:
00082
00083 };
00084
00085 class LineSegmentDetector: public jsk_topic_tools::DiagnosticNodelet
00086 {
00087 public:
00088 LineSegmentDetector(): DiagnosticNodelet("LineSegmentDetector")
00089 {
00090 }
00091 typedef message_filters::sync_policies::ExactTime<
00092 sensor_msgs::PointCloud2,
00093 jsk_recognition_msgs::ClusterPointIndices> SyncPolicy;
00094 typedef pcl::PointXYZ PointT;
00095 typedef jsk_pcl_ros::LineSegmentDetectorConfig Config;
00096 protected:
00098
00100 virtual void subscribe();
00101 virtual void unsubscribe();
00102 virtual void updateDiagnostic(
00103 diagnostic_updater::DiagnosticStatusWrapper &stat);
00104 virtual void onInit();
00105 virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00106 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_msg);
00107 virtual void configCallback(Config &config, uint32_t level);
00108 virtual void segmentLines(
00109 const pcl::PointCloud<PointT>::Ptr& cloud,
00110 const pcl::PointIndices::Ptr& indices,
00111 std::vector<pcl::PointIndices::Ptr>& line_indices,
00112 std::vector<pcl::ModelCoefficients::Ptr>& line_coefficients);
00113 virtual void publishResult(
00114 const std_msgs::Header& header,
00115 const pcl::PointCloud<PointT>::Ptr& cloud,
00116 const std::vector<LineSegment::Ptr>& segments);
00118
00120 ros::Publisher pub_line_marker_;
00121 ros::Publisher pub_indices_;
00122 ros::Publisher pub_coefficients_;
00123 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00124 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00125 message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_indices_;
00126 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00127 boost::mutex mutex_;
00128
00130
00132 double outlier_threshold_;
00133 int max_iterations_;
00134 int min_indices_;
00135 double min_length_;
00136 private:
00137
00138 };
00139 }
00140
00141 #endif