organized_multi_plane_segmentation.h
Go to the documentation of this file.
00001 // -*- mode: C++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2013, Ryohei Ueda and JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
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_pcl_ros/pcl_util.h"
00053 #include "jsk_pcl_ros/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 
00059 namespace jsk_pcl_ros
00060 {
00061   class OrganizedMultiPlaneSegmentation:
00062     public jsk_topic_tools::ConnectionBasedNodelet
00063   {
00064   public:
00065     typedef pcl::PointXYZRGBA PointT;
00066     typedef std::vector<pcl::PlanarRegion<PointT>,
00067                         Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > >
00068     PlanarRegionVector;
00069     typedef jsk_pcl_ros::OrganizedMultiPlaneSegmentationConfig Config;
00070   protected:
00072     // methods
00074     virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& msg);
00075     virtual void estimateNormal(pcl::PointCloud<PointT>::Ptr input,
00076                                 pcl::PointCloud<pcl::Normal>::Ptr output);
00077     virtual void configCallback (Config &config, uint32_t level);
00078     virtual void pointCloudToPolygon(const pcl::PointCloud<PointT>& input,
00079                                      geometry_msgs::Polygon& polygon);
00080     virtual void pclIndicesArrayToClusterPointIndices(const std::vector<pcl::PointIndices>& inlier_indices,
00081                                                       const std_msgs::Header& header,
00082                                                       jsk_recognition_msgs::ClusterPointIndices& output_indices);
00083     virtual void connectPlanesMap(const pcl::PointCloud<PointT>::Ptr& input,
00084                                   const std::vector<pcl::ModelCoefficients>& model_coefficients,
00085                                   const std::vector<pcl::PointIndices>& boundary_indices,
00086                                   IntegerGraphMap& connection_map);
00087     virtual void buildConnectedPlanes(const pcl::PointCloud<PointT>::Ptr& input,
00088                                       const std_msgs::Header& header,
00089                                       const std::vector<pcl::PointIndices>& inlier_indices,
00090                                       const std::vector<pcl::PointIndices>& boundary_indices,
00091                                       const std::vector<pcl::ModelCoefficients>& model_coefficients,
00092                                       const IntegerGraphMap& connection_map,
00093                                       std::vector<pcl::PointIndices>& output_indices,
00094                                       std::vector<pcl::ModelCoefficients>& output_coefficients,
00095                                       std::vector<pcl::PointCloud<PointT> >& output_boundary_clouds);
00096     virtual void forceToDirectOrigin(const std::vector<pcl::ModelCoefficients>& coefficients,
00097                                      std::vector<pcl::ModelCoefficients>& output_coefficients);
00098     virtual void publishMarkerOfConnection(
00099       IntegerGraphMap connection_map,
00100       const pcl::PointCloud<PointT>::Ptr cloud,
00101       const std::vector<pcl::PointIndices>& inliers,
00102       const std_msgs::Header& header);
00103 
00104     virtual void segmentOrganizedMultiPlanes(
00105       pcl::PointCloud<PointT>::Ptr input,
00106       pcl::PointCloud<pcl::Normal>::Ptr normal,
00107       PlanarRegionVector& regions,
00108       std::vector<pcl::ModelCoefficients>& model_coefficients,
00109       std::vector<pcl::PointIndices>& inlier_indices,
00110       pcl::PointCloud<pcl::Label>::Ptr& labels,
00111       std::vector<pcl::PointIndices>& label_indices,
00112       std::vector<pcl::PointIndices>& boundary_indices);
00113     
00114     virtual void segmentFromNormals(pcl::PointCloud<PointT>::Ptr input,
00115                                     pcl::PointCloud<pcl::Normal>::Ptr normal,
00116                                     const std_msgs::Header& header);
00117     
00118     virtual void publishSegmentationInformation(
00119       const std_msgs::Header& header,
00120       const pcl::PointCloud<PointT>::Ptr input,
00121       ros::Publisher& indices_pub,
00122       ros::Publisher& polygon_pub,
00123       ros::Publisher& coefficients_pub,
00124       const std::vector<pcl::PointIndices>& inlier_indices,
00125       const std::vector<pcl::PointCloud<PointT> >& boundaries,
00126       const std::vector<pcl::ModelCoefficients>& model_coefficients);
00127     virtual void publishSegmentationInformation(
00128       const std_msgs::Header& header,
00129       const pcl::PointCloud<PointT>::Ptr input,
00130       ros::Publisher& indices_pub,
00131       ros::Publisher& polygon_pub,
00132       ros::Publisher& coefficients_pub,
00133       const std::vector<pcl::PointIndices>& inlier_indices,
00134       const std::vector<pcl::PointIndices>& boundary_indices,
00135       const std::vector<pcl::ModelCoefficients>& model_coefficients);
00136     
00137     virtual void refineBasedOnRANSAC(
00138       const pcl::PointCloud<PointT>::Ptr input,
00139       const std::vector<pcl::PointIndices>& input_indices,
00140       const std::vector<pcl::ModelCoefficients>& input_coefficients,
00141       std::vector<pcl::PointIndices>& output_indices,
00142       std::vector<pcl::ModelCoefficients>& output_coefficients,
00143       std::vector<ConvexPolygon::Ptr>& output_boundaries);
00144 
00145     
00146     virtual void updateDiagnostics(const ros::TimerEvent& event);
00147     virtual void updateDiagnosticNormalEstimation(
00148       diagnostic_updater::DiagnosticStatusWrapper &stat);
00149     virtual void updateDiagnosticPlaneSegmentation(
00150       diagnostic_updater::DiagnosticStatusWrapper &stat);
00151     virtual void subscribe();
00152     virtual void unsubscribe();
00154     // ROS variables
00156     ros::Publisher org_pub_, org_polygon_pub_, org_coefficients_pub_;
00157     ros::Publisher pub_, polygon_pub_, coefficients_pub_;
00158     ros::Publisher refined_pub_, refined_polygon_pub_, refined_coefficients_pub_;
00159     ros::Publisher normal_pub_;
00160     ros::Publisher pub_connection_marker_;
00161     ros::Subscriber sub_;
00162     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00163     boost::mutex mutex_;
00164     boost::shared_ptr<diagnostic_updater::Updater> diagnostic_updater_;
00165     jsk_topic_tools::TimeAccumulator plane_segmentation_time_acc_;
00166     jsk_topic_tools::TimeAccumulator normal_estimation_time_acc_;
00167     jsk_topic_tools::TimeAccumulator ransac_refinement_time_acc_;
00168     jsk_topic_tools::VitalChecker::Ptr normal_estimation_vital_checker_;
00169     jsk_topic_tools::VitalChecker::Ptr plane_segmentation_vital_checker_;
00170     ros::Timer diagnostics_timer_;
00171     
00172     int min_size_;
00173     double concave_alpha_;
00174     double angular_threshold_;
00175     double distance_threshold_;
00176     double max_curvature_;
00177     double connect_plane_angle_threshold_;
00178     double connect_distance_threshold_;
00179     double min_refined_area_threshold_;
00180     double max_refined_area_threshold_;
00181     int estimation_method_;
00182     bool depth_dependent_smoothing_;
00183     double max_depth_change_factor_;
00184     double normal_smoothing_size_;
00185     bool border_policy_ignore_;
00186     bool estimate_normal_;
00187     bool publish_normal_;
00188 
00190     // parameters for RANSAC refinement
00192     bool ransac_refine_coefficients_;
00193     double ransac_refine_outlier_distance_threshold_;
00194     
00195     Counter original_plane_num_counter_;
00196     Counter connected_plane_num_counter_;
00197 
00198     
00199   private:
00200     virtual void onInit();
00201   };
00202 }
00203 
00204 #endif


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:48