hinted_plane_detector.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Ryohei Ueda and 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 #ifndef JSK_PCL_ROS_HINTED_PLANE_DETECTOR_H_
37 #define JSK_PCL_ROS_HINTED_PLANE_DETECTOR_H_
38 
39 #include <ros/ros.h>
40 #include <pcl/point_types.h>
41 #include <pcl_ros/pcl_nodelet.h>
42 
49 #include <geometry_msgs/PolygonStamped.h>
50 #include <jsk_recognition_msgs/PolygonArray.h>
51 #include <dynamic_reconfigure/server.h>
52 #include <jsk_pcl_ros/HintedPlaneDetectorConfig.h>
53 
54 namespace jsk_pcl_ros {
55 
57  {
58  public:
59  typedef HintedPlaneDetectorConfig Config;
61  sensor_msgs::PointCloud2,
62  sensor_msgs::PointCloud2> SyncPolicy;
63  HintedPlaneDetector(): DiagnosticNodelet("HintedPlaneDetector") {}
64 
65  protected:
66  virtual void onInit();
67  virtual void subscribe();
68  virtual void unsubscribe();
69  virtual void detect(
70  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
71  const sensor_msgs::PointCloud2::ConstPtr& hint_cloud_msg);
72  virtual bool detectHintPlane(
73  pcl::PointCloud<pcl::PointXYZ>::Ptr hint_cloud,
75  virtual bool detectLargerPlane(
76  pcl::PointCloud<pcl::PointNormal>::Ptr input_cloud,
78  virtual pcl::PointIndices::Ptr getBestCluster(
79  pcl::PointCloud<pcl::PointNormal>::Ptr input_cloud,
80  const std::vector<pcl::PointIndices>& cluster_indices,
82  virtual void publishPolygon(
84  ros::Publisher& pub_polygon, ros::Publisher& pub_polygon_array,
85  const pcl::PCLHeader& header);
86  virtual void configCallback(Config &config, uint32_t level);
87  virtual void densityFilter(
88  const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
89  const pcl::PointIndices::Ptr indices,
90  pcl::PointIndices& output);
91  virtual void euclideanFilter(
92  const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
93  const pcl::PointIndices::Ptr indices,
95  pcl::PointIndices& output);
96  virtual void planeFilter(
97  const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
98  const pcl::PointIndices::Ptr indices,
99  const Eigen::Vector3f& normal,
100  pcl::PointIndices& output,
101  pcl::ModelCoefficients& coefficients);
102  virtual void hintFilter(
103  const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
105  pcl::PointIndices& output);
106 
108  // ROS variables
127 
129  // parameters
137  double eps_angle_;
147  };
148 }
149 
150 #endif
virtual bool detectHintPlane(pcl::PointCloud< pcl::PointXYZ >::Ptr hint_cloud, jsk_recognition_utils::ConvexPolygon::Ptr &convex)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void detect(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &hint_cloud_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > SyncPolicy
config
coefficients
virtual pcl::PointIndices::Ptr getBestCluster(pcl::PointCloud< pcl::PointNormal >::Ptr input_cloud, const std::vector< pcl::PointIndices > &cluster_indices, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex)
virtual void hintFilter(const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex, pcl::PointIndices &output)
virtual void publishPolygon(const jsk_recognition_utils::ConvexPolygon::Ptr convex, ros::Publisher &pub_polygon, ros::Publisher &pub_polygon_array, const pcl::PCLHeader &header)
virtual void planeFilter(const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, const Eigen::Vector3f &normal, pcl::PointIndices &output, pcl::ModelCoefficients &coefficients)
DiagnosticNodelet(const std::string &name)
void output(int index, double value)
virtual bool detectLargerPlane(pcl::PointCloud< pcl::PointNormal >::Ptr input_cloud, jsk_recognition_utils::ConvexPolygon::Ptr hint_convex)
HintedPlaneDetectorConfig Config
virtual void euclideanFilter(const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex, pcl::PointIndices &output)
virtual void configCallback(Config &config, uint32_t level)
virtual void densityFilter(const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, pcl::PointIndices &output)
boost::mutex mutex
global mutex.
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_hint_cloud_
cloud


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