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 #ifndef JSK_PCL_ROS_ORGANIZED_PLANE_SEGMENTATION_H_
00037 #define JSK_PCL_ROS_ORGANIZED_PLANE_SEGMENTATION_H_
00038
00039 #include <ros/ros.h>
00040 #include <ros/names.h>
00041
00042 #include "jsk_recognition_msgs/ClusterPointIndices.h"
00043 #include "sensor_msgs/PointCloud2.h"
00044 #include <pcl_ros/pcl_nodelet.h>
00045 #include <pcl/segmentation/organized_multi_plane_segmentation.h>
00046 #include <dynamic_reconfigure/server.h>
00047 #include "jsk_pcl_ros/OrganizedMultiPlaneSegmentationConfig.h"
00048 #include "jsk_recognition_msgs/PolygonArray.h"
00049 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
00050 #include <jsk_topic_tools/time_accumulator.h>
00051 #include <jsk_topic_tools/vital_checker.h>
00052 #include "jsk_recognition_utils/pcl_util.h"
00053 #include "jsk_recognition_utils/geo_util.h"
00054
00055 #include <diagnostic_updater/diagnostic_updater.h>
00056 #include <diagnostic_updater/publisher.h>
00057 #include <jsk_topic_tools/connection_based_nodelet.h>
00058 #include <jsk_topic_tools/diagnostic_utils.h>
00059
00060 namespace jsk_pcl_ros
00061 {
00062 class OrganizedMultiPlaneSegmentation:
00063 public jsk_topic_tools::ConnectionBasedNodelet
00064 {
00065 public:
00066 typedef pcl::PointXYZRGBA PointT;
00067 typedef std::vector<pcl::PlanarRegion<PointT>,
00068 Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > >
00069 PlanarRegionVector;
00070 typedef jsk_pcl_ros::OrganizedMultiPlaneSegmentationConfig Config;
00071 protected:
00073
00075 virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& msg);
00076 virtual void estimateNormal(pcl::PointCloud<PointT>::Ptr input,
00077 pcl::PointCloud<pcl::Normal>::Ptr output);
00078 virtual void configCallback (Config &config, uint32_t level);
00079 virtual void pointCloudToPolygon(const pcl::PointCloud<PointT>& input,
00080 geometry_msgs::Polygon& polygon);
00081 virtual void pclIndicesArrayToClusterPointIndices(const std::vector<pcl::PointIndices>& inlier_indices,
00082 const std_msgs::Header& header,
00083 jsk_recognition_msgs::ClusterPointIndices& output_indices);
00084 virtual void connectPlanesMap(const pcl::PointCloud<PointT>::Ptr& input,
00085 const std::vector<pcl::ModelCoefficients>& model_coefficients,
00086 const std::vector<pcl::PointIndices>& boundary_indices,
00087 jsk_recognition_utils::IntegerGraphMap& connection_map);
00088 virtual void buildConnectedPlanes(const pcl::PointCloud<PointT>::Ptr& input,
00089 const std_msgs::Header& header,
00090 const std::vector<pcl::PointIndices>& inlier_indices,
00091 const std::vector<pcl::PointIndices>& boundary_indices,
00092 const std::vector<pcl::ModelCoefficients>& model_coefficients,
00093 const jsk_recognition_utils::IntegerGraphMap& connection_map,
00094 std::vector<pcl::PointIndices>& output_indices,
00095 std::vector<pcl::ModelCoefficients>& output_coefficients,
00096 std::vector<pcl::PointCloud<PointT> >& output_boundary_clouds);
00097 virtual void forceToDirectOrigin(const std::vector<pcl::ModelCoefficients>& coefficients,
00098 std::vector<pcl::ModelCoefficients>& output_coefficients);
00099 virtual void publishMarkerOfConnection(
00100 jsk_recognition_utils::IntegerGraphMap connection_map,
00101 const pcl::PointCloud<PointT>::Ptr cloud,
00102 const std::vector<pcl::PointIndices>& inliers,
00103 const std_msgs::Header& header);
00104
00105 virtual void segmentOrganizedMultiPlanes(
00106 pcl::PointCloud<PointT>::Ptr input,
00107 pcl::PointCloud<pcl::Normal>::Ptr normal,
00108 PlanarRegionVector& regions,
00109 std::vector<pcl::ModelCoefficients>& model_coefficients,
00110 std::vector<pcl::PointIndices>& inlier_indices,
00111 pcl::PointCloud<pcl::Label>::Ptr& labels,
00112 std::vector<pcl::PointIndices>& label_indices,
00113 std::vector<pcl::PointIndices>& boundary_indices);
00114
00115 virtual void segmentFromNormals(pcl::PointCloud<PointT>::Ptr input,
00116 pcl::PointCloud<pcl::Normal>::Ptr normal,
00117 const std_msgs::Header& header);
00118
00119 virtual void publishSegmentationInformation(
00120 const std_msgs::Header& header,
00121 const pcl::PointCloud<PointT>::Ptr input,
00122 ros::Publisher& indices_pub,
00123 ros::Publisher& polygon_pub,
00124 ros::Publisher& coefficients_pub,
00125 const std::vector<pcl::PointIndices>& inlier_indices,
00126 const std::vector<pcl::PointCloud<PointT> >& boundaries,
00127 const std::vector<pcl::ModelCoefficients>& model_coefficients);
00128 virtual void publishSegmentationInformation(
00129 const std_msgs::Header& header,
00130 const pcl::PointCloud<PointT>::Ptr input,
00131 ros::Publisher& indices_pub,
00132 ros::Publisher& polygon_pub,
00133 ros::Publisher& coefficients_pub,
00134 const std::vector<pcl::PointIndices>& inlier_indices,
00135 const std::vector<pcl::PointIndices>& boundary_indices,
00136 const std::vector<pcl::ModelCoefficients>& model_coefficients);
00137
00138 virtual void refineBasedOnRANSAC(
00139 const pcl::PointCloud<PointT>::Ptr input,
00140 const std::vector<pcl::PointIndices>& input_indices,
00141 const std::vector<pcl::ModelCoefficients>& input_coefficients,
00142 std::vector<pcl::PointIndices>& output_indices,
00143 std::vector<pcl::ModelCoefficients>& output_coefficients,
00144 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_boundaries);
00145
00146
00147 virtual void updateDiagnostics(const ros::TimerEvent& event);
00148 virtual void updateDiagnosticNormalEstimation(
00149 diagnostic_updater::DiagnosticStatusWrapper &stat);
00150 virtual void updateDiagnosticPlaneSegmentation(
00151 diagnostic_updater::DiagnosticStatusWrapper &stat);
00152 virtual void subscribe();
00153 virtual void unsubscribe();
00155
00157 ros::Publisher org_pub_, org_polygon_pub_, org_coefficients_pub_;
00158 ros::Publisher pub_, polygon_pub_, coefficients_pub_;
00159 ros::Publisher refined_pub_, refined_polygon_pub_, refined_coefficients_pub_;
00160 ros::Publisher normal_pub_;
00161 ros::Publisher pub_connection_marker_;
00162 ros::Subscriber sub_;
00163 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00164 boost::mutex mutex_;
00165 boost::shared_ptr<diagnostic_updater::Updater> diagnostic_updater_;
00166 jsk_topic_tools::TimeAccumulator plane_segmentation_time_acc_;
00167 jsk_topic_tools::TimeAccumulator normal_estimation_time_acc_;
00168 jsk_topic_tools::TimeAccumulator ransac_refinement_time_acc_;
00169 jsk_topic_tools::VitalChecker::Ptr normal_estimation_vital_checker_;
00170 jsk_topic_tools::VitalChecker::Ptr plane_segmentation_vital_checker_;
00171 ros::Timer diagnostics_timer_;
00172
00173 int min_size_;
00174 double concave_alpha_;
00175 double angular_threshold_;
00176 double distance_threshold_;
00177 double max_curvature_;
00178 double connect_plane_angle_threshold_;
00179 double connect_distance_threshold_;
00180 double min_refined_area_threshold_;
00181 double max_refined_area_threshold_;
00182 int estimation_method_;
00183 bool depth_dependent_smoothing_;
00184 double max_depth_change_factor_;
00185 double normal_smoothing_size_;
00186 bool border_policy_ignore_;
00187 bool estimate_normal_;
00188 bool publish_normal_;
00189
00191
00193 bool ransac_refine_coefficients_;
00194 double ransac_refine_outlier_distance_threshold_;
00195
00196 jsk_recognition_utils::Counter original_plane_num_counter_;
00197 jsk_recognition_utils::Counter connected_plane_num_counter_;
00198
00199
00200 private:
00201 virtual void onInit();
00202 };
00203 }
00204
00205 #endif