edge_depth_refinement.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_EDGE_DEPTH_REFINEMENT_H_
38 #define JSK_PCL_ROS_EDGE_DEPTH_REFINEMENT_H_
39 
40 #include <pcl_ros/pcl_nodelet.h>
41 #include <sensor_msgs/PointCloud2.h>
42 #include <jsk_recognition_msgs/ClusterPointIndices.h>
43 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
44 #include <jsk_recognition_msgs/SegmentArray.h>
45 
49 
52 #include <jsk_pcl_ros/EdgeDepthRefinementConfig.h>
53 #include <dynamic_reconfigure/server.h>
54 #include <boost/tuple/tuple.hpp>
55 
56 #include <jsk_topic_tools/connection_based_nodelet.h>
57 
58 namespace jsk_pcl_ros
59 {
60  class EdgeDepthRefinement: public jsk_topic_tools::ConnectionBasedNodelet
61  {
62  public:
64  sensor_msgs::PointCloud2,
65  jsk_recognition_msgs::ClusterPointIndices > SyncPolicy;
66  typedef pcl::PointXYZRGB PointT;
67  typedef jsk_pcl_ros::EdgeDepthRefinementConfig Config;
68  virtual ~EdgeDepthRefinement();
69  protected:
71  // methods
73  virtual void onInit();
74 
75  virtual void refine(
76  const sensor_msgs::PointCloud2ConstPtr &point,
77  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices);
78 
79  virtual void removeOutliersByLine(
80  const pcl::PointCloud<PointT>::Ptr& cloud,
81  const std::vector<int>& indices,
82  pcl::PointIndices& inliers,
83  pcl::ModelCoefficients& coefficients);
84 
85  virtual void removeOutliers(
86  const pcl::PointCloud<PointT>::Ptr& cloud,
87  const std::vector<PCLIndicesMsg>& indices,
88  std::vector<pcl::PointIndices::Ptr>& output_inliers,
89  std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients);
90 
91  virtual void removeDuplicatedEdges(
92  const pcl::PointCloud<PointT>::Ptr& cloud,
93  const std::vector<pcl::PointIndices::Ptr> inliers,
94  const std::vector<pcl::ModelCoefficients::Ptr> coefficients,
95  std::vector<pcl::PointIndices::Ptr>& output_inliers,
96  std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients);
97 
99  const pcl::ModelCoefficients::Ptr coefficients);
100 
102  const pcl::PointCloud<PointT>::Ptr& cloud,
103  const std::vector<int>& indices,
105 
106  virtual void publishIndices(
108  ros::Publisher& pub_coefficients,
109  ros::Publisher& pub_edges,
110  const std::vector<pcl::PointIndices::Ptr> inliers,
111  const std::vector<pcl::ModelCoefficients::Ptr> coefficients,
112  const std_msgs::Header& header);
113 
114  virtual boost::tuple<int, int> findMinMaxIndex(
115  const int width, const int height,
116  const std::vector<int>& indices);
117 
118  virtual void integrateDuplicatedIndices(
119  const pcl::PointCloud<PointT>::Ptr& cloud,
120  const std::set<int>& duplicated_set,
121  const std::vector<pcl::PointIndices::Ptr> all_inliers,
122  pcl::PointIndices::Ptr& output_indices);
123 
124  virtual void configCallback (Config &config, uint32_t level);
125 
126  virtual void subscribe();
127  virtual void unsubscribe();
128 
130  // ROS variables
141  // outlier removal
144  int min_inliers_;
146  // duplication removal
150  private:
151 
152  };
153 }
154 
155 #endif
jsk_pcl_ros::EdgeDepthRefinement::pub_edges_
ros::Publisher pub_edges_
Definition: edge_depth_refinement.h:202
jsk_pcl_ros::EdgeDepthRefinement::segmentFromIndices
virtual jsk_recognition_utils::Segment::Ptr segmentFromIndices(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, const jsk_recognition_utils::Line::Ptr &line)
Definition: edge_depth_refinement_nodelet.cpp:204
jsk_pcl_ros::EdgeDepthRefinement::removeOutliers
virtual void removeOutliers(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< PCLIndicesMsg > &indices, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients)
Definition: edge_depth_refinement_nodelet.cpp:358
ros::Publisher
boost::shared_ptr
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::EdgeDepthRefinement::onInit
virtual void onInit()
Definition: edge_depth_refinement_nodelet.cpp:78
jsk_pcl_ros::EdgeDepthRefinement::pub_coefficients_
ros::Publisher pub_coefficients_
Definition: edge_depth_refinement.h:201
geo_util.h
jsk_pcl_ros::EdgeDepthRefinement::mutex_
boost::mutex mutex_
Definition: edge_depth_refinement.h:203
attention_pose_set.pub
pub
Definition: attention_pose_set.py:8
time_synchronizer.h
message_filters::Subscriber< sensor_msgs::PointCloud2 >
pcl_nodelet.h
jsk_pcl_ros::EdgeDepthRefinement::refine
virtual void refine(const sensor_msgs::PointCloud2ConstPtr &point, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices)
Definition: edge_depth_refinement_nodelet.cpp:446
jsk_pcl_ros::EdgeDepthRefinement::duplication_distance_threshold_
double duplication_distance_threshold_
Definition: edge_depth_refinement.h:213
jsk_pcl_ros::EdgeDepthRefinement::~EdgeDepthRefinement
virtual ~EdgeDepthRefinement()
Definition: edge_depth_refinement_nodelet.cpp:108
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::EdgeDepthRefinement::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: edge_depth_refinement.h:197
jsk_pcl_ros::EdgeDepthRefinement::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: edge_depth_refinement_nodelet.cpp:437
subscriber.h
jsk_pcl_ros::EdgeDepthRefinement::findMinMaxIndex
virtual boost::tuple< int, int > findMinMaxIndex(const int width, const int height, const std::vector< int > &indices)
Definition: edge_depth_refinement_nodelet.cpp:160
jsk_pcl_ros::EdgeDepthRefinement::Config
jsk_pcl_ros::EdgeDepthRefinementConfig Config
Definition: edge_depth_refinement.h:131
jsk_pcl_ros::EdgeDepthRefinement::lineFromCoefficients
virtual jsk_recognition_utils::Line::Ptr lineFromCoefficients(const pcl::ModelCoefficients::Ptr coefficients)
Definition: edge_depth_refinement_nodelet.cpp:147
jsk_pcl_ros::EdgeDepthRefinement::publishIndices
virtual void publishIndices(ros::Publisher &pub, ros::Publisher &pub_coefficients, ros::Publisher &pub_edges, const std::vector< pcl::PointIndices::Ptr > inliers, const std::vector< pcl::ModelCoefficients::Ptr > coefficients, const std_msgs::Header &header)
Definition: edge_depth_refinement_nodelet.cpp:398
jsk_pcl_ros::EdgeDepthRefinement::removeOutliersByLine
virtual void removeOutliersByLine(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, pcl::PointIndices &inliers, pcl::ModelCoefficients &coefficients)
Definition: edge_depth_refinement_nodelet.cpp:378
jsk_pcl_ros::EdgeDepthRefinement::duplication_angle_threshold_
double duplication_angle_threshold_
Definition: edge_depth_refinement.h:212
pcl_conversion_util.h
line
jsk_pcl_ros::EdgeDepthRefinement::subscribe
virtual void subscribe()
Definition: edge_depth_refinement_nodelet.cpp:119
jsk_pcl_ros::EdgeDepthRefinement::pub_outlier_removed_edges_
ros::Publisher pub_outlier_removed_edges_
Definition: edge_depth_refinement.h:202
jsk_pcl_ros::EdgeDepthRefinement::unsubscribe
virtual void unsubscribe()
Definition: edge_depth_refinement_nodelet.cpp:132
point
std::chrono::system_clock::time_point point
jsk_pcl_ros::EdgeDepthRefinement::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
Definition: edge_depth_refinement.h:129
jsk_pcl_ros::EdgeDepthRefinement::min_inliers_
int min_inliers_
Definition: edge_depth_refinement.h:208
jsk_pcl_ros::EdgeDepthRefinement::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: edge_depth_refinement.h:196
synchronizer.h
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::EdgeDepthRefinement::outlier_distance_threshold_
double outlier_distance_threshold_
Definition: edge_depth_refinement.h:207
jsk_pcl_ros::EdgeDepthRefinement::integrateDuplicatedIndices
virtual void integrateDuplicatedIndices(const pcl::PointCloud< PointT >::Ptr &cloud, const std::set< int > &duplicated_set, const std::vector< pcl::PointIndices::Ptr > all_inliers, pcl::PointIndices::Ptr &output_indices)
Definition: edge_depth_refinement_nodelet.cpp:222
jsk_pcl_ros::EdgeDepthRefinement::removeDuplicatedEdges
virtual void removeDuplicatedEdges(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< pcl::PointIndices::Ptr > inliers, const std::vector< pcl::ModelCoefficients::Ptr > coefficients, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients)
Definition: edge_depth_refinement_nodelet.cpp:238
jsk_pcl_ros::EdgeDepthRefinement::sub_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
Definition: edge_depth_refinement.h:198
message_filters::sync_policies::ExactTime
jsk_pcl_ros::EdgeDepthRefinement::pub_outlier_removed_indices_
ros::Publisher pub_outlier_removed_indices_
Definition: edge_depth_refinement.h:200
jsk_pcl_ros::EdgeDepthRefinement::PointT
pcl::PointXYZRGB PointT
Definition: edge_depth_refinement.h:130
jsk_pcl_ros::EdgeDepthRefinement::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: edge_depth_refinement.h:199
jsk_pcl_ros::EdgeDepthRefinement::pub_outlier_removed_coefficients_
ros::Publisher pub_outlier_removed_coefficients_
Definition: edge_depth_refinement.h:201
jsk_pcl_ros::EdgeDepthRefinement::pub_indices_
ros::Publisher pub_indices_
Definition: edge_depth_refinement.h:200


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