organized_multi_plane_segmentation.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_ORGANIZED_PLANE_SEGMENTATION_H_
37 #define JSK_PCL_ROS_ORGANIZED_PLANE_SEGMENTATION_H_
38 
39 #include <ros/ros.h>
40 #include <ros/names.h>
41 
42 #include "jsk_recognition_msgs/ClusterPointIndices.h"
43 #include "sensor_msgs/PointCloud2.h"
44 #include <pcl_ros/pcl_nodelet.h>
45 #include <pcl/segmentation/organized_multi_plane_segmentation.h>
46 #include <dynamic_reconfigure/server.h>
47 #include "jsk_pcl_ros/OrganizedMultiPlaneSegmentationConfig.h"
48 #include "jsk_recognition_msgs/PolygonArray.h"
49 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
50 #include <jsk_topic_tools/time_accumulator.h>
51 #include <jsk_topic_tools/vital_checker.h>
54 
57 #include <jsk_topic_tools/connection_based_nodelet.h>
58 #include <jsk_topic_tools/diagnostic_utils.h>
59 
60 namespace jsk_pcl_ros
61 {
62  class OrganizedMultiPlaneSegmentation:
63  public jsk_topic_tools::ConnectionBasedNodelet
64  {
65  public:
66  typedef pcl::PointXYZRGBA PointT;
67  typedef std::vector<pcl::PlanarRegion<PointT>,
68  Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > >
70  typedef jsk_pcl_ros::OrganizedMultiPlaneSegmentationConfig Config;
71  protected:
73  // methods
75  virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& msg);
76  virtual void estimateNormal(pcl::PointCloud<PointT>::Ptr input,
77  pcl::PointCloud<pcl::Normal>::Ptr output);
78  virtual void configCallback (Config &config, uint32_t level);
79  virtual void pointCloudToPolygon(const pcl::PointCloud<PointT>& input,
80  geometry_msgs::Polygon& polygon);
81  virtual void pclIndicesArrayToClusterPointIndices(const std::vector<pcl::PointIndices>& inlier_indices,
82  const std_msgs::Header& header,
83  jsk_recognition_msgs::ClusterPointIndices& output_indices);
84  virtual void connectPlanesMap(const pcl::PointCloud<PointT>::Ptr& input,
85  const std::vector<pcl::ModelCoefficients>& model_coefficients,
86  const std::vector<pcl::PointIndices>& boundary_indices,
88  virtual void buildConnectedPlanes(const pcl::PointCloud<PointT>::Ptr& input,
89  const std_msgs::Header& header,
90  const std::vector<pcl::PointIndices>& inlier_indices,
91  const std::vector<pcl::PointIndices>& boundary_indices,
92  const std::vector<pcl::ModelCoefficients>& model_coefficients,
93  const jsk_recognition_utils::IntegerGraphMap& connection_map,
94  std::vector<pcl::PointIndices>& output_indices,
95  std::vector<pcl::ModelCoefficients>& output_coefficients,
96  std::vector<pcl::PointCloud<PointT> >& output_boundary_clouds);
97  virtual void forceToDirectOrigin(const std::vector<pcl::ModelCoefficients>& coefficients,
98  std::vector<pcl::ModelCoefficients>& output_coefficients);
99  virtual void publishMarkerOfConnection(
101  const pcl::PointCloud<PointT>::Ptr cloud,
102  const std::vector<pcl::PointIndices>& inliers,
103  const std_msgs::Header& header);
104 
105  virtual void segmentOrganizedMultiPlanes(
106  pcl::PointCloud<PointT>::Ptr input,
107  pcl::PointCloud<pcl::Normal>::Ptr normal,
108  PlanarRegionVector& regions,
109  std::vector<pcl::ModelCoefficients>& model_coefficients,
110  std::vector<pcl::PointIndices>& inlier_indices,
111  pcl::PointCloud<pcl::Label>::Ptr& labels,
112  std::vector<pcl::PointIndices>& label_indices,
113  std::vector<pcl::PointIndices>& boundary_indices);
114 
115  virtual void segmentFromNormals(pcl::PointCloud<PointT>::Ptr input,
116  pcl::PointCloud<pcl::Normal>::Ptr normal,
117  const std_msgs::Header& header);
118 
119  virtual void publishSegmentationInformation(
120  const std_msgs::Header& header,
121  const pcl::PointCloud<PointT>::Ptr input,
122  ros::Publisher& indices_pub,
123  ros::Publisher& polygon_pub,
125  const std::vector<pcl::PointIndices>& inlier_indices,
126  const std::vector<pcl::PointCloud<PointT> >& boundaries,
127  const std::vector<pcl::ModelCoefficients>& model_coefficients);
128  virtual void publishSegmentationInformation(
129  const std_msgs::Header& header,
130  const pcl::PointCloud<PointT>::Ptr input,
131  ros::Publisher& indices_pub,
132  ros::Publisher& polygon_pub,
134  const std::vector<pcl::PointIndices>& inlier_indices,
135  const std::vector<pcl::PointIndices>& boundary_indices,
136  const std::vector<pcl::ModelCoefficients>& model_coefficients);
137 
138  virtual void refineBasedOnRANSAC(
139  const pcl::PointCloud<PointT>::Ptr input,
140  const std::vector<pcl::PointIndices>& input_indices,
141  const std::vector<pcl::ModelCoefficients>& input_coefficients,
142  std::vector<pcl::PointIndices>& output_indices,
143  std::vector<pcl::ModelCoefficients>& output_coefficients,
144  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_boundaries);
145 
146 
147  virtual void updateDiagnostics(const ros::TimerEvent& event);
152  virtual void subscribe();
153  virtual void unsubscribe();
155  // ROS variables
166  jsk_topic_tools::TimeAccumulator plane_segmentation_time_acc_;
167  jsk_topic_tools::TimeAccumulator normal_estimation_time_acc_;
168  jsk_topic_tools::TimeAccumulator ransac_refinement_time_acc_;
169  jsk_topic_tools::VitalChecker::Ptr normal_estimation_vital_checker_;
170  jsk_topic_tools::VitalChecker::Ptr plane_segmentation_vital_checker_;
172 
173  int min_size_;
174  double concave_alpha_;
175  double angular_threshold_;
176  double distance_threshold_;
177  double max_curvature_;
182  int estimation_method_;
185  double normal_smoothing_size_;
187  bool estimate_normal_;
188  bool publish_normal_;
189 
193  jsk_topic_tools::ConnectionStatus previous_checked_connection_status_for_normal_;
194 
198  jsk_topic_tools::ConnectionStatus previous_checked_connection_status_for_plane_;
199 
201  // parameters for RANSAC refinement
205 
208 
209 
210  private:
211  virtual void onInit();
212  };
213 }
214 
215 #endif
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::estimation_method_
int estimation_method_
Definition: organized_multi_plane_segmentation.h:246
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::org_coefficients_pub_
ros::Publisher org_coefficients_pub_
Definition: organized_multi_plane_segmentation.h:221
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::buildConnectedPlanes
virtual void buildConnectedPlanes(const pcl::PointCloud< PointT >::Ptr &input, const std_msgs::Header &header, const std::vector< pcl::PointIndices > &inlier_indices, const std::vector< pcl::PointIndices > &boundary_indices, const std::vector< pcl::ModelCoefficients > &model_coefficients, const jsk_recognition_utils::IntegerGraphMap &connection_map, std::vector< pcl::PointIndices > &output_indices, std::vector< pcl::ModelCoefficients > &output_coefficients, std::vector< pcl::PointCloud< PointT > > &output_boundary_clouds)
Definition: organized_multi_plane_segmentation_nodelet.cpp:347
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::plane_segmentation_time_acc_
jsk_topic_tools::TimeAccumulator plane_segmentation_time_acc_
Definition: organized_multi_plane_segmentation.h:230
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::connectPlanesMap
virtual void connectPlanesMap(const pcl::PointCloud< PointT >::Ptr &input, const std::vector< pcl::ModelCoefficients > &model_coefficients, const std::vector< pcl::PointIndices > &boundary_indices, jsk_recognition_utils::IntegerGraphMap &connection_map)
Definition: organized_multi_plane_segmentation_nodelet.cpp:230
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::diagnostics_timer_
ros::Timer diagnostics_timer_
Definition: organized_multi_plane_segmentation.h:235
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::refined_polygon_pub_
ros::Publisher refined_polygon_pub_
Definition: organized_multi_plane_segmentation.h:223
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::refined_pub_
ros::Publisher refined_pub_
Definition: organized_multi_plane_segmentation.h:223
jsk_recognition_utils::IntegerGraphMap
std::map< int, std::vector< int > > IntegerGraphMap
ros::Publisher
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::org_polygon_pub_
ros::Publisher org_polygon_pub_
Definition: organized_multi_plane_segmentation.h:221
sample_simulate_tabletop_cloud.polygon
polygon
Definition: sample_simulate_tabletop_cloud.py:167
boost::shared_ptr
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::updateDiagnosticPlaneSegmentation
virtual void updateDiagnosticPlaneSegmentation(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: organized_multi_plane_segmentation_nodelet.cpp:871
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::pub_
ros::Publisher pub_
Definition: organized_multi_plane_segmentation.h:222
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::Config
jsk_pcl_ros::OrganizedMultiPlaneSegmentationConfig Config
Definition: organized_multi_plane_segmentation.h:134
ros.h
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::min_size_
int min_size_
Definition: organized_multi_plane_segmentation.h:237
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::ransac_refinement_time_acc_
jsk_topic_tools::TimeAccumulator ransac_refinement_time_acc_
Definition: organized_multi_plane_segmentation.h:232
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::normal_estimation_vital_checker_
jsk_topic_tools::VitalChecker::Ptr normal_estimation_vital_checker_
Definition: organized_multi_plane_segmentation.h:233
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::ransac_refine_outlier_distance_threshold_
double ransac_refine_outlier_distance_threshold_
Definition: organized_multi_plane_segmentation.h:268
geo_util.h
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::original_plane_num_counter_
jsk_recognition_utils::Counter original_plane_num_counter_
Definition: organized_multi_plane_segmentation.h:270
plane_time_ensync_for_recognition.coefficients_pub
coefficients_pub
Definition: plane_time_ensync_for_recognition.py:38
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::sub_
ros::Subscriber sub_
Definition: organized_multi_plane_segmentation.h:226
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::connect_distance_threshold_
double connect_distance_threshold_
Definition: organized_multi_plane_segmentation.h:243
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::unsubscribe
virtual void unsubscribe()
Definition: organized_multi_plane_segmentation_nodelet.cpp:202
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::ransac_refine_coefficients_
bool ransac_refine_coefficients_
Definition: organized_multi_plane_segmentation.h:267
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::publishSegmentationInformation
virtual void publishSegmentationInformation(const std_msgs::Header &header, const pcl::PointCloud< PointT >::Ptr input, ros::Publisher &indices_pub, ros::Publisher &polygon_pub, ros::Publisher &coefficients_pub, const std::vector< pcl::PointIndices > &inlier_indices, const std::vector< pcl::PointCloud< PointT > > &boundaries, const std::vector< pcl::ModelCoefficients > &model_coefficients)
Definition: organized_multi_plane_segmentation_nodelet.cpp:463
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::estimateNormal
virtual void estimateNormal(pcl::PointCloud< PointT >::Ptr input, pcl::PointCloud< pcl::Normal >::Ptr output)
Definition: organized_multi_plane_segmentation_nodelet.cpp:745
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::normal_pub_
ros::Publisher normal_pub_
Definition: organized_multi_plane_segmentation.h:224
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::refined_coefficients_pub_
ros::Publisher refined_coefficients_pub_
Definition: organized_multi_plane_segmentation.h:223
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::pointCloudToPolygon
virtual void pointCloudToPolygon(const pcl::PointCloud< PointT > &input, geometry_msgs::Polygon &polygon)
Definition: organized_multi_plane_segmentation_nodelet.cpp:334
publisher.h
diagnostic_updater.h
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::segmentOrganizedMultiPlanes
virtual void segmentOrganizedMultiPlanes(pcl::PointCloud< PointT >::Ptr input, pcl::PointCloud< pcl::Normal >::Ptr normal, PlanarRegionVector &regions, std::vector< pcl::ModelCoefficients > &model_coefficients, std::vector< pcl::PointIndices > &inlier_indices, pcl::PointCloud< pcl::Label >::Ptr &labels, std::vector< pcl::PointIndices > &label_indices, std::vector< pcl::PointIndices > &boundary_indices)
Definition: organized_multi_plane_segmentation_nodelet.cpp:437
pcl_nodelet.h
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::updateDiagnostics
virtual void updateDiagnostics(const ros::TimerEvent &event)
Definition: organized_multi_plane_segmentation_nodelet.cpp:920
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::segment
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: organized_multi_plane_segmentation_nodelet.cpp:780
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::pub_connection_marker_
ros::Publisher pub_connection_marker_
Definition: organized_multi_plane_segmentation.h:225
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::coefficients_pub_
ros::Publisher coefficients_pub_
Definition: organized_multi_plane_segmentation.h:222
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::pclIndicesArrayToClusterPointIndices
virtual void pclIndicesArrayToClusterPointIndices(const std::vector< pcl::PointIndices > &inlier_indices, const std_msgs::Header &header, jsk_recognition_msgs::ClusterPointIndices &output_indices)
Definition: organized_multi_plane_segmentation_nodelet.cpp:320
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::depth_dependent_smoothing_
bool depth_dependent_smoothing_
Definition: organized_multi_plane_segmentation.h:247
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::diagnostic_updater_
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
Definition: organized_multi_plane_segmentation.h:229
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::max_depth_change_factor_
double max_depth_change_factor_
Definition: organized_multi_plane_segmentation.h:248
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::forceToDirectOrigin
virtual void forceToDirectOrigin(const std::vector< pcl::ModelCoefficients > &coefficients, std::vector< pcl::ModelCoefficients > &output_coefficients)
Definition: organized_multi_plane_segmentation_nodelet.cpp:173
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::org_pub_
ros::Publisher org_pub_
Definition: organized_multi_plane_segmentation.h:221
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::refineBasedOnRANSAC
virtual void refineBasedOnRANSAC(const pcl::PointCloud< PointT >::Ptr input, const std::vector< pcl::PointIndices > &input_indices, const std::vector< pcl::ModelCoefficients > &input_coefficients, std::vector< pcl::PointIndices > &output_indices, std::vector< pcl::ModelCoefficients > &output_coefficients, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &output_boundaries)
Definition: organized_multi_plane_segmentation_nodelet.cpp:687
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::estimate_normal_
bool estimate_normal_
Definition: organized_multi_plane_segmentation.h:251
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::previous_checked_connection_status_for_normal_
jsk_topic_tools::ConnectionStatus previous_checked_connection_status_for_normal_
Previous checked status of connection.
Definition: organized_multi_plane_segmentation.h:257
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: organized_multi_plane_segmentation_nodelet.cpp:207
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::PointT
pcl::PointXYZRGBA PointT
Definition: organized_multi_plane_segmentation.h:130
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::segmentFromNormals
virtual void segmentFromNormals(pcl::PointCloud< PointT >::Ptr input, pcl::PointCloud< pcl::Normal >::Ptr normal, const std_msgs::Header &header)
Definition: organized_multi_plane_segmentation_nodelet.cpp:606
ros::TimerEvent
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::plane_segmentation_vital_checker_
jsk_topic_tools::VitalChecker::Ptr plane_segmentation_vital_checker_
Definition: organized_multi_plane_segmentation.h:234
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::mutex_
boost::mutex mutex_
Definition: organized_multi_plane_segmentation.h:228
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::max_refined_area_threshold_
double max_refined_area_threshold_
Definition: organized_multi_plane_segmentation.h:245
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::subscribe
virtual void subscribe()
Definition: organized_multi_plane_segmentation_nodelet.cpp:196
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::min_refined_area_threshold_
double min_refined_area_threshold_
Definition: organized_multi_plane_segmentation.h:244
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::connect_plane_angle_threshold_
double connect_plane_angle_threshold_
Definition: organized_multi_plane_segmentation.h:242
jsk_recognition_utils::Counter
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::max_curvature_
double max_curvature_
Definition: organized_multi_plane_segmentation.h:241
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::polygon_pub_
ros::Publisher polygon_pub_
Definition: organized_multi_plane_segmentation.h:222
names.h
pcl_util.h
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::concave_alpha_
double concave_alpha_
Definition: organized_multi_plane_segmentation.h:238
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::publishMarkerOfConnection
virtual void publishMarkerOfConnection(jsk_recognition_utils::IntegerGraphMap connection_map, const pcl::PointCloud< PointT >::Ptr cloud, const std::vector< pcl::PointIndices > &inliers, const std_msgs::Header &header)
Definition: organized_multi_plane_segmentation_nodelet.cpp:542
diagnostic_updater::DiagnosticStatusWrapper
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::distance_threshold_
double distance_threshold_
Definition: organized_multi_plane_segmentation.h:240
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::normal_smoothing_size_
double normal_smoothing_size_
Definition: organized_multi_plane_segmentation.h:249
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::updateDiagnosticNormalEstimation
virtual void updateDiagnosticNormalEstimation(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: organized_multi_plane_segmentation_nodelet.cpp:809
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::previous_checked_connection_status_for_plane_
jsk_topic_tools::ConnectionStatus previous_checked_connection_status_for_plane_
Previous checked status of connection for plane segmentation.
Definition: organized_multi_plane_segmentation.h:262
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::angular_threshold_
double angular_threshold_
Definition: organized_multi_plane_segmentation.h:239
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::normal_estimation_time_acc_
jsk_topic_tools::TimeAccumulator normal_estimation_time_acc_
Definition: organized_multi_plane_segmentation.h:231
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: organized_multi_plane_segmentation.h:227
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
ros::Timer
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::border_policy_ignore_
bool border_policy_ignore_
Definition: organized_multi_plane_segmentation.h:250
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::onInit
virtual void onInit()
Definition: organized_multi_plane_segmentation_nodelet.cpp:97
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::publish_normal_
bool publish_normal_
Definition: organized_multi_plane_segmentation.h:252
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::PlanarRegionVector
std::vector< pcl::PlanarRegion< PointT >, Eigen::aligned_allocator< pcl::PlanarRegion< PointT > > > PlanarRegionVector
Definition: organized_multi_plane_segmentation.h:133
ros::Subscriber
jsk_pcl_ros::OrganizedMultiPlaneSegmentation::connected_plane_num_counter_
jsk_recognition_utils::Counter connected_plane_num_counter_
Definition: organized_multi_plane_segmentation.h:271


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