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
00037
00038
00039
00040
00042 #ifndef JSK_PCL_ROS_LINE_SEGMENT_COLLECTOR_H_
00043 #define JSK_PCL_ROS_LINE_SEGMENT_COLLECTOR_H_
00044
00045 #include <jsk_topic_tools/diagnostic_nodelet.h>
00046 #include <jsk_recognition_msgs/ClusterPointIndices.h>
00047 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
00048 #include <sensor_msgs/JointState.h>
00049 #include "jsk_pcl_ros/line_segment_detector.h"
00050 #include <jsk_topic_tools/time_accumulator.h>
00051 #include <jsk_pcl_ros/LineSegmentCollectorConfig.h>
00052 #include <dynamic_reconfigure/server.h>
00053 #include "jsk_recognition_utils/geo_util.h"
00054 #include <jsk_recognition_msgs/PolygonArray.h>
00055 #include <jsk_recognition_msgs/TimeRange.h>
00056
00057 namespace jsk_pcl_ros
00058 {
00059
00060 class LineSegmentCluster
00061 {
00062 public:
00063 typedef boost::shared_ptr<LineSegmentCluster> Ptr;
00064 LineSegmentCluster();
00065 virtual ~LineSegmentCluster() { };
00066
00068
00070 virtual void addLineSegmentEWMA(LineSegment::Ptr segment, const double tau);
00071 virtual Eigen::Vector3f getDelta() { return delta_; }
00072 virtual pcl::PointCloud<pcl::PointXYZ>::Ptr getPoints();
00073 virtual pcl::PointCloud<pcl::PointXYZ>::Ptr getRawPoints();
00074 virtual void removeBefore(const ros::Time& stamp);
00075 virtual bool isEmpty();
00076 protected:
00077 Eigen::Vector3f delta_;
00078 std::vector<LineSegment::Ptr> segments_;
00079 pcl::PointCloud<pcl::PointXYZ>::Ptr points_;
00080 pcl::PointCloud<pcl::PointXYZ>::Ptr raw_points_;
00081 private:
00082
00083 };
00084
00085 template <class T>
00086 class TimeStampedVector: public std::vector<T>
00087 {
00088 public:
00089 typedef typename std::vector<T>::iterator iterator;
00090 void removeBefore(const ros::Time& stamp)
00091 {
00092 for (iterator it = std::vector<T>::begin();
00093 it != std::vector<T>::end();) {
00094 if (((*it)->header.stamp - stamp) < ros::Duration(0.0)) {
00095 it = this->erase(it);
00096 }
00097 else {
00098 ++it;
00099 }
00100 }
00101 }
00102 protected:
00103 private:
00104 };
00105
00106 class LineSegmentCollector: public jsk_topic_tools::DiagnosticNodelet
00107 {
00108 public:
00109 LineSegmentCollector(): DiagnosticNodelet("LineSegmentCollector") { }
00110 typedef message_filters::sync_policies::ExactTime<
00111 sensor_msgs::PointCloud2,
00112 jsk_recognition_msgs::ClusterPointIndices,
00113 jsk_recognition_msgs::ModelCoefficientsArray> SyncPolicy;
00114 enum RotateType {
00115 ROTATION_SPINDLE, ROTATION_TILT, ROTATION_TILT_TWO_WAY
00116 };
00117 typedef jsk_pcl_ros::LineSegmentCollectorConfig Config;
00118 protected:
00120
00122 virtual void onInit();
00123 virtual void collectFromBuffers(const std_msgs::Header& header,
00124 std::vector<LineSegment::Ptr> new_segments);
00125 virtual void collect(
00126 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00127 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
00128 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg);
00129 virtual void subscribe();
00130 virtual void unsubscribe();
00131 virtual void triggerCallback(
00132 const jsk_recognition_msgs::TimeRange::ConstPtr& trigger);
00133 virtual void cleanupBuffers(
00134 const ros::Time& stamp);
00135 virtual void publishBeforePlaneSegmentation(
00136 const std_msgs::Header& header,
00137 const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
00138 const std::vector<pcl::PointIndices::Ptr>& connected_indices);
00139 virtual LineSegmentCluster::Ptr lookupNearestSegment(
00140 LineSegment::Ptr segment);
00141 virtual void publishResult(
00142 const std_msgs::Header& header,
00143 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
00144 std::vector<pcl::ModelCoefficients::Ptr> all_coefficients,
00145 std::vector<pcl::PointIndices::Ptr> all_indices);
00146 virtual void configCallback(Config &config, uint32_t level);
00148
00150 boost::mutex mutex_;
00151 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00152 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00153 message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_indices_;
00154 message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> sub_coefficients_;
00155 ros::Publisher pub_point_cloud_;
00156 ros::Publisher pub_inliers_;
00157 ros::Publisher pub_coefficients_;
00158 ros::Publisher pub_polygons_;
00159 ros::Publisher debug_pub_inliers_before_plane_;
00160 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00161 jsk_topic_tools::TimeAccumulator connect_ac_;
00162 ros::Subscriber sub_trigger_;
00163
00165
00167 std::string fixed_frame_id_;
00168 RotateType rotate_type_;
00169 TimeStampedVector<sensor_msgs::PointCloud2::ConstPtr> pointclouds_buffer_;
00170 TimeStampedVector<jsk_recognition_msgs::ClusterPointIndices::ConstPtr> indices_buffer_;
00171 TimeStampedVector<jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr> coefficients_buffer_;
00172 TimeStampedVector<LineSegment::Ptr> segments_buffer_;
00173 std::vector<LineSegmentCluster::Ptr> segment_clusters_;
00174 double segment_connect_normal_threshold_;
00175 double ewma_tau_;
00176 jsk_recognition_msgs::TimeRange::ConstPtr time_range_;
00178
00180 double outlier_threshold_;
00181
00182 private:
00183
00184 };
00185 }
00186
00187 #endif