hinted_plane_detector.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_HINTED_PLANE_DETECTOR_H_
00037 #define JSK_PCL_ROS_HINTED_PLANE_DETECTOR_H_
00038 
00039 #include <ros/ros.h>
00040 #include <pcl/point_types.h>
00041 #include <pcl_ros/pcl_nodelet.h>
00042 
00043 #include <jsk_topic_tools/diagnostic_nodelet.h>
00044 #include <message_filters/subscriber.h>
00045 #include <message_filters/time_synchronizer.h>
00046 #include <message_filters/synchronizer.h>
00047 #include "jsk_pcl_ros/pcl_conversion_util.h"
00048 #include "jsk_pcl_ros/geo_util.h"
00049 #include <geometry_msgs/PolygonStamped.h>
00050 #include <jsk_recognition_msgs/PolygonArray.h>
00051 #include <dynamic_reconfigure/server.h>
00052 #include <jsk_pcl_ros/HintedPlaneDetectorConfig.h>
00053 
00054 namespace jsk_pcl_ros {
00055   
00056   class HintedPlaneDetector: public jsk_topic_tools::DiagnosticNodelet
00057   {
00058   public:
00059     typedef HintedPlaneDetectorConfig Config;
00060     typedef message_filters::sync_policies::ExactTime<
00061     sensor_msgs::PointCloud2,
00062     sensor_msgs::PointCloud2> SyncPolicy;
00063     HintedPlaneDetector(): DiagnosticNodelet("HintedPlaneDetector") {}
00064     
00065   protected:
00066     virtual void onInit();
00067     virtual void subscribe();
00068     virtual void unsubscribe();
00069     virtual void detect(
00070       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00071       const sensor_msgs::PointCloud2::ConstPtr& hint_cloud_msg);
00072     virtual bool detectHintPlane(
00073       pcl::PointCloud<pcl::PointXYZ>::Ptr hint_cloud,
00074       ConvexPolygon::Ptr& convex);
00075     virtual bool detectLargerPlane(
00076       pcl::PointCloud<pcl::PointNormal>::Ptr input_cloud,
00077       ConvexPolygon::Ptr hint_convex);
00078     virtual pcl::PointIndices::Ptr getBestCluster(
00079       pcl::PointCloud<pcl::PointNormal>::Ptr input_cloud,
00080       const std::vector<pcl::PointIndices>& cluster_indices,
00081       const ConvexPolygon::Ptr hint_convex);
00082     virtual void publishPolygon(
00083       const ConvexPolygon::Ptr convex,
00084       ros::Publisher& pub_polygon, ros::Publisher& pub_polygon_array,
00085       const pcl::PCLHeader& header);
00086     virtual void configCallback(Config &config, uint32_t level);
00087     virtual void densityFilter(
00088       const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00089       const pcl::PointIndices::Ptr indices,
00090       pcl::PointIndices& output);
00091     virtual void euclideanFilter(
00092       const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00093       const pcl::PointIndices::Ptr indices,
00094       const ConvexPolygon::Ptr hint_convex,
00095       pcl::PointIndices& output);
00096     virtual void planeFilter(
00097       const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00098       const pcl::PointIndices::Ptr indices,
00099       const Eigen::Vector3f& normal,
00100       pcl::PointIndices& output,
00101       pcl::ModelCoefficients& coefficients);
00102     virtual void hintFilter(
00103       const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00104       const ConvexPolygon::Ptr hint_convex,
00105       pcl::PointIndices& output);
00106 
00108     // ROS variables
00110     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00111     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_cloud_;
00112     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_hint_cloud_;
00113     ros::Publisher pub_hint_polygon_;
00114     ros::Publisher pub_hint_polygon_array_;
00115     ros::Publisher pub_hint_inliers_;
00116     ros::Publisher pub_hint_coefficients_;
00117     ros::Publisher pub_polygon_array_;
00118     ros::Publisher pub_polygon_;
00119     ros::Publisher pub_inliers_;
00120     ros::Publisher pub_coefficients_;
00121     ros::Publisher pub_hint_filtered_indices_;
00122     ros::Publisher pub_plane_filtered_indices_;
00123     ros::Publisher pub_density_filtered_indices_;
00124     ros::Publisher pub_euclidean_filtered_indices_;
00125     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00126     boost::mutex mutex_;
00127 
00129     // parameters
00131     double hint_outlier_threashold_;
00132     int hint_max_iteration_;
00133     int hint_min_size_;
00134     int max_iteration_;
00135     int min_size_;
00136     double outlier_threashold_;
00137     double eps_angle_;
00138     double normal_filter_eps_angle_;
00139     double euclidean_clustering_filter_tolerance_;
00140     int euclidean_clustering_filter_min_size_;
00141     bool enable_euclidean_filtering_;
00142     bool enable_normal_filtering_;
00143     bool enable_distance_filtering_;
00144     bool enable_density_filtering_;
00145     double density_radius_;
00146     int density_num_;
00147   };
00148 }
00149 
00150 #endif


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