multi_plane_extraction.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 #ifndef JSK_PCL_ROS_MULTI_PLANE_EXTRACTION_H_
00036 #define JSK_PCL_ROS_MULTI_PLANE_EXTRACTION_H_
00037 
00038 #include <ros/ros.h>
00039 #include <ros/names.h>
00040 #include <pcl_ros/pcl_nodelet.h>
00041 #include <message_filters/pass_through.h>
00042 #include <message_filters/time_synchronizer.h>
00043 #include <message_filters/synchronizer.h>
00044 #include <message_filters/sync_policies/approximate_time.h>
00045 
00046 #include "jsk_recognition_msgs/ClusterPointIndices.h"
00047 #include "sensor_msgs/PointCloud2.h"
00048 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
00049 #include "jsk_recognition_msgs/PolygonArray.h"
00050 #include <dynamic_reconfigure/server.h>
00051 #include "jsk_pcl_ros/MultiPlaneExtractionConfig.h"
00052 #include "jsk_recognition_utils/pcl_util.h"
00053 #include "jsk_recognition_utils/pcl_conversion_util.h"
00054 #include <jsk_topic_tools/vital_checker.h>
00055 #include <jsk_topic_tools/diagnostic_nodelet.h>
00056 #include "jsk_pcl_ros/tf_listener_singleton.h"
00057 
00058 namespace jsk_pcl_ros
00059 {
00060   class MultiPlaneExtraction: public jsk_topic_tools::DiagnosticNodelet
00061   {
00062   public:
00063     
00064     typedef message_filters::sync_policies::ExactTime<
00065     sensor_msgs::PointCloud2,
00066     jsk_recognition_msgs::ClusterPointIndices,
00067     jsk_recognition_msgs::ModelCoefficientsArray,
00068     jsk_recognition_msgs::PolygonArray> SyncPolicy;
00069     typedef message_filters::sync_policies::ApproximateTime<
00070       sensor_msgs::PointCloud2,
00071       jsk_recognition_msgs::ClusterPointIndices,
00072       jsk_recognition_msgs::ModelCoefficientsArray,
00073       jsk_recognition_msgs::PolygonArray> ASyncPolicy;
00074     typedef jsk_pcl_ros::MultiPlaneExtractionConfig Config;
00075 
00076     MultiPlaneExtraction(): DiagnosticNodelet("MultiPlaneExtraction") { }
00077   protected:
00079     // methods
00081     virtual void onInit();
00082     
00083     virtual void fillEmptyIndices(
00084       const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);
00085     virtual void fillEmptyCoefficients(
00086       const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);
00087 
00088     virtual void extract(const sensor_msgs::PointCloud2::ConstPtr& input,
00089                          const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
00090                          const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
00091                          const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);
00092     
00093     virtual void configCallback (Config &config, uint32_t level);
00094 
00095     virtual void updateDiagnostic(
00096       diagnostic_updater::DiagnosticStatusWrapper &stat);
00097 
00098     virtual void subscribe();
00099     virtual void unsubscribe();
00101     // ROS variables
00103     boost::mutex mutex_;
00104     ros::Publisher pub_, nonplane_pub_;
00105     ros::Publisher pub_indices_;
00106     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00107     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00108     message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> sub_coefficients_;
00109     message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> sub_polygons_;
00110     message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_indices_;
00111     message_filters::PassThrough<jsk_recognition_msgs::ClusterPointIndices> null_indices_;
00112     message_filters::PassThrough<jsk_recognition_msgs::ModelCoefficientsArray> null_coefficients_;
00113     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00114     boost::shared_ptr<message_filters::Synchronizer<ASyncPolicy> > async_;
00115 
00116 
00118     // Diagnostics Variables
00120     jsk_recognition_utils::Counter plane_counter_;
00121     
00123     // Parameters
00125     tf::TransformListener* tf_listener_;
00126     bool use_async_;
00127     bool keep_organized_;
00128     int maximum_queue_size_;
00129     double min_height_, max_height_;
00130     bool use_indices_;
00131     double maginify_;
00132     bool use_sensor_frame_;
00133     std::string sensor_frame_;
00134     bool use_coefficients_;
00135   private:
00136     
00137     
00138   };
00139 }
00140 
00141 #endif


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