multi_plane_sac_segmentation.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/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 
37 #ifndef JSK_PCL_ROS_MULTI_PLANE_SEGMENTATION_H_
38 #define JSK_PCL_ROS_MULTI_PLANE_SEGMENTATION_H_
39 
40 #include <pcl_ros/pcl_nodelet.h>
44 #include <dynamic_reconfigure/server.h>
49 
50 #include <jsk_pcl_ros/MultiPlaneSACSegmentationConfig.h>
53 
54 
56 // messages
58 #include <sensor_msgs/PointCloud2.h>
59 #include <jsk_recognition_msgs/PolygonArray.h>
60 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
61 #include <jsk_recognition_msgs/ClusterPointIndices.h>
62 #include <sensor_msgs/Imu.h>
63 
64 namespace jsk_pcl_ros
65 {
67  {
68  public:
69  typedef pcl::PointXYZRGB PointT;
70  typedef jsk_pcl_ros::MultiPlaneSACSegmentationConfig Config;
72  sensor_msgs::PointCloud2,
73  sensor_msgs::PointCloud2 > SyncPolicy;
75  sensor_msgs::PointCloud2,
76  jsk_recognition_msgs::ClusterPointIndices > SyncClusterPolicy;
78  sensor_msgs::PointCloud2,
79  sensor_msgs::Imu
82  sensor_msgs::PointCloud2,
83  sensor_msgs::PointCloud2,
84  sensor_msgs::Imu
88  protected:
90  // methods
92  virtual void onInit();
93 
94  virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& msg);
95  virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& msg,
96  const sensor_msgs::PointCloud2::ConstPtr& msg_nromal);
97  virtual void segmentWithImu(const sensor_msgs::PointCloud2::ConstPtr& msg,
98  const sensor_msgs::Imu::ConstPtr& imu);
99  virtual void segmentWithImu(const sensor_msgs::PointCloud2::ConstPtr& msg,
100  const sensor_msgs::PointCloud2::ConstPtr& msg_nromal,
101  const sensor_msgs::Imu::ConstPtr& imu);
102  virtual void segmentWithClusters(
103  const sensor_msgs::PointCloud2::ConstPtr& msg,
104  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& clusters);
105  virtual void applyRecursiveRANSAC(
106  const pcl::PointCloud<PointT>::Ptr& input,
107  const pcl::PointCloud<pcl::Normal>::Ptr& normal,
108  const Eigen::Vector3f& imu_vector,
109  std::vector<pcl::PointIndices::Ptr>& output_inliers,
110  std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients,
111  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_polygons);
112  virtual void publishResult(
113  const std_msgs::Header& header,
114  const std::vector<pcl::PointIndices::Ptr>& inliers,
115  const std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
116  const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
117  virtual void configCallback (Config &config, uint32_t level);
118 
119  virtual void subscribe();
120  virtual void unsubscribe();
121 
123  // ROS variabels
138 
140  // parameters
150  double eps_angle_;
153  private:
154 
155  };
156 }
157 
158 #endif
virtual void segmentWithImu(const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::Imu::ConstPtr &imu)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
virtual void publishResult(const std_msgs::Header &header, const std::vector< pcl::PointIndices::Ptr > &inliers, const std::vector< pcl::ModelCoefficients::Ptr > &coefficients, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &msg)
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::Imu > SyncImuPolicy
virtual void segmentWithClusters(const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &clusters)
message_filters::Synchronizer< SyncNormalImuPolicy > NormalImuSynchronizer
boost::shared_ptr< message_filters::Synchronizer< SyncClusterPolicy > > sync_cluster_
virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< message_filters::Synchronizer< SyncNormalImuPolicy > > sync_normal_imu_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncClusterPolicy
message_filters::Subscriber< sensor_msgs::Imu > sub_imu_
jsk_pcl_ros::MultiPlaneSACSegmentationConfig Config
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_clusters_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > SyncPolicy
boost::mutex mutex
global mutex.
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::Imu > SyncNormalImuPolicy
virtual void applyRecursiveRANSAC(const pcl::PointCloud< PointT >::Ptr &input, const pcl::PointCloud< pcl::Normal >::Ptr &normal, const Eigen::Vector3f &imu_vector, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &output_polygons)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< message_filters::Synchronizer< SyncImuPolicy > > sync_imu_


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