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/or 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 
53 #include <jsk_topic_tools/connection_based_nodelet.h>
54 
55 namespace jsk_pcl_ros
56 {
57  class ParallelEdgeFinder: public jsk_topic_tools::ConnectionBasedNodelet
58  {
59  public:
61  jsk_recognition_msgs::ClusterPointIndices,
62  jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy;
63  typedef jsk_pcl_ros::ParallelEdgeFinderConfig Config;
64  virtual ~ParallelEdgeFinder();
65  protected:
67  // methods
69  virtual void onInit();
70 
71  virtual void estimate(
72  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
73  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients);
74 
75  virtual void publishResult(
76  const std::vector<std::set<int> >& parallel_groups_list,
77  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
78  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients);
79 
80  // for visualization
81  virtual void publishResultAsCluser(
82  const std::vector<std::set<int> >& parallel_groups_list,
83  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
84  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients);
85 
86  virtual void configCallback (Config &config, uint32_t level);
87 
88  virtual void subscribe();
89  virtual void unsubscribe();
90 
92  // ROS variables
101  // parallel estimation parameters
103  double angle_threshold_;
104  private:
105 
106  };
107 }
108 
109 #endif
ros::Publisher
jsk_pcl_ros::ParallelEdgeFinder::pub_
ros::Publisher pub_
Definition: parallel_edge_finder.h:161
jsk_pcl_ros::ParallelEdgeFinder::subscribe
virtual void subscribe()
Definition: parallel_edge_finder_nodelet.cpp:105
boost::shared_ptr
jsk_pcl_ros::ParallelEdgeFinder::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: parallel_edge_finder.h:160
jsk_pcl_ros::ParallelEdgeFinder::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: parallel_edge_finder.h:162
geo_util.h
jsk_pcl_ros::ParallelEdgeFinder::unsubscribe
virtual void unsubscribe()
Definition: parallel_edge_finder_nodelet.cpp:118
time_synchronizer.h
jsk_pcl_ros::ParallelEdgeFinder::publishResult
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)
Definition: parallel_edge_finder_nodelet.cpp:192
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices >
jsk_pcl_ros::ParallelEdgeFinder::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: parallel_edge_finder.h:159
jsk_pcl_ros::ParallelEdgeFinder::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: parallel_edge_finder_nodelet.cpp:124
pcl_nodelet.h
jsk_pcl_ros::ParallelEdgeFinder::~ParallelEdgeFinder
virtual ~ParallelEdgeFinder()
Definition: parallel_edge_finder_nodelet.cpp:94
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::ParallelEdgeFinder::onInit
virtual void onInit()
Definition: parallel_edge_finder_nodelet.cpp:74
subscriber.h
jsk_pcl_ros::ParallelEdgeFinder::pub_clusters_
ros::Publisher pub_clusters_
Definition: parallel_edge_finder.h:161
jsk_pcl_ros::ParallelEdgeFinder::angle_threshold_
double angle_threshold_
Definition: parallel_edge_finder.h:167
jsk_pcl_ros::ParallelEdgeFinder::mutex_
boost::mutex mutex_
Definition: parallel_edge_finder.h:163
pcl_conversion_util.h
jsk_pcl_ros::ParallelEdgeFinder::estimate
virtual void estimate(const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)
Definition: parallel_edge_finder_nodelet.cpp:131
synchronizer.h
jsk_pcl_ros::ParallelEdgeFinder::publishResultAsCluser
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)
Definition: parallel_edge_finder_nodelet.cpp:225
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
message_filters::sync_policies::ExactTime
jsk_pcl_ros::ParallelEdgeFinder::sub_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
Definition: parallel_edge_finder.h:158
jsk_pcl_ros::ParallelEdgeFinder::Config
jsk_pcl_ros::ParallelEdgeFinderConfig Config
Definition: parallel_edge_finder.h:127
jsk_pcl_ros::ParallelEdgeFinder::SyncPolicy
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
Definition: parallel_edge_finder.h:126


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45