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/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  * 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>
45 #include <jsk_topic_tools/diagnostic_nodelet.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 {
62  class PrimitiveShapeClassifier : public jsk_topic_tools::DiagnosticNodelet
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  virtual ~PrimitiveShapeClassifier();
74  protected:
75  virtual void onInit();
76  virtual void subscribe();
77  virtual void unsubscribe();
78  virtual void configCallback(Config& config, uint32_t level);
79 
80  virtual void
81  process(const sensor_msgs::PointCloud2::ConstPtr& ros_cloud,
82  const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
83  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
84  const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons);
85 
86  virtual bool
87  estimate(const pcl::PointCloud<PointT>::Ptr& cloud,
88  const pcl::PointCloud<pcl::Normal>::Ptr& normal,
89  const pcl::ModelCoefficients::Ptr& plane,
90  pcl::PointIndices::Ptr& boundary_indices,
91  pcl::PointCloud<PointT>::Ptr& projected_cloud,
92  float& circle_likelihood,
93  float& box_likelihood);
94 
95  virtual bool
96  getSupportPlane(const pcl::PointCloud<PointT>::Ptr& cloud,
97  const std::vector<jsk_recognition_utils::Polygon::Ptr>& polygons,
98  pcl::ModelCoefficients::Ptr& coeff);
99 
100  virtual bool
101  checkFrameId(const sensor_msgs::PointCloud2::ConstPtr& ros_cloud,
102  const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
103  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
104  const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons);
105 
106  // properties
117 
118  // parameters
119  int queue_size_;
120  int min_points_num_;
125  };
126 }
127 
128 #endif // JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__
jsk_pcl_ros::PrimitiveShapeClassifier::checkFrameId
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)
Definition: primitive_shape_classifier_nodelet.cpp:163
jsk_pcl_ros::PrimitiveShapeClassifier::sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
Definition: primitive_shape_classifier.h:176
jsk_pcl_ros::PrimitiveShapeClassifier::estimate
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)
Definition: primitive_shape_classifier_nodelet.cpp:295
ros::Publisher
jsk_pcl_ros::PrimitiveShapeClassifier::PrimitiveShapeClassifier
PrimitiveShapeClassifier()
Definition: primitive_shape_classifier.h:136
boost::shared_ptr
jsk_pcl_ros::PrimitiveShapeClassifier::pub_boundary_indices_
ros::Publisher pub_boundary_indices_
Definition: primitive_shape_classifier.h:179
pcl_ros_util.h
geo_util.h
time_synchronizer.h
jsk_pcl_ros::PrimitiveShapeClassifier::PointT
pcl::PointXYZRGBA PointT
Definition: primitive_shape_classifier.h:134
jsk_pcl_ros::PrimitiveShapeClassifier::unsubscribe
virtual void unsubscribe()
Definition: primitive_shape_classifier_nodelet.cpp:127
jsk_pcl_ros::PrimitiveShapeClassifier::circle_threshold_
double circle_threshold_
Definition: primitive_shape_classifier.h:188
jsk_pcl_ros::PrimitiveShapeClassifier::sub_normal_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
Definition: primitive_shape_classifier.h:174
jsk_pcl_ros::PrimitiveShapeClassifier::mutex_
boost::mutex mutex_
Definition: primitive_shape_classifier.h:171
jsk_pcl_ros::PrimitiveShapeClassifier::queue_size_
int queue_size_
Definition: primitive_shape_classifier.h:183
jsk_pcl_ros::PrimitiveShapeClassifier::Config
PrimitiveShapeClassifierConfig Config
Definition: primitive_shape_classifier.h:133
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::PrimitiveShapeClassifier::pub_class_
ros::Publisher pub_class_
Definition: primitive_shape_classifier.h:178
jsk_pcl_ros::PrimitiveShapeClassifier::subscribe
virtual void subscribe()
Definition: primitive_shape_classifier_nodelet.cpp:115
jsk_pcl_ros::PrimitiveShapeClassifier::~PrimitiveShapeClassifier
virtual ~PrimitiveShapeClassifier()
Definition: primitive_shape_classifier_nodelet.cpp:104
jsk_pcl_ros::PrimitiveShapeClassifier::min_points_num_
int min_points_num_
Definition: primitive_shape_classifier.h:184
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::PrimitiveShapeClassifier::process
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)
Definition: primitive_shape_classifier_nodelet.cpp:189
jsk_pcl_ros::PrimitiveShapeClassifier::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: primitive_shape_classifier.h:172
subscriber.h
jsk_pcl_ros::PrimitiveShapeClassifier::box_threshold_
double box_threshold_
Definition: primitive_shape_classifier.h:188
jsk_pcl_ros::PrimitiveShapeClassifier::sac_max_iterations_
int sac_max_iterations_
Definition: primitive_shape_classifier.h:185
jsk_pcl_ros::PrimitiveShapeClassifier::getSupportPlane
virtual bool getSupportPlane(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< jsk_recognition_utils::Polygon::Ptr > &polygons, pcl::ModelCoefficients::Ptr &coeff)
Definition: primitive_shape_classifier_nodelet.cpp:376
jsk_pcl_ros::PrimitiveShapeClassifier::sac_distance_threshold_
double sac_distance_threshold_
Definition: primitive_shape_classifier.h:186
jsk_pcl_ros::PrimitiveShapeClassifier::sac_radius_limit_min_
double sac_radius_limit_min_
Definition: primitive_shape_classifier.h:187
jsk_pcl_ros::PrimitiveShapeClassifier::onInit
virtual void onInit()
Definition: primitive_shape_classifier_nodelet.cpp:86
jsk_pcl_ros::PrimitiveShapeClassifier::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: primitive_shape_classifier.h:177
synchronizer.h
jsk_pcl_ros::PrimitiveShapeClassifier::sac_radius_limit_max_
double sac_radius_limit_max_
Definition: primitive_shape_classifier.h:187
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
message_filters::sync_policies::ExactTime
jsk_pcl_ros::PrimitiveShapeClassifier::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: primitive_shape_classifier.h:173
jsk_pcl_ros::PrimitiveShapeClassifier::pub_projected_cloud_
ros::Publisher pub_projected_cloud_
Definition: primitive_shape_classifier.h:180
jsk_pcl_ros::PrimitiveShapeClassifier::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray > SyncPolicy
Definition: primitive_shape_classifier.h:132
jsk_pcl_ros::PrimitiveShapeClassifier::sub_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
Definition: primitive_shape_classifier.h:175
jsk_pcl_ros::PrimitiveShapeClassifier::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: primitive_shape_classifier_nodelet.cpp:135


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