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


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