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_REGION_GROWING_MULTIPLE_PLANE_SEGMENTATION_H_
00038 #define JSK_PCL_ROS_REGION_GROWING_MULTIPLE_PLANE_SEGMENTATION_H_
00039
00040 #include <dynamic_reconfigure/server.h>
00041 #include "jsk_pcl_ros/RegionGrowingMultiplePlaneSegmentationConfig.h"
00042 #include <message_filters/subscriber.h>
00043 #include <message_filters/time_synchronizer.h>
00044 #include <message_filters/sync_policies/approximate_time.h>
00045 #include <message_filters/synchronizer.h>
00046 #include <jsk_topic_tools/diagnostic_nodelet.h>
00047 #include "jsk_recognition_utils/geo_util.h"
00048 #include "jsk_recognition_msgs/PolygonArray.h"
00049 #include "jsk_recognition_msgs/ClusterPointIndices.h"
00050 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
00051 #include <jsk_recognition_utils/time_util.h>
00052 #include <std_msgs/Float32.h>
00053
00054 namespace jsk_pcl_ros
00055 {
00056 class RegionGrowingMultiplePlaneSegmentation:
00057 public jsk_topic_tools::DiagnosticNodelet
00058 {
00059 public:
00060 typedef pcl::PointXYZRGB PointT;
00061 typedef RegionGrowingMultiplePlaneSegmentationConfig
00062 Config;
00063 typedef message_filters::sync_policies::ExactTime<
00064 sensor_msgs::PointCloud2,
00065 sensor_msgs::PointCloud2 > NormalSyncPolicy;
00066 RegionGrowingMultiplePlaneSegmentation()
00067 : DiagnosticNodelet("RegionGrowingMultiplePlaneSegmentation"),
00068 timer_(10),
00069 done_initialization_(false) {}
00070
00071 protected:
00073
00075 virtual void onInit();
00076 virtual void subscribe();
00077 virtual void unsubscribe();
00078 virtual void segment(
00079 const sensor_msgs::PointCloud2::ConstPtr& msg,
00080 const sensor_msgs::PointCloud2::ConstPtr& normal_msg);
00081 virtual void configCallback (Config &config, uint32_t level);
00083
00085
00086 static void setCondifionFunctionParameter(
00087 const double angular_threshold,
00088 const double distance_threshold)
00089 {
00090 global_angular_threshold = angular_threshold;
00091 global_distance_threshold = distance_threshold;
00092 }
00093 virtual void ransacEstimation(
00094 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &cloud,
00095 const pcl::PointIndices::Ptr& indices,
00096 pcl::PointIndices& inliers,
00097 pcl::ModelCoefficients& coefficient);
00098
00099 static bool regionGrowingFunction(const pcl::PointXYZRGBNormal& a,
00100 const pcl::PointXYZRGBNormal& b,
00101 float distance)
00102 {
00103 if (distance > global_distance_threshold) {
00104 return false;
00105 }
00106 else {
00107 Eigen::Vector3f a_normal(a.normal_x, a.normal_y, a.normal_z);
00108 Eigen::Vector3f b_normal(b.normal_x, b.normal_y, b.normal_z);
00109 double dot = std::abs(a_normal.dot(b_normal));
00110 double angle;
00111 if (dot > 1.0) {
00112 angle = acos(1.0);
00113 }
00114 else if (dot < -1.0) {
00115 angle = acos(-1.0);
00116 }
00117 else {
00118 angle = acos(dot);
00119 }
00120
00121 if (angle > global_angular_threshold) {
00122 return false;
00123 }
00124 else {
00125 return true;
00126 }
00127 }
00128 }
00129
00131
00133 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00134 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_normal_;
00135 boost::shared_ptr<
00136 message_filters::Synchronizer<NormalSyncPolicy> > sync_;
00137 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00138 ros::Publisher pub_polygons_;
00139 ros::Publisher pub_inliers_;
00140 ros::Publisher pub_coefficients_;
00141 ros::Publisher pub_clustering_result_;
00142 ros::Publisher pub_latest_time_;
00143 ros::Publisher pub_average_time_;
00144 boost::mutex mutex_;
00145 jsk_recognition_utils::WallDurationTimer timer_;
00147
00149 double angular_threshold_;
00150 double distance_threshold_;
00151 double max_curvature_;
00152 int min_size_;
00153 int max_size_;
00154 double min_area_;
00155 double max_area_;
00156 double cluster_tolerance_;
00157 double ransac_refine_outlier_distance_threshold_;
00158 int ransac_refine_max_iterations_;
00159 bool done_initialization_;
00161
00163 static double global_angular_threshold;
00164 static double global_distance_threshold;
00165 static boost::mutex global_custom_condigion_function_mutex;
00166 private:
00167
00168 };
00169 }
00170
00171 #endif