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_PARALLEL_EDGE_FINDER_H_ 00038 #define JSK_PCL_ROS_PARALLEL_EDGE_FINDER_H_ 00039 00040 #include <pcl_ros/pcl_nodelet.h> 00041 #include <jsk_recognition_msgs/ParallelEdgeArray.h> 00042 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 00043 #include <jsk_recognition_msgs/ClusterPointIndices.h> 00044 #include <jsk_pcl_ros/ParallelEdgeFinderConfig.h> 00045 #include "jsk_pcl_ros/pcl_conversion_util.h" 00046 #include <dynamic_reconfigure/server.h> 00047 00048 #include <message_filters/subscriber.h> 00049 #include <message_filters/time_synchronizer.h> 00050 #include <message_filters/synchronizer.h> 00051 #include "jsk_pcl_ros/geo_util.h" 00052 00053 #include <jsk_topic_tools/connection_based_nodelet.h> 00054 00055 namespace jsk_pcl_ros 00056 { 00057 class ParallelEdgeFinder: public jsk_topic_tools::ConnectionBasedNodelet 00058 { 00059 public: 00060 typedef message_filters::sync_policies::ExactTime< 00061 jsk_recognition_msgs::ClusterPointIndices, 00062 jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy; 00063 typedef jsk_pcl_ros::ParallelEdgeFinderConfig Config; 00064 protected: 00066 // methods 00068 virtual void onInit(); 00069 00070 virtual void estimate( 00071 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices, 00072 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients); 00073 00074 virtual void publishResult( 00075 const std::vector<std::set<int> >& parallel_groups_list, 00076 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices, 00077 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients); 00078 00079 // for visualization 00080 virtual void publishResultAsCluser( 00081 const std::vector<std::set<int> >& parallel_groups_list, 00082 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices, 00083 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients); 00084 00085 virtual void configCallback (Config &config, uint32_t level); 00086 00087 virtual void subscribe(); 00088 virtual void unsubscribe(); 00089 00091 // ROS variables 00093 message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_indices_; 00094 message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> sub_coefficients_; 00095 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_; 00096 ros::Publisher pub_, pub_clusters_; 00097 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_; 00098 boost::mutex mutex_; 00100 // parallel estimation parameters 00102 double angle_threshold_; 00103 private: 00104 00105 }; 00106 } 00107 00108 #endif