organized_edge_detector.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_ORGANIZED_EDGE_DETECTOR_H_
38 #define JSK_PCL_ROS_ORGANIZED_EDGE_DETECTOR_H_
39 
40 #include <pcl_ros/pcl_nodelet.h>
41 #include <sensor_msgs/PointCloud2.h>
42 #include <jsk_pcl_ros/OrganizedEdgeDetectorConfig.h>
43 #include <dynamic_reconfigure/server.h>
45 #include "jsk_topic_tools/connection_based_nodelet.h"
46 
47 namespace jsk_pcl_ros
48 {
49  class OrganizedEdgeDetector: public jsk_topic_tools::ConnectionBasedNodelet
50  {
51  public:
52  typedef pcl::PointXYZRGB PointT;
53  typedef jsk_pcl_ros::OrganizedEdgeDetectorConfig Config;
54 
55  protected:
57  // methods
59  virtual void onInit();
60  virtual void configCallback (Config &config, uint32_t level);
61  virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr& msg);
62  virtual void estimateNormal(
63  const pcl::PointCloud<PointT>::Ptr& input,
64  pcl::PointCloud<pcl::Normal>::Ptr output,
65  const std_msgs::Header& header);
66  virtual void estimateEdge(
67  const pcl::PointCloud<PointT>::Ptr& input,
68  const pcl::PointCloud<pcl::Normal>::Ptr& normal,
69  pcl::PointCloud<pcl::Label>::Ptr& output,
70  std::vector<pcl::PointIndices>& label_indices);
71  virtual void publishIndices(
73  ros::Publisher& pub_indices,
74  const pcl::PointCloud<PointT>::Ptr& cloud,
75  const std::vector<int>& indices,
76  const std_msgs::Header& header);
77  virtual void estimateStraightEdges(
78  const pcl::PointCloud<PointT>::Ptr& cloud,
79  const std::vector<int>& indices,
80  const std_msgs::Header& header,
81  std::vector<std::vector<int> >& output_indices);
82  virtual void publishStraightEdges(
83  const pcl::PointCloud<PointT>::Ptr& cloud,
84  const std_msgs::Header& header,
85  const std::vector<std::vector<int> > indices);
86 
87  virtual void subscribe();
88  virtual void unsubscribe();
89 
91  // ROS variables
106  // parameters for normal estimation
108  int estimation_method_;
111  double normal_smoothing_size_;
113  bool publish_normal_;
115  // parameters for edge detection
119  bool use_nan_boundary_;
120  bool use_occluding_;
121  bool use_occluded_;
122  bool use_curvature_;
123  bool use_rgb_;
124 
126  // straight line detection
129  double rho_;
130  double theta_;
132  double min_line_length_;
133  double max_line_gap_;
135 
136  private:
137 
138  };
139 }
140 
141 #endif
jsk_pcl_ros::OrganizedEdgeDetector::use_curvature_
bool use_curvature_
Definition: organized_edge_detector.h:186
jsk_pcl_ros::OrganizedEdgeDetector::sub_
ros::Subscriber sub_
Definition: organized_edge_detector.h:157
jsk_pcl_ros::OrganizedEdgeDetector::mutex_
boost::mutex mutex_
Definition: organized_edge_detector.h:168
ros::Publisher
jsk_pcl_ros::OrganizedEdgeDetector::pub_all_edges_indices_
ros::Publisher pub_all_edges_indices_
Definition: organized_edge_detector.h:160
jsk_pcl_ros::OrganizedEdgeDetector::use_occluded_
bool use_occluded_
Definition: organized_edge_detector.h:185
jsk_pcl_ros::OrganizedEdgeDetector::pub_normal_
ros::Publisher pub_normal_
Definition: organized_edge_detector.h:164
boost::shared_ptr
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::OrganizedEdgeDetector::pub_edge_image_
image_transport::Publisher pub_edge_image_
Definition: organized_edge_detector.h:166
jsk_pcl_ros::OrganizedEdgeDetector::pub_occluding_edges_indices_
ros::Publisher pub_occluding_edges_indices_
Definition: organized_edge_detector.h:159
jsk_pcl_ros::OrganizedEdgeDetector::rho_
double rho_
Definition: organized_edge_detector.h:193
jsk_pcl_ros::OrganizedEdgeDetector::normal_smoothing_size_
double normal_smoothing_size_
Definition: organized_edge_detector.h:175
jsk_pcl_ros::OrganizedEdgeDetector::unsubscribe
virtual void unsubscribe()
Definition: organized_edge_detector_nodelet.cpp:143
jsk_pcl_ros::OrganizedEdgeDetector::pub_all_edges_
ros::Publisher pub_all_edges_
Definition: organized_edge_detector.h:163
jsk_pcl_ros::OrganizedEdgeDetector::pub_occluded_edges_
ros::Publisher pub_occluded_edges_
Definition: organized_edge_detector.h:162
jsk_pcl_ros::OrganizedEdgeDetector::use_rgb_
bool use_rgb_
Definition: organized_edge_detector.h:187
jsk_pcl_ros::OrganizedEdgeDetector::max_line_gap_
double max_line_gap_
Definition: organized_edge_detector.h:197
jsk_pcl_ros::OrganizedEdgeDetector::estimateStraightEdges
virtual void estimateStraightEdges(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, const std_msgs::Header &header, std::vector< std::vector< int > > &output_indices)
Definition: organized_edge_detector_nodelet.cpp:288
jsk_pcl_ros::OrganizedEdgeDetector::publish_debug_image_
bool publish_debug_image_
Definition: organized_edge_detector.h:198
jsk_pcl_ros::OrganizedEdgeDetector::border_policy_ignore_
bool border_policy_ignore_
Definition: organized_edge_detector.h:173
attention_pose_set.pub
pub
Definition: attention_pose_set.py:8
jsk_pcl_ros::OrganizedEdgeDetector::estimateEdge
virtual void estimateEdge(const pcl::PointCloud< PointT >::Ptr &input, const pcl::PointCloud< pcl::Normal >::Ptr &normal, pcl::PointCloud< pcl::Label >::Ptr &output, std::vector< pcl::PointIndices > &label_indices)
Definition: organized_edge_detector_nodelet.cpp:213
jsk_pcl_ros::OrganizedEdgeDetector::depth_discontinuation_threshold_
double depth_discontinuation_threshold_
Definition: organized_edge_detector.h:181
jsk_pcl_ros::OrganizedEdgeDetector::pub_hough_image_
image_transport::Publisher pub_hough_image_
Definition: organized_edge_detector.h:166
jsk_pcl_ros::OrganizedEdgeDetector::publish_normal_
bool publish_normal_
Definition: organized_edge_detector.h:177
jsk_pcl_ros::OrganizedEdgeDetector::min_line_length_
double min_line_length_
Definition: organized_edge_detector.h:196
jsk_pcl_ros::OrganizedEdgeDetector::use_straightline_detection_
bool use_straightline_detection_
Definition: organized_edge_detector.h:192
jsk_pcl_ros::OrganizedEdgeDetector::pub_rgb_edges_indices_
ros::Publisher pub_rgb_edges_indices_
Definition: organized_edge_detector.h:160
jsk_pcl_ros::OrganizedEdgeDetector::pub_occluding_edges_
ros::Publisher pub_occluding_edges_
Definition: organized_edge_detector.h:162
jsk_pcl_ros::OrganizedEdgeDetector::pub_nan_boundary_edges_indices_
ros::Publisher pub_nan_boundary_edges_indices_
Definition: organized_edge_detector.h:158
pcl_nodelet.h
jsk_pcl_ros::OrganizedEdgeDetector::pub_straight_edges_indices_
ros::Publisher pub_straight_edges_indices_
Definition: organized_edge_detector.h:165
jsk_pcl_ros::OrganizedEdgeDetector::pub_nan_boundary_edges_
ros::Publisher pub_nan_boundary_edges_
Definition: organized_edge_detector.h:161
jsk_pcl_ros::OrganizedEdgeDetector::max_search_neighbors_
int max_search_neighbors_
Definition: organized_edge_detector.h:182
jsk_pcl_ros::OrganizedEdgeDetector::theta_
double theta_
Definition: organized_edge_detector.h:194
jsk_pcl_ros::OrganizedEdgeDetector::publishIndices
virtual void publishIndices(ros::Publisher &pub, ros::Publisher &pub_indices, const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, const std_msgs::Header &header)
Definition: organized_edge_detector_nodelet.cpp:244
jsk_pcl_ros::OrganizedEdgeDetector::estimate
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: organized_edge_detector_nodelet.cpp:347
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::OrganizedEdgeDetector::Config
jsk_pcl_ros::OrganizedEdgeDetectorConfig Config
Definition: organized_edge_detector.h:117
jsk_pcl_ros::OrganizedEdgeDetector::subscribe
virtual void subscribe()
Definition: organized_edge_detector_nodelet.cpp:138
jsk_pcl_ros::OrganizedEdgeDetector::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: organized_edge_detector.h:167
jsk_pcl_ros::OrganizedEdgeDetector::estimation_method_
int estimation_method_
Definition: organized_edge_detector.h:172
jsk_pcl_ros::OrganizedEdgeDetector::max_depth_change_factor_
double max_depth_change_factor_
Definition: organized_edge_detector.h:174
jsk_pcl_ros::OrganizedEdgeDetector::depth_dependent_smoothing_
bool depth_dependent_smoothing_
Definition: organized_edge_detector.h:176
jsk_pcl_ros::OrganizedEdgeDetector::pub_curvature_edges_indices_
ros::Publisher pub_curvature_edges_indices_
Definition: organized_edge_detector.h:160
jsk_pcl_ros::OrganizedEdgeDetector::onInit
virtual void onInit()
Definition: organized_edge_detector_nodelet.cpp:84
jsk_pcl_ros::OrganizedEdgeDetector::pub_rgb_edges_
ros::Publisher pub_rgb_edges_
Definition: organized_edge_detector.h:163
image_transport.h
jsk_pcl_ros::OrganizedEdgeDetector::pub_curvature_edges_
ros::Publisher pub_curvature_edges_
Definition: organized_edge_detector.h:163
jsk_pcl_ros::OrganizedEdgeDetector::pub_occluded_edges_indices_
ros::Publisher pub_occluded_edges_indices_
Definition: organized_edge_detector.h:159
jsk_pcl_ros::OrganizedEdgeDetector::use_nan_boundary_
bool use_nan_boundary_
Definition: organized_edge_detector.h:183
jsk_pcl_ros::OrganizedEdgeDetector::publishStraightEdges
virtual void publishStraightEdges(const pcl::PointCloud< PointT >::Ptr &cloud, const std_msgs::Header &header, const std::vector< std::vector< int > > indices)
Definition: organized_edge_detector_nodelet.cpp:270
image_transport::Publisher
jsk_pcl_ros::OrganizedEdgeDetector::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: organized_edge_detector_nodelet.cpp:188
jsk_pcl_ros::OrganizedEdgeDetector::estimateNormal
virtual void estimateNormal(const pcl::PointCloud< PointT >::Ptr &input, pcl::PointCloud< pcl::Normal >::Ptr output, const std_msgs::Header &header)
Definition: organized_edge_detector_nodelet.cpp:148
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::OrganizedEdgeDetector::use_occluding_
bool use_occluding_
Definition: organized_edge_detector.h:184
jsk_pcl_ros::OrganizedEdgeDetector::straightline_threshold_
int straightline_threshold_
Definition: organized_edge_detector.h:195
jsk_pcl_ros::OrganizedEdgeDetector::PointT
pcl::PointXYZRGB PointT
Definition: organized_edge_detector.h:116
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
ros::Subscriber


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