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/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 #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 
43 #include <jsk_topic_tools/diagnostic_nodelet.h>
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 
56  class HintedPlaneDetector: public jsk_topic_tools::DiagnosticNodelet
57  {
58  public:
59  typedef HintedPlaneDetectorConfig Config;
61  sensor_msgs::PointCloud2,
62  sensor_msgs::PointCloud2> SyncPolicy;
63  HintedPlaneDetector(): DiagnosticNodelet("HintedPlaneDetector") {}
64  virtual ~HintedPlaneDetector();
65  protected:
66  virtual void onInit();
67  virtual void subscribe();
68  virtual void unsubscribe();
69  virtual void setHintCloud(const sensor_msgs::PointCloud2::ConstPtr& msg);
70  virtual void detect(
71  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
72  const sensor_msgs::PointCloud2::ConstPtr& hint_cloud_msg);
73  virtual bool detectHintPlane(
74  pcl::PointCloud<pcl::PointXYZ>::Ptr hint_cloud,
76  virtual bool detectLargerPlane(
77  pcl::PointCloud<pcl::PointNormal>::Ptr input_cloud,
79  virtual pcl::PointIndices::Ptr getBestCluster(
80  pcl::PointCloud<pcl::PointNormal>::Ptr input_cloud,
81  const std::vector<pcl::PointIndices>& cluster_indices,
83  virtual void publishPolygon(
85  ros::Publisher& pub_polygon, ros::Publisher& pub_polygon_array,
86  const pcl::PCLHeader& header);
87  virtual void configCallback(Config &config, uint32_t level);
88  virtual void densityFilter(
89  const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
90  const pcl::PointIndices::Ptr indices,
91  pcl::PointIndices& output);
92  virtual void euclideanFilter(
93  const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
94  const pcl::PointIndices::Ptr indices,
96  pcl::PointIndices& output);
97  virtual void planeFilter(
98  const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
99  const pcl::PointIndices::Ptr indices,
100  const Eigen::Vector3f& normal,
101  pcl::PointIndices& output,
102  pcl::ModelCoefficients& coefficients);
103  virtual void hintFilter(
104  const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
106  pcl::PointIndices& output);
107 
109  // ROS variables
130  sensor_msgs::PointCloud2::ConstPtr hint_cloud_;
131 
133  // parameters
135  bool synchronize_;
138  int hint_min_size_;
139  int max_iteration_;
140  int min_size_;
141  double outlier_threashold_;
142  double eps_angle_;
150  double density_radius_;
151  int density_num_;
152  };
153 }
154 
155 #endif
jsk_pcl_ros::HintedPlaneDetector::pub_coefficients_
ros::Publisher pub_coefficients_
Definition: hinted_plane_detector.h:185
jsk_pcl_ros::HintedPlaneDetector::enable_normal_filtering_
bool enable_normal_filtering_
Definition: hinted_plane_detector.h:211
ros::Publisher
jsk_pcl_ros::HintedPlaneDetector::enable_density_filtering_
bool enable_density_filtering_
Definition: hinted_plane_detector.h:213
jsk_pcl_ros::HintedPlaneDetector::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: hinted_plane_detector.h:175
jsk_pcl_ros::HintedPlaneDetector::HintedPlaneDetector
HintedPlaneDetector()
Definition: hinted_plane_detector.h:127
boost::shared_ptr< ConvexPolygon >
jsk_pcl_ros::HintedPlaneDetector::subscribe
virtual void subscribe()
Definition: hinted_plane_detector_nodelet.cpp:98
jsk_pcl_ros::HintedPlaneDetector::pub_density_filtered_indices_
ros::Publisher pub_density_filtered_indices_
Definition: hinted_plane_detector.h:188
jsk_pcl_ros::HintedPlaneDetector::outlier_threashold_
double outlier_threashold_
Definition: hinted_plane_detector.h:205
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::HintedPlaneDetector::sub_cloud_single_
ros::Subscriber sub_cloud_single_
Definition: hinted_plane_detector.h:192
jsk_pcl_ros::HintedPlaneDetector::density_num_
int density_num_
Definition: hinted_plane_detector.h:215
ros.h
jsk_pcl_ros::HintedPlaneDetector::hintFilter
virtual void hintFilter(const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex, pcl::PointIndices &output)
Definition: hinted_plane_detector_nodelet.cpp:288
jsk_pcl_ros::HintedPlaneDetector::planeFilter
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)
Definition: hinted_plane_detector_nodelet.cpp:311
jsk_pcl_ros::HintedPlaneDetector::hint_max_iteration_
int hint_max_iteration_
Definition: hinted_plane_detector.h:201
geo_util.h
time_synchronizer.h
jsk_pcl_ros::HintedPlaneDetector::pub_polygon_array_
ros::Publisher pub_polygon_array_
Definition: hinted_plane_detector.h:182
sample_simulate_tabletop_cloud.pub_polygon
pub_polygon
Definition: sample_simulate_tabletop_cloud.py:150
jsk_pcl_ros::HintedPlaneDetector::unsubscribe
virtual void unsubscribe()
Definition: hinted_plane_detector_nodelet.cpp:117
jsk_pcl_ros::HintedPlaneDetector::mutex_
boost::mutex mutex_
Definition: hinted_plane_detector.h:191
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::HintedPlaneDetector::densityFilter
virtual void densityFilter(const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, pcl::PointIndices &output)
Definition: hinted_plane_detector_nodelet.cpp:222
pcl_nodelet.h
jsk_pcl_ros::HintedPlaneDetector::~HintedPlaneDetector
virtual ~HintedPlaneDetector()
Definition: hinted_plane_detector_nodelet.cpp:87
jsk_pcl_ros::HintedPlaneDetector::getBestCluster
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)
Definition: hinted_plane_detector_nodelet.cpp:197
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::HintedPlaneDetector::eps_angle_
double eps_angle_
Definition: hinted_plane_detector.h:206
jsk_pcl_ros::HintedPlaneDetector::hint_min_size_
int hint_min_size_
Definition: hinted_plane_detector.h:202
jsk_pcl_ros::HintedPlaneDetector::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: hinted_plane_detector.h:190
jsk_pcl_ros::HintedPlaneDetector::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: hinted_plane_detector.h:176
jsk_pcl_ros::HintedPlaneDetector::sub_hint_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_hint_cloud_
Definition: hinted_plane_detector.h:177
jsk_pcl_ros::HintedPlaneDetector::density_radius_
double density_radius_
Definition: hinted_plane_detector.h:214
subscriber.h
jsk_pcl_ros::HintedPlaneDetector::normal_filter_eps_angle_
double normal_filter_eps_angle_
Definition: hinted_plane_detector.h:207
jsk_pcl_ros::HintedPlaneDetector::pub_inliers_
ros::Publisher pub_inliers_
Definition: hinted_plane_detector.h:184
jsk_pcl_ros::HintedPlaneDetector::euclidean_clustering_filter_min_size_
int euclidean_clustering_filter_min_size_
Definition: hinted_plane_detector.h:209
jsk_pcl_ros::HintedPlaneDetector::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > SyncPolicy
Definition: hinted_plane_detector.h:126
jsk_pcl_ros::HintedPlaneDetector::pub_plane_filtered_indices_
ros::Publisher pub_plane_filtered_indices_
Definition: hinted_plane_detector.h:187
jsk_pcl_ros::HintedPlaneDetector::pub_hint_filtered_indices_
ros::Publisher pub_hint_filtered_indices_
Definition: hinted_plane_detector.h:186
jsk_pcl_ros::HintedPlaneDetector::euclideanFilter
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)
Definition: hinted_plane_detector_nodelet.cpp:253
jsk_pcl_ros::HintedPlaneDetector::hint_cloud_
sensor_msgs::PointCloud2::ConstPtr hint_cloud_
Definition: hinted_plane_detector.h:194
jsk_pcl_ros::HintedPlaneDetector::pub_hint_polygon_array_
ros::Publisher pub_hint_polygon_array_
Definition: hinted_plane_detector.h:179
jsk_pcl_ros::HintedPlaneDetector::max_iteration_
int max_iteration_
Definition: hinted_plane_detector.h:203
jsk_pcl_ros::HintedPlaneDetector::euclidean_clustering_filter_tolerance_
double euclidean_clustering_filter_tolerance_
Definition: hinted_plane_detector.h:208
jsk_pcl_ros::HintedPlaneDetector::detect
virtual void detect(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &hint_cloud_msg)
Definition: hinted_plane_detector_nodelet.cpp:164
pcl_conversion_util.h
jsk_pcl_ros::HintedPlaneDetector::min_size_
int min_size_
Definition: hinted_plane_detector.h:204
jsk_pcl_ros::HintedPlaneDetector::detectHintPlane
virtual bool detectHintPlane(pcl::PointCloud< pcl::PointXYZ >::Ptr hint_cloud, jsk_recognition_utils::ConvexPolygon::Ptr &convex)
Definition: hinted_plane_detector_nodelet.cpp:410
jsk_pcl_ros::HintedPlaneDetector::publishPolygon
virtual void publishPolygon(const jsk_recognition_utils::ConvexPolygon::Ptr convex, ros::Publisher &pub_polygon, ros::Publisher &pub_polygon_array, const pcl::PCLHeader &header)
Definition: hinted_plane_detector_nodelet.cpp:393
jsk_pcl_ros::HintedPlaneDetector::pub_euclidean_filtered_indices_
ros::Publisher pub_euclidean_filtered_indices_
Definition: hinted_plane_detector.h:189
jsk_pcl_ros::HintedPlaneDetector::enable_euclidean_filtering_
bool enable_euclidean_filtering_
Definition: hinted_plane_detector.h:210
jsk_pcl_ros::HintedPlaneDetector::onInit
virtual void onInit()
Definition: hinted_plane_detector_nodelet.cpp:52
synchronizer.h
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::HintedPlaneDetector::sub_hint_cloud_single_
ros::Subscriber sub_hint_cloud_single_
Definition: hinted_plane_detector.h:193
jsk_pcl_ros::HintedPlaneDetector::synchronize_
bool synchronize_
Definition: hinted_plane_detector.h:199
message_filters::sync_policies::ExactTime
jsk_pcl_ros::HintedPlaneDetector::pub_hint_inliers_
ros::Publisher pub_hint_inliers_
Definition: hinted_plane_detector.h:180
jsk_pcl_ros::HintedPlaneDetector::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: hinted_plane_detector_nodelet.cpp:128
jsk_pcl_ros::HintedPlaneDetector::hint_outlier_threashold_
double hint_outlier_threashold_
Definition: hinted_plane_detector.h:200
jsk_pcl_ros::HintedPlaneDetector::enable_distance_filtering_
bool enable_distance_filtering_
Definition: hinted_plane_detector.h:212
jsk_pcl_ros::HintedPlaneDetector::pub_hint_coefficients_
ros::Publisher pub_hint_coefficients_
Definition: hinted_plane_detector.h:181
jsk_pcl_ros::HintedPlaneDetector::setHintCloud
virtual void setHintCloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: hinted_plane_detector_nodelet.cpp:156
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::HintedPlaneDetector::pub_polygon_
ros::Publisher pub_polygon_
Definition: hinted_plane_detector.h:183
jsk_pcl_ros::HintedPlaneDetector::pub_hint_polygon_
ros::Publisher pub_hint_polygon_
Definition: hinted_plane_detector.h:178
ros::Subscriber
jsk_pcl_ros::HintedPlaneDetector::detectLargerPlane
virtual bool detectLargerPlane(pcl::PointCloud< pcl::PointNormal >::Ptr input_cloud, jsk_recognition_utils::ConvexPolygon::Ptr hint_convex)
Definition: hinted_plane_detector_nodelet.cpp:336
jsk_pcl_ros::HintedPlaneDetector::Config
HintedPlaneDetectorConfig Config
Definition: hinted_plane_detector.h:123


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