primitive_shape_classifier.h
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2017, 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  * primitive_shape_classifier.h
37  * Author: Yuki Furuta <furushchev@jsk.imi.i.u-tokyo.ac.jp>
38  */
39 
40 #ifndef JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__
41 #define JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__
42 
43 #include <boost/shared_ptr.hpp>
44 #include <dynamic_reconfigure/server.h>
49 #include <sensor_msgs/PointCloud2.h>
50 #include <jsk_recognition_msgs/ClusterPointIndices.h>
51 #include <jsk_recognition_msgs/ClassificationResult.h>
52 #include <jsk_recognition_msgs/PolygonArray.h>
55 #include <jsk_pcl_ros/PrimitiveShapeClassifierConfig.h>
56 #include <pcl/point_types.h>
57 #include <pcl/point_cloud.h>
58 #include <pcl/ModelCoefficients.h>
59 
60 namespace jsk_pcl_ros
61 {
63  {
64  public:
65  typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2,
66  sensor_msgs::PointCloud2,
67  jsk_recognition_msgs::ClusterPointIndices,
68  jsk_recognition_msgs::PolygonArray> SyncPolicy;
69  typedef PrimitiveShapeClassifierConfig Config;
70  typedef pcl::PointXYZRGBA PointT;
71 
72  PrimitiveShapeClassifier() : DiagnosticNodelet("PrimitiveShapeClassifier") {}
73  protected:
74  virtual void onInit();
75  virtual void subscribe();
76  virtual void unsubscribe();
77  virtual void configCallback(Config& config, uint32_t level);
78 
79  virtual void
80  process(const sensor_msgs::PointCloud2::ConstPtr& ros_cloud,
81  const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
82  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
83  const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons);
84 
85  virtual bool
86  estimate(const pcl::PointCloud<PointT>::Ptr& cloud,
87  const pcl::PointCloud<pcl::Normal>::Ptr& normal,
88  const pcl::ModelCoefficients::Ptr& plane,
89  pcl::PointIndices::Ptr& boundary_indices,
90  pcl::PointCloud<PointT>::Ptr& projected_cloud,
91  float& circle_likelihood,
92  float& box_likelihood);
93 
94  virtual bool
95  getSupportPlane(const pcl::PointCloud<PointT>::Ptr& cloud,
96  const std::vector<jsk_recognition_utils::Polygon::Ptr>& polygons,
97  pcl::ModelCoefficients::Ptr& coeff);
98 
99  virtual bool
100  checkFrameId(const sensor_msgs::PointCloud2::ConstPtr& ros_cloud,
101  const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
102  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
103  const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons);
104 
105  // properties
116 
117  // parameters
124  };
125 }
126 
127 #endif // JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__
virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
config
virtual bool estimate(const pcl::PointCloud< PointT >::Ptr &cloud, const pcl::PointCloud< pcl::Normal >::Ptr &normal, const pcl::ModelCoefficients::Ptr &plane, pcl::PointIndices::Ptr &boundary_indices, pcl::PointCloud< PointT >::Ptr &projected_cloud, float &circle_likelihood, float &box_likelihood)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
DiagnosticNodelet(const std::string &name)
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray > SyncPolicy
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
virtual void process(const sensor_msgs::PointCloud2::ConstPtr &ros_cloud, const sensor_msgs::PointCloud2::ConstPtr &ros_normal, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &ros_indices, const jsk_recognition_msgs::PolygonArray::ConstPtr &ros_polygons)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::mutex mutex
global mutex.
virtual bool checkFrameId(const sensor_msgs::PointCloud2::ConstPtr &ros_cloud, const sensor_msgs::PointCloud2::ConstPtr &ros_normal, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &ros_indices, const jsk_recognition_msgs::PolygonArray::ConstPtr &ros_polygons)
cloud
virtual bool getSupportPlane(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< jsk_recognition_utils::Polygon::Ptr > &polygons, pcl::ModelCoefficients::Ptr &coeff)
polygons


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