parallel_edge_finder.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_PCL_ROS_PARALLEL_EDGE_FINDER_H_
38 #define JSK_PCL_ROS_PARALLEL_EDGE_FINDER_H_
39 
40 #include <pcl_ros/pcl_nodelet.h>
41 #include <jsk_recognition_msgs/ParallelEdgeArray.h>
42 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
43 #include <jsk_recognition_msgs/ClusterPointIndices.h>
44 #include <jsk_pcl_ros/ParallelEdgeFinderConfig.h>
46 #include <dynamic_reconfigure/server.h>
47 
52 
54 
55 namespace jsk_pcl_ros
56 {
58  {
59  public:
61  jsk_recognition_msgs::ClusterPointIndices,
62  jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy;
63  typedef jsk_pcl_ros::ParallelEdgeFinderConfig Config;
64  protected:
66  // methods
68  virtual void onInit();
69 
70  virtual void estimate(
71  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
72  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients);
73 
74  virtual void publishResult(
75  const std::vector<std::set<int> >& parallel_groups_list,
76  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
77  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients);
78 
79  // for visualization
80  virtual void publishResultAsCluser(
81  const std::vector<std::set<int> >& parallel_groups_list,
82  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
83  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients);
84 
85  virtual void configCallback (Config &config, uint32_t level);
86 
87  virtual void subscribe();
88  virtual void unsubscribe();
89 
91  // ROS variables
100  // parallel estimation parameters
103  private:
104 
105  };
106 }
107 
108 #endif
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
jsk_pcl_ros::ParallelEdgeFinderConfig Config
virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void publishResultAsCluser(const std::vector< std::set< int > > &parallel_groups_list, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)
boost::mutex mutex
global mutex.
virtual void publishResult(const std::vector< std::set< int > > &parallel_groups_list, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void estimate(const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47