edge_depth_refinement.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, 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 
00037 #ifndef JSK_PCL_ROS_EDGE_DEPTH_REFINEMENT_H_
00038 #define JSK_PCL_ROS_EDGE_DEPTH_REFINEMENT_H_
00039 
00040 #include <pcl_ros/pcl_nodelet.h>
00041 #include <sensor_msgs/PointCloud2.h>
00042 #include <jsk_recognition_msgs/ClusterPointIndices.h>
00043 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
00044 
00045 #include <message_filters/subscriber.h>
00046 #include <message_filters/time_synchronizer.h>
00047 #include <message_filters/synchronizer.h>
00048 
00049 #include "jsk_pcl_ros/pcl_conversion_util.h"
00050 #include "jsk_pcl_ros/geo_util.h"
00051 #include <jsk_pcl_ros/EdgeDepthRefinementConfig.h>
00052 #include <dynamic_reconfigure/server.h>
00053 #include <boost/tuple/tuple.hpp>
00054 
00055 #include <jsk_topic_tools/connection_based_nodelet.h>
00056 
00057 namespace jsk_pcl_ros
00058 {
00059   class EdgeDepthRefinement: public jsk_topic_tools::ConnectionBasedNodelet
00060   {
00061   public:
00062     typedef message_filters::sync_policies::ExactTime<
00063     sensor_msgs::PointCloud2,
00064     jsk_recognition_msgs::ClusterPointIndices > SyncPolicy;
00065     typedef pcl::PointXYZRGB PointT;
00066     typedef jsk_pcl_ros::EdgeDepthRefinementConfig Config;
00067   protected:
00069     // methods
00071     virtual void onInit();
00072     
00073     virtual void refine(
00074       const sensor_msgs::PointCloud2ConstPtr &point,
00075       const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices);
00076     
00077     virtual void removeOutliersByLine(
00078       const pcl::PointCloud<PointT>::Ptr& cloud,
00079       const std::vector<int>& indices,
00080       pcl::PointIndices& inliers,
00081       pcl::ModelCoefficients& coefficients);
00082     
00083     virtual void removeOutliers(
00084       const pcl::PointCloud<PointT>::Ptr& cloud,
00085       const std::vector<PCLIndicesMsg>& indices,
00086       std::vector<pcl::PointIndices::Ptr>& output_inliers,
00087       std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients);
00088     
00089     virtual void removeDuplicatedEdges(
00090       const pcl::PointCloud<PointT>::Ptr& cloud,
00091       const std::vector<pcl::PointIndices::Ptr> inliers,
00092       const std::vector<pcl::ModelCoefficients::Ptr> coefficients,
00093       std::vector<pcl::PointIndices::Ptr>& output_inliers,
00094       std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients);
00095     
00096     virtual Line::Ptr lineFromCoefficients(
00097       const pcl::ModelCoefficients::Ptr coefficients);
00098     
00099     virtual Segment::Ptr segmentFromIndices(
00100       const pcl::PointCloud<PointT>::Ptr& cloud,
00101       const std::vector<int>& indices,
00102       const Line::Ptr& line);
00103     
00104     virtual void publishIndices(
00105       ros::Publisher& pub,
00106       ros::Publisher& pub_coefficients,
00107       const std::vector<pcl::PointIndices::Ptr> inliers,
00108       const std::vector<pcl::ModelCoefficients::Ptr> coefficients,
00109       const std_msgs::Header& header);
00110     
00111     virtual boost::tuple<int, int> findMinMaxIndex(
00112       const int width, const int height,
00113       const std::vector<int>& indices);
00114     
00115     virtual void integrateDuplicatedIndices(
00116       const pcl::PointCloud<PointT>::Ptr& cloud,
00117       const std::set<int>& duplicated_set,
00118       const std::vector<pcl::PointIndices::Ptr> all_inliers,
00119       pcl::PointIndices::Ptr& output_indices);
00120     
00121     virtual void configCallback (Config &config, uint32_t level);
00122 
00123     virtual void subscribe();
00124     virtual void unsubscribe();
00125     
00127     // ROS variables
00129     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00130     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00131     message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_indices_;
00132     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00133     ros::Publisher pub_indices_, pub_outlier_removed_indices_;
00134     ros::Publisher pub_coefficients_, pub_outlier_removed_coefficients_;
00135     boost::mutex mutex_;
00137     // outlier removal
00139     double outlier_distance_threshold_;
00140     int min_inliers_;
00142     // duplication removal
00144     double duplication_angle_threshold_;
00145     double duplication_distance_threshold_;
00146   private:
00147     
00148   };
00149 }
00150 
00151 #endif


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