primitive_shape_classifier.h
Go to the documentation of this file.
00001 // -*- mode: C++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2017, 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  * primitive_shape_classifier.h
00037  * Author: Yuki Furuta <furushchev@jsk.imi.i.u-tokyo.ac.jp>
00038  */
00039 
00040 #ifndef JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__
00041 #define JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__
00042 
00043 #include <boost/shared_ptr.hpp>
00044 #include <dynamic_reconfigure/server.h>
00045 #include <jsk_topic_tools/diagnostic_nodelet.h>
00046 #include <message_filters/time_synchronizer.h>
00047 #include <message_filters/synchronizer.h>
00048 #include <message_filters/subscriber.h>
00049 #include <sensor_msgs/PointCloud2.h>
00050 #include <jsk_recognition_msgs/ClusterPointIndices.h>
00051 #include <jsk_recognition_msgs/ClassificationResult.h>
00052 #include <jsk_recognition_msgs/PolygonArray.h>
00053 #include <jsk_recognition_utils/geo_util.h>
00054 #include <jsk_recognition_utils/pcl_ros_util.h>
00055 #include <jsk_pcl_ros/PrimitiveShapeClassifierConfig.h>
00056 #include <pcl/point_types.h>
00057 #include <pcl/point_cloud.h>
00058 #include <pcl/ModelCoefficients.h>
00059 
00060 namespace jsk_pcl_ros
00061 {
00062   class PrimitiveShapeClassifier : public jsk_topic_tools::DiagnosticNodelet
00063   {
00064   public:
00065     typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2,
00066                                                       sensor_msgs::PointCloud2,
00067                                                       jsk_recognition_msgs::ClusterPointIndices,
00068                                                       jsk_recognition_msgs::PolygonArray> SyncPolicy;
00069     typedef PrimitiveShapeClassifierConfig Config;
00070     typedef pcl::PointXYZRGBA PointT;
00071 
00072     PrimitiveShapeClassifier() : DiagnosticNodelet("PrimitiveShapeClassifier") {}
00073   protected:
00074     virtual void onInit();
00075     virtual void subscribe();
00076     virtual void unsubscribe();
00077     virtual void configCallback(Config& config, uint32_t level);
00078 
00079     virtual void
00080     process(const sensor_msgs::PointCloud2::ConstPtr& ros_cloud,
00081             const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
00082             const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
00083             const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons);
00084 
00085     virtual bool
00086     estimate(const pcl::PointCloud<PointT>::Ptr& cloud,
00087              const pcl::PointCloud<pcl::Normal>::Ptr& normal,
00088              const pcl::ModelCoefficients::Ptr& plane,
00089              pcl::PointIndices::Ptr& boundary_indices,
00090              pcl::PointCloud<PointT>::Ptr& projected_cloud,
00091              float& circle_likelihood,
00092              float& box_likelihood);
00093 
00094     virtual bool
00095     getSupportPlane(const pcl::PointCloud<PointT>::Ptr& cloud,
00096                     const std::vector<jsk_recognition_utils::Polygon::Ptr>& polygons,
00097                     pcl::ModelCoefficients::Ptr& coeff);
00098 
00099     virtual bool
00100     checkFrameId(const sensor_msgs::PointCloud2::ConstPtr& ros_cloud,
00101                  const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
00102                  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
00103                  const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons);
00104 
00105     // properties
00106     boost::mutex mutex_;
00107     boost::shared_ptr<dynamic_reconfigure::Server<Config> > srv_;
00108     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_cloud_;
00109     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_normal_;
00110     message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_indices_;
00111     message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> sub_polygons_;
00112     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00113     ros::Publisher pub_class_;
00114     ros::Publisher pub_boundary_indices_;
00115     ros::Publisher pub_projected_cloud_;
00116 
00117     // parameters
00118     int queue_size_;
00119     int min_points_num_;
00120     int sac_max_iterations_;
00121     double sac_distance_threshold_;
00122     double sac_radius_limit_min_, sac_radius_limit_max_;
00123     double box_threshold_, circle_threshold_;
00124   };
00125 }
00126 
00127 #endif // JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:50