multi_plane_extraction.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 #ifndef JSK_PCL_ROS_MULTI_PLANE_EXTRACTION_H_
36 #define JSK_PCL_ROS_MULTI_PLANE_EXTRACTION_H_
37 
38 #include <ros/ros.h>
39 #include <ros/names.h>
40 #include <pcl_ros/pcl_nodelet.h>
45 
46 #include "jsk_recognition_msgs/ClusterPointIndices.h"
47 #include "sensor_msgs/PointCloud2.h"
48 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
49 #include "jsk_recognition_msgs/PolygonArray.h"
50 #include <dynamic_reconfigure/server.h>
51 #include "jsk_pcl_ros/MultiPlaneExtractionConfig.h"
54 #include <jsk_topic_tools/vital_checker.h>
55 #include <jsk_topic_tools/diagnostic_nodelet.h>
57 
58 namespace jsk_pcl_ros
59 {
60  class MultiPlaneExtraction: public jsk_topic_tools::DiagnosticNodelet
61  {
62  public:
63 
65  sensor_msgs::PointCloud2,
66  jsk_recognition_msgs::ClusterPointIndices,
67  jsk_recognition_msgs::ModelCoefficientsArray,
68  jsk_recognition_msgs::PolygonArray> SyncPolicy;
70  sensor_msgs::PointCloud2,
71  jsk_recognition_msgs::ClusterPointIndices,
72  jsk_recognition_msgs::ModelCoefficientsArray,
73  jsk_recognition_msgs::PolygonArray> ASyncPolicy;
74  typedef jsk_pcl_ros::MultiPlaneExtractionConfig Config;
75 
76  MultiPlaneExtraction(): DiagnosticNodelet("MultiPlaneExtraction") { }
77  virtual ~MultiPlaneExtraction();
78  protected:
80  // methods
82  virtual void onInit();
83 
84  virtual void fillEmptyIndices(
85  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);
86  virtual void fillEmptyCoefficients(
87  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);
88 
89  virtual void extract(const sensor_msgs::PointCloud2::ConstPtr& input,
90  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
91  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
92  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);
93 
94  virtual void configCallback (Config &config, uint32_t level);
95 
96  virtual void updateDiagnostic(
98 
99  virtual void subscribe();
100  virtual void unsubscribe();
102  // ROS variables
116 
117 
119  // Diagnostics Variables
122 
124  // Parameters
127  bool use_async_;
128  bool keep_organized_;
130  double min_height_, max_height_;
131  bool use_indices_;
132  double magnify_;
133  bool use_sensor_frame_;
134  std::string sensor_frame_;
135  bool use_coefficients_;
136  private:
137 
138 
139  };
140 }
141 
142 #endif
jsk_pcl_ros::MultiPlaneExtraction::magnify_
double magnify_
Definition: multi_plane_extraction.h:196
jsk_pcl_ros::MultiPlaneExtraction::mutex_
boost::mutex mutex_
Definition: multi_plane_extraction.h:168
ros::Publisher
pass_through.h
boost::shared_ptr
jsk_pcl_ros::MultiPlaneExtraction::max_height_
double max_height_
Definition: multi_plane_extraction.h:194
jsk_pcl_ros::MultiPlaneExtraction::sub_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
Definition: multi_plane_extraction.h:175
jsk_pcl_ros::MultiPlaneExtraction::use_sensor_frame_
bool use_sensor_frame_
Definition: multi_plane_extraction.h:197
jsk_pcl_ros::MultiPlaneExtraction::Config
jsk_pcl_ros::MultiPlaneExtractionConfig Config
Definition: multi_plane_extraction.h:138
ros.h
jsk_pcl_ros::MultiPlaneExtraction::tf_listener_
tf::TransformListener * tf_listener_
Definition: multi_plane_extraction.h:190
jsk_pcl_ros::MultiPlaneExtraction::min_height_
double min_height_
Definition: multi_plane_extraction.h:194
jsk_pcl_ros::MultiPlaneExtraction::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: multi_plane_extraction.h:173
jsk_pcl_ros::MultiPlaneExtraction::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: multi_plane_extraction.h:178
time_synchronizer.h
tf_listener_singleton.h
jsk_pcl_ros::MultiPlaneExtraction::pub_
ros::Publisher pub_
Definition: multi_plane_extraction.h:169
jsk_pcl_ros::MultiPlaneExtraction::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray, jsk_recognition_msgs::PolygonArray > SyncPolicy
Definition: multi_plane_extraction.h:132
jsk_pcl_ros::MultiPlaneExtraction::async_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
Definition: multi_plane_extraction.h:179
jsk_pcl_ros::MultiPlaneExtraction::MultiPlaneExtraction
MultiPlaneExtraction()
Definition: multi_plane_extraction.h:140
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::MultiPlaneExtraction::subscribe
virtual void subscribe()
Definition: multi_plane_extraction_nodelet.cpp:133
jsk_pcl_ros::MultiPlaneExtraction::sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
Definition: multi_plane_extraction.h:174
pcl_nodelet.h
jsk_pcl_ros::MultiPlaneExtraction::use_async_
bool use_async_
Definition: multi_plane_extraction.h:191
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros::MultiPlaneExtraction::extract
virtual void extract(const sensor_msgs::PointCloud2::ConstPtr &input, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
Definition: multi_plane_extraction_nodelet.cpp:256
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::MultiPlaneExtraction::plane_counter_
jsk_recognition_utils::Counter plane_counter_
Definition: multi_plane_extraction.h:185
jsk_pcl_ros::MultiPlaneExtraction::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: multi_plane_extraction.h:171
jsk_pcl_ros::MultiPlaneExtraction::pub_indices_
ros::Publisher pub_indices_
Definition: multi_plane_extraction.h:170
jsk_pcl_ros::MultiPlaneExtraction::use_indices_
bool use_indices_
Definition: multi_plane_extraction.h:195
jsk_pcl_ros::MultiPlaneExtraction::null_coefficients_
message_filters::PassThrough< jsk_recognition_msgs::ModelCoefficientsArray > null_coefficients_
Definition: multi_plane_extraction.h:177
jsk_pcl_ros::MultiPlaneExtraction::keep_organized_
bool keep_organized_
Definition: multi_plane_extraction.h:192
pcl_conversion_util.h
jsk_recognition_utils::Counter
names.h
message_filters::PassThrough< jsk_recognition_msgs::ClusterPointIndices >
jsk_pcl_ros::MultiPlaneExtraction::unsubscribe
virtual void unsubscribe()
Definition: multi_plane_extraction_nodelet.cpp:191
pcl_util.h
jsk_pcl_ros::MultiPlaneExtraction::sensor_frame_
std::string sensor_frame_
Definition: multi_plane_extraction.h:198
jsk_pcl_ros::MultiPlaneExtraction::null_indices_
message_filters::PassThrough< jsk_recognition_msgs::ClusterPointIndices > null_indices_
Definition: multi_plane_extraction.h:176
jsk_pcl_ros::MultiPlaneExtraction::use_coefficients_
bool use_coefficients_
Definition: multi_plane_extraction.h:199
tf::TransformListener
jsk_pcl_ros::MultiPlaneExtraction::updateDiagnostic
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: multi_plane_extraction_nodelet.cpp:223
synchronizer.h
jsk_pcl_ros::MultiPlaneExtraction::nonplane_pub_
ros::Publisher nonplane_pub_
Definition: multi_plane_extraction.h:169
diagnostic_updater::DiagnosticStatusWrapper
approximate_time.h
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
jsk_pcl_ros::MultiPlaneExtraction::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: multi_plane_extraction_nodelet.cpp:203
message_filters::sync_policies::ExactTime
jsk_pcl_ros::MultiPlaneExtraction::ASyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray, jsk_recognition_msgs::PolygonArray > ASyncPolicy
Definition: multi_plane_extraction.h:137
jsk_pcl_ros::MultiPlaneExtraction::~MultiPlaneExtraction
virtual ~MultiPlaneExtraction()
Definition: multi_plane_extraction_nodelet.cpp:121
jsk_pcl_ros::MultiPlaneExtraction::fillEmptyCoefficients
virtual void fillEmptyCoefficients(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
Definition: multi_plane_extraction_nodelet.cpp:246
jsk_pcl_ros::MultiPlaneExtraction::fillEmptyIndices
virtual void fillEmptyIndices(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
Definition: multi_plane_extraction_nodelet.cpp:236
jsk_pcl_ros::MultiPlaneExtraction::onInit
virtual void onInit()
Definition: multi_plane_extraction_nodelet.cpp:81
jsk_pcl_ros::MultiPlaneExtraction::maximum_queue_size_
int maximum_queue_size_
Definition: multi_plane_extraction.h:193
jsk_pcl_ros::MultiPlaneExtraction::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: multi_plane_extraction.h:172


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