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/o2r 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>
46 
47 namespace jsk_pcl_ros
48 {
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
115  // parameters for edge detection
123  bool use_rgb_;
124 
126  // straight line detection
129  double rho_;
130  double theta_;
135 
136  private:
137 
138  };
139 }
140 
141 #endif
image_transport::Publisher pub_hough_image_
virtual void estimateNormal(const pcl::PointCloud< PointT >::Ptr &input, pcl::PointCloud< pcl::Normal >::Ptr output, const std_msgs::Header &header)
image_transport::Publisher pub_edge_image_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
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)
virtual void configCallback(Config &config, uint32_t level)
jsk_pcl_ros::OrganizedEdgeDetectorConfig Config
boost::mutex mutex
global mutex.
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &msg)
virtual void publishStraightEdges(const pcl::PointCloud< PointT >::Ptr &cloud, const std_msgs::Header &header, const std::vector< std::vector< int > > indices)
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)
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)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47