plane_concatenator.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_UTILS_PLANE_CONCATENATOR_H_
38 #define JSK_PCL_ROS_UTILS_PLANE_CONCATENATOR_H_
39 
40 #include <jsk_recognition_msgs/PolygonArray.h>
41 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
42 #include <jsk_recognition_msgs/ClusterPointIndices.h>
43 
44 #include <jsk_pcl_ros_utils/PlaneConcatenatorConfig.h>
45 #include <dynamic_reconfigure/server.h>
46 #include <jsk_topic_tools/diagnostic_nodelet.h>
50 
52 
53 namespace jsk_pcl_ros_utils
54 {
55  class PlaneConcatenator: public jsk_topic_tools::DiagnosticNodelet
56  {
57  public:
59  typedef PlaneConcatenatorConfig Config;
60  typedef pcl::PointXYZRGB PointT;
62  sensor_msgs::PointCloud2,
63  jsk_recognition_msgs::ClusterPointIndices,
64  jsk_recognition_msgs::PolygonArray,
65  jsk_recognition_msgs::ModelCoefficientsArray
66  > SyncPolicy;
67  PlaneConcatenator(): DiagnosticNodelet("PlaneConcatenator") {}
68  virtual ~PlaneConcatenator();
69  protected:
71  // methods
73  virtual void onInit();
74  virtual void subscribe();
75  virtual void unsubscribe();
76  virtual void concatenate(
77  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
78  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
79  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_array_msg,
80  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_array_msg);
81  virtual void configCallback(Config &config, uint32_t level);
82  virtual bool isNearPointCloud(
83  pcl::KdTreeFLANN<PointT>& kdtree,
84  pcl::PointCloud<PointT>::Ptr cloud,
86  virtual pcl::ModelCoefficients::Ptr refinement(
87  pcl::PointCloud<PointT>::Ptr cloud,
88  pcl::PointIndices::Ptr indices,
89  pcl::ModelCoefficients::Ptr original_coefficients);
90  virtual void forceToDirectOrigin(
91  const pcl::ModelCoefficients::Ptr& coefficients,
92  pcl::ModelCoefficients::Ptr& output_coefficients);
94  // ROS variables
101  boost::mutex mutex_;
107  // parameters
116  int min_size_;
117  double min_area_;
118  double max_area_;
119  private:
120 
121  };
122 }
123 #endif
jsk_pcl_ros_utils::PlaneConcatenator::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: plane_concatenator.h:163
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
jsk_pcl_ros_utils::PlaneConcatenator::PlaneConcatenator
PlaneConcatenator()
Definition: plane_concatenator.h:131
jsk_pcl_ros_utils::PlaneConcatenator::mutex_
boost::mutex mutex_
Definition: plane_concatenator.h:165
jsk_pcl_ros_utils::PlaneConcatenator::sub_polygon_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
Definition: plane_concatenator.h:162
jsk_pcl_ros_utils::PlaneConcatenator::pub_indices_
ros::Publisher pub_indices_
Definition: plane_concatenator.h:167
ros::Publisher
jsk_pcl_ros_utils::PlaneConcatenator::connect_distance_threshold_
double connect_distance_threshold_
Definition: plane_concatenator.h:174
boost::shared_ptr
jsk_pcl_ros_utils::PlaneConcatenator::connect_angular_threshold_
double connect_angular_threshold_
Definition: plane_concatenator.h:173
geo_util.h
jsk_pcl_ros_utils::PlaneConcatenator::unsubscribe
virtual void unsubscribe()
Definition: plane_concatenator_nodelet.cpp:90
jsk_pcl_ros_utils::PlaneConcatenator::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: plane_concatenator_nodelet.cpp:269
time_synchronizer.h
jsk_pcl_ros_utils::PlaneConcatenator::onInit
virtual void onInit()
Definition: plane_concatenator_nodelet.cpp:46
sample_camera_info_and_pointcloud_publisher.cloud
cloud
Definition: sample_camera_info_and_pointcloud_publisher.py:30
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros_utils::PlaneConcatenator::connect_perpendicular_distance_threshold_
double connect_perpendicular_distance_threshold_
Definition: plane_concatenator.h:175
jsk_pcl_ros_utils::PlaneConcatenator::pub_coefficients_
ros::Publisher pub_coefficients_
Definition: plane_concatenator.h:169
jsk_pcl_ros_utils::PlaneConcatenator::PointT
pcl::PointXYZRGB PointT
Definition: plane_concatenator.h:124
jsk_pcl_ros_utils::PlaneConcatenator::Ptr
boost::shared_ptr< PlaneConcatenator > Ptr
Definition: plane_concatenator.h:122
subscriber.h
jsk_pcl_ros_utils::PlaneConcatenator::refinement
virtual pcl::ModelCoefficients::Ptr refinement(pcl::PointCloud< PointT >::Ptr cloud, pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr original_coefficients)
Definition: plane_concatenator_nodelet.cpp:206
jsk_pcl_ros_utils::PlaneConcatenator::pub_polygon_
ros::Publisher pub_polygon_
Definition: plane_concatenator.h:168
jsk_pcl_ros_utils::PlaneConcatenator::concatenate
virtual void concatenate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_array_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_array_msg)
Definition: plane_concatenator_nodelet.cpp:98
jsk_pcl_ros_utils::PlaneConcatenator::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: plane_concatenator.h:166
jsk_pcl_ros_utils::PlaneConcatenator::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: plane_concatenator.h:164
jsk_pcl_ros_utils::PlaneConcatenator::min_size_
int min_size_
Definition: plane_concatenator.h:180
jsk_pcl_ros_utils::PlaneConcatenator::forceToDirectOrigin
virtual void forceToDirectOrigin(const pcl::ModelCoefficients::Ptr &coefficients, pcl::ModelCoefficients::Ptr &output_coefficients)
Definition: plane_concatenator_nodelet.cpp:285
jsk_pcl_ros_utils::PlaneConcatenator::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: plane_concatenator.h:160
jsk_pcl_ros_utils::PlaneConcatenator::ransac_refinement_eps_distance_
double ransac_refinement_eps_distance_
Definition: plane_concatenator.h:178
jsk_pcl_ros_utils::PlaneConcatenator::~PlaneConcatenator
virtual ~PlaneConcatenator()
Definition: plane_concatenator_nodelet.cpp:66
jsk_pcl_ros_utils::PlaneConcatenator::min_area_
double min_area_
Definition: plane_concatenator.h:181
jsk_pcl_ros_utils::PlaneConcatenator::subscribe
virtual void subscribe()
Definition: plane_concatenator_nodelet.cpp:77
jsk_pcl_ros_utils::PlaneConcatenator::ransac_refinement_max_iteration_
int ransac_refinement_max_iteration_
Definition: plane_concatenator.h:176
synchronizer.h
jsk_pcl_ros_utils::PlaneConcatenator::ransac_refinement_eps_angle_
double ransac_refinement_eps_angle_
Definition: plane_concatenator.h:179
message_filters::sync_policies::ExactTime
jsk_pcl_ros_utils::PlaneConcatenator::Config
PlaneConcatenatorConfig Config
Definition: plane_concatenator.h:123
jsk_pcl_ros_utils::PlaneConcatenator::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
Definition: plane_concatenator.h:130
jsk_pcl_ros_utils::PlaneConcatenator::ransac_refinement_outlier_threshold_
double ransac_refinement_outlier_threshold_
Definition: plane_concatenator.h:177
jsk_pcl_ros_utils::PlaneConcatenator::isNearPointCloud
virtual bool isNearPointCloud(pcl::KdTreeFLANN< PointT > &kdtree, pcl::PointCloud< PointT >::Ptr cloud, jsk_recognition_utils::Plane::Ptr target_plane)
Definition: plane_concatenator_nodelet.cpp:242
jsk_pcl_ros_utils::PlaneConcatenator::sub_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
Definition: plane_concatenator.h:161
jsk_pcl_ros_utils::PlaneConcatenator::max_area_
double max_area_
Definition: plane_concatenator.h:182


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43