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 <pcl/segmentation/sac_segmentation.h>
00041
00042 #include <jsk_topic_tools/diagnostic_nodelet.h>
00043 #include <message_filters/subscriber.h>
00044 #include <message_filters/time_synchronizer.h>
00045 #include <message_filters/synchronizer.h>
00046 #include <message_filters/sync_policies/exact_time.h>
00047 #include <message_filters/sync_policies/approximate_time.h>
00048
00049 #include <jsk_recognition_msgs/ClusterPointIndices.h>
00050 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
00051 #include <jsk_pcl_ros/LineSegmentDetectorConfig.h>
00052 #include <dynamic_reconfigure/server.h>
00053 #include <visualization_msgs/Marker.h>
00054 #include "jsk_recognition_utils/geo_util.h"
00055
00056 namespace jsk_pcl_ros
00057 {
00058
00059 class LineSegment
00060 {
00061 public:
00062 typedef boost::shared_ptr<LineSegment> Ptr;
00063 LineSegment(const std_msgs::Header& input_header,
00064 pcl::PointIndices::Ptr indices,
00065 pcl::ModelCoefficients::Ptr coefficients,
00066 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
00067 LineSegment(pcl::PointIndices::Ptr indices,
00068 pcl::ModelCoefficients::Ptr coefficients);
00069 virtual ~LineSegment();
00070 virtual bool addMarkerLine(
00071 visualization_msgs::Marker& marker,
00072 const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
00073 double minimum_line_length);
00074
00075 virtual jsk_recognition_utils::Line::Ptr toSegment();
00076 pcl::PointIndices::Ptr getIndices() { return indices_; }
00077 pcl::ModelCoefficients::Ptr getCoefficients() { return coefficients_; }
00078 pcl::PointCloud<pcl::PointXYZ>::Ptr getPoints() { return points_; }
00079 pcl::PointCloud<pcl::PointXYZ>::Ptr getRawPoints() { return raw_points_; }
00080 std_msgs::Header header;
00081 protected:
00082 pcl::PointIndices::Ptr indices_;
00083 pcl::ModelCoefficients::Ptr coefficients_;
00084 pcl::PointCloud<pcl::PointXYZ>::Ptr points_;
00085 pcl::PointCloud<pcl::PointXYZ>::Ptr raw_points_;
00086 private:
00087
00088 };
00089
00090 class LineSegmentDetector: public jsk_topic_tools::DiagnosticNodelet
00091 {
00092 public:
00093 LineSegmentDetector(): DiagnosticNodelet("LineSegmentDetector")
00094 {
00095 }
00096 ~LineSegmentDetector()
00097 {
00098 sync_.reset();
00099 srv_.reset();
00100 }
00101 typedef message_filters::sync_policies::ExactTime<
00102 sensor_msgs::PointCloud2,
00103 jsk_recognition_msgs::ClusterPointIndices> SyncPolicy;
00104 typedef message_filters::sync_policies::ApproximateTime<
00105 sensor_msgs::PointCloud2,
00106 jsk_recognition_msgs::ClusterPointIndices> ApproximateSyncPolicy;
00107 typedef pcl::PointXYZ PointT;
00108 typedef jsk_pcl_ros::LineSegmentDetectorConfig Config;
00109 protected:
00111
00113 virtual void subscribe();
00114 virtual void unsubscribe();
00115 virtual void onInit();
00116 virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00117 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_msg);
00118 virtual void configCallback(Config &config, uint32_t level);
00119 virtual void segmentLines(
00120 const pcl::PointCloud<PointT>::Ptr& cloud,
00121 const pcl::PointIndices::Ptr& indices,
00122 std::vector<pcl::PointIndices::Ptr>& line_indices,
00123 std::vector<pcl::ModelCoefficients::Ptr>& line_coefficients);
00124 virtual void publishResult(
00125 const std_msgs::Header& header,
00126 const pcl::PointCloud<PointT>::Ptr& cloud,
00127 const std::vector<LineSegment::Ptr>& segments);
00129
00131 ros::Publisher pub_line_marker_;
00132 ros::Publisher pub_indices_;
00133 ros::Publisher pub_coefficients_;
00134 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00135 boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > async_;
00136 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00137 message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_indices_;
00138 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00139 boost::mutex mutex_;
00140 boost::recursive_mutex config_mutex_;
00141
00143
00145 bool approximate_sync_;
00146 double outlier_threshold_;
00147 int max_iterations_;
00148 int min_indices_;
00149 double min_length_;
00150 double line_width_;
00151
00152 pcl::SACSegmentation<PointT> seg_;
00153
00154 private:
00155
00156 };
00157 }
00158
00159 #endif