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/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 
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>
51 #include <jsk_topic_tools/connection_based_nodelet.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 {
66  class MultiPlaneSACSegmentation: public jsk_topic_tools::ConnectionBasedNodelet
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
80  > SyncImuPolicy;
82  sensor_msgs::PointCloud2,
83  sensor_msgs::PointCloud2,
84  sensor_msgs::Imu
89  protected:
91  // methods
93  virtual void onInit();
94 
95  virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& msg);
96  virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& msg,
97  const sensor_msgs::PointCloud2::ConstPtr& msg_nromal);
98  virtual void segmentWithImu(const sensor_msgs::PointCloud2::ConstPtr& msg,
99  const sensor_msgs::Imu::ConstPtr& imu);
100  virtual void segmentWithImu(const sensor_msgs::PointCloud2::ConstPtr& msg,
101  const sensor_msgs::PointCloud2::ConstPtr& msg_nromal,
102  const sensor_msgs::Imu::ConstPtr& imu);
103  virtual void segmentWithClusters(
104  const sensor_msgs::PointCloud2::ConstPtr& msg,
105  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& clusters);
106  virtual void applyRecursiveRANSAC(
107  const pcl::PointCloud<PointT>::Ptr& input,
108  const pcl::PointCloud<pcl::Normal>::Ptr& normal,
109  const Eigen::Vector3f& imu_vector,
110  std::vector<pcl::PointIndices::Ptr>& output_inliers,
111  std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients,
112  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_polygons);
113  virtual void publishResult(
114  const std_msgs::Header& header,
115  const std::vector<pcl::PointIndices::Ptr>& inliers,
116  const std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
117  const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
118  virtual void configCallback (Config &config, uint32_t level);
119 
120  virtual void subscribe();
121  virtual void unsubscribe();
122 
124  // ROS variabels
139 
141  // parameters
143  double outlier_threshold_;
145  int min_points_;
146  int max_iterations_;
147  bool use_normal_;
148  bool use_clusters_;
151  double eps_angle_;
153  int min_trial_;
154  private:
155 
156  };
157 }
158 
159 #endif
jsk_pcl_ros::MultiPlaneSACSegmentation::Config
jsk_pcl_ros::MultiPlaneSACSegmentationConfig Config
Definition: multi_plane_sac_segmentation.h:134
jsk_pcl_ros::MultiPlaneSACSegmentation::unsubscribe
virtual void unsubscribe()
Definition: multi_plane_sac_segmentation_nodelet.cpp:170
jsk_pcl_ros::MultiPlaneSACSegmentation::sync_normal_imu_
boost::shared_ptr< message_filters::Synchronizer< SyncNormalImuPolicy > > sync_normal_imu_
Definition: multi_plane_sac_segmentation.h:196
jsk_pcl_ros::MultiPlaneSACSegmentation::outlier_threshold_
double outlier_threshold_
Definition: multi_plane_sac_segmentation.h:207
ros::Publisher
message_filters::Synchronizer
boost::shared_ptr
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::MultiPlaneSACSegmentation::NormalImuSynchronizer
message_filters::Synchronizer< SyncNormalImuPolicy > NormalImuSynchronizer
Definition: multi_plane_sac_segmentation.h:151
jsk_pcl_ros::MultiPlaneSACSegmentation::pub_polygons_
ros::Publisher pub_polygons_
Definition: multi_plane_sac_segmentation.h:191
jsk_pcl_ros::MultiPlaneSACSegmentation::segmentWithClusters
virtual void segmentWithClusters(const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &clusters)
Definition: multi_plane_sac_segmentation_nodelet.cpp:308
jsk_pcl_ros::MultiPlaneSACSegmentation::sub_normal_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
Definition: multi_plane_sac_segmentation.h:198
geo_util.h
jsk_pcl_ros::MultiPlaneSACSegmentation::use_clusters_
bool use_clusters_
Definition: multi_plane_sac_segmentation.h:212
time_synchronizer.h
tf_listener_singleton.h
jsk_pcl_ros::MultiPlaneSACSegmentation::applyRecursiveRANSAC
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)
Definition: multi_plane_sac_segmentation_nodelet.cpp:200
jsk_pcl_ros::MultiPlaneSACSegmentation::publishResult
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)
Definition: multi_plane_sac_segmentation_nodelet.cpp:342
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::MultiPlaneSACSegmentation::sync_cluster_
boost::shared_ptr< message_filters::Synchronizer< SyncClusterPolicy > > sync_cluster_
Definition: multi_plane_sac_segmentation.h:194
pcl_nodelet.h
jsk_pcl_ros::MultiPlaneSACSegmentation::sub_imu_
message_filters::Subscriber< sensor_msgs::Imu > sub_imu_
Definition: multi_plane_sac_segmentation.h:200
jsk_pcl_ros::MultiPlaneSACSegmentation::~MultiPlaneSACSegmentation
virtual ~MultiPlaneSACSegmentation()
Definition: multi_plane_sac_segmentation_nodelet.cpp:107
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros::MultiPlaneSACSegmentation::normal_distance_weight_
double normal_distance_weight_
Definition: multi_plane_sac_segmentation.h:216
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::MultiPlaneSACSegmentation::pub_coefficients_
ros::Publisher pub_coefficients_
Definition: multi_plane_sac_segmentation.h:191
jsk_pcl_ros::MultiPlaneSACSegmentation::SyncNormalImuPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::Imu > SyncNormalImuPolicy
Definition: multi_plane_sac_segmentation.h:149
subscriber.h
jsk_pcl_ros::MultiPlaneSACSegmentation::use_imu_perpendicular_
bool use_imu_perpendicular_
Definition: multi_plane_sac_segmentation.h:214
jsk_pcl_ros::MultiPlaneSACSegmentation::sub_clusters_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_clusters_
Definition: multi_plane_sac_segmentation.h:199
jsk_pcl_ros::MultiPlaneSACSegmentation::sync_imu_
boost::shared_ptr< message_filters::Synchronizer< SyncImuPolicy > > sync_imu_
Definition: multi_plane_sac_segmentation.h:195
pcl_conversion_util.h
jsk_pcl_ros::MultiPlaneSACSegmentation::segment
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: multi_plane_sac_segmentation_nodelet.cpp:444
jsk_pcl_ros::MultiPlaneSACSegmentation::min_inliers_
int min_inliers_
Definition: multi_plane_sac_segmentation.h:208
jsk_pcl_ros::MultiPlaneSACSegmentation::use_imu_parallel_
bool use_imu_parallel_
Definition: multi_plane_sac_segmentation.h:213
jsk_pcl_ros::MultiPlaneSACSegmentation::SyncImuPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::Imu > SyncImuPolicy
Definition: multi_plane_sac_segmentation.h:144
jsk_pcl_ros::MultiPlaneSACSegmentation::PointT
pcl::PointXYZRGB PointT
Definition: multi_plane_sac_segmentation.h:133
jsk_pcl_ros::MultiPlaneSACSegmentation::min_points_
int min_points_
Definition: multi_plane_sac_segmentation.h:209
jsk_pcl_ros::MultiPlaneSACSegmentation::max_iterations_
int max_iterations_
Definition: multi_plane_sac_segmentation.h:210
pcl_util.h
jsk_pcl_ros::MultiPlaneSACSegmentation::pub_inliers_
ros::Publisher pub_inliers_
Definition: multi_plane_sac_segmentation.h:191
jsk_pcl_ros::MultiPlaneSACSegmentation::subscribe
virtual void subscribe()
Definition: multi_plane_sac_segmentation_nodelet.cpp:121
jsk_pcl_ros::MultiPlaneSACSegmentation::tf_listener_
tf::TransformListener * tf_listener_
Definition: multi_plane_sac_segmentation.h:202
jsk_pcl_ros::MultiPlaneSACSegmentation::SyncClusterPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncClusterPolicy
Definition: multi_plane_sac_segmentation.h:140
jsk_pcl_ros::MultiPlaneSACSegmentation::use_normal_
bool use_normal_
Definition: multi_plane_sac_segmentation.h:211
jsk_pcl_ros::MultiPlaneSACSegmentation::mutex_
boost::mutex mutex_
Definition: multi_plane_sac_segmentation.h:201
tf::TransformListener
jsk_pcl_ros::MultiPlaneSACSegmentation::eps_angle_
double eps_angle_
Definition: multi_plane_sac_segmentation.h:215
synchronizer.h
jsk_pcl_ros::MultiPlaneSACSegmentation::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: multi_plane_sac_segmentation.h:193
approximate_time.h
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::MultiPlaneSACSegmentation::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > SyncPolicy
Definition: multi_plane_sac_segmentation.h:137
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
message_filters::sync_policies::ExactTime
jsk_pcl_ros::MultiPlaneSACSegmentation::segmentWithImu
virtual void segmentWithImu(const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::Imu::ConstPtr &imu)
Definition: multi_plane_sac_segmentation_nodelet.cpp:369
jsk_pcl_ros::MultiPlaneSACSegmentation::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: multi_plane_sac_segmentation.h:192
jsk_pcl_ros::MultiPlaneSACSegmentation::min_trial_
int min_trial_
Definition: multi_plane_sac_segmentation.h:217
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::MultiPlaneSACSegmentation::sub_
ros::Subscriber sub_
Definition: multi_plane_sac_segmentation.h:190
jsk_pcl_ros::MultiPlaneSACSegmentation::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: multi_plane_sac_segmentation.h:197
ros::Subscriber
jsk_pcl_ros::MultiPlaneSACSegmentation::onInit
virtual void onInit()
Definition: multi_plane_sac_segmentation_nodelet.cpp:78
jsk_pcl_ros::MultiPlaneSACSegmentation::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: multi_plane_sac_segmentation_nodelet.cpp:188


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