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_pcl_ros/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
00052 namespace jsk_pcl_ros
00053 {
00054 class RegionGrowingMultiplePlaneSegmentation:
00055 public jsk_topic_tools::DiagnosticNodelet
00056 {
00057 public:
00058 typedef pcl::PointXYZRGB PointT;
00059 typedef RegionGrowingMultiplePlaneSegmentationConfig
00060 Config;
00061 typedef message_filters::sync_policies::ExactTime<
00062 sensor_msgs::PointCloud2,
00063 sensor_msgs::PointCloud2 > NormalSyncPolicy;
00064 RegionGrowingMultiplePlaneSegmentation()
00065 : DiagnosticNodelet("RegionGrowingMultiplePlaneSegmentation") {}
00066
00067 protected:
00069
00071 virtual void onInit();
00072 virtual void subscribe();
00073 virtual void unsubscribe();
00074 virtual void segment(
00075 const sensor_msgs::PointCloud2::ConstPtr& msg,
00076 const sensor_msgs::PointCloud2::ConstPtr& normal_msg);
00077 virtual void configCallback (Config &config, uint32_t level);
00079
00081
00082 static void setCondifionFunctionParameter(
00083 const double angular_threshold,
00084 const double distance_threshold)
00085 {
00086 global_angular_threshold = angular_threshold;
00087 global_distance_threshold = distance_threshold;
00088 }
00089 virtual void ransacEstimation(
00090 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &cloud,
00091 const pcl::PointIndices::Ptr& indices,
00092 pcl::PointIndices& inliers,
00093 pcl::ModelCoefficients& coefficient);
00094
00095 static bool regionGrowingFunction(const pcl::PointXYZRGBNormal& a,
00096 const pcl::PointXYZRGBNormal& b,
00097 float distance)
00098 {
00099 if (distance > global_distance_threshold) {
00100 return false;
00101 }
00102 else {
00103 Eigen::Vector3f a_normal(a.normal_x, a.normal_y, a.normal_z);
00104 Eigen::Vector3f b_normal(b.normal_x, b.normal_y, b.normal_z);
00105 double dot = std::abs(a_normal.dot(b_normal));
00106 double angle;
00107 if (dot > 1.0) {
00108 angle = acos(1.0);
00109 }
00110 else if (dot < -1.0) {
00111 angle = acos(-1.0);
00112 }
00113 else {
00114 angle = acos(dot);
00115 }
00116
00117 if (angle > global_angular_threshold) {
00118 return false;
00119 }
00120 else {
00121 return true;
00122 }
00123 }
00124 }
00125
00127
00129 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00130 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_normal_;
00131 boost::shared_ptr<
00132 message_filters::Synchronizer<NormalSyncPolicy> > sync_;
00133 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00134 ros::Publisher pub_polygons_;
00135 ros::Publisher pub_inliers_;
00136 ros::Publisher pub_coefficients_;
00137 ros::Publisher pub_clustering_result_;
00138 boost::mutex mutex_;
00139
00141
00143 double angular_threshold_;
00144 double distance_threshold_;
00145 double max_curvature_;
00146 int min_size_;
00147 int max_size_;
00148 double cluster_tolerance_;
00149 double ransac_refine_outlier_distance_threshold_;
00150 int ransac_refine_max_iterations_;
00152
00154 static double global_angular_threshold;
00155 static double global_distance_threshold;
00156 static boost::mutex global_custom_condigion_function_mutex;
00157 private:
00158
00159 };
00160 }
00161
00162 #endif