line_segment_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_LINE_SEGMENT_DETECTOR_H_
38 #define JSK_PCL_ROS_LINE_SEGMENT_DETECTOR_H_
39 
40 #include <pcl/segmentation/sac_segmentation.h>
41 
42 #include <jsk_topic_tools/diagnostic_nodelet.h>
48 
49 #include <jsk_recognition_msgs/ClusterPointIndices.h>
50 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
51 #include <jsk_pcl_ros/LineSegmentDetectorConfig.h>
52 #include <dynamic_reconfigure/server.h>
53 #include <visualization_msgs/Marker.h>
55 
56 namespace jsk_pcl_ros
57 {
58 
59  class LineSegment
60  {
61  public:
63  LineSegment(const std_msgs::Header& input_header,
64  pcl::PointIndices::Ptr indices,
65  pcl::ModelCoefficients::Ptr coefficients,
66  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
67  LineSegment(pcl::PointIndices::Ptr indices,
68  pcl::ModelCoefficients::Ptr coefficients);
69  virtual ~LineSegment();
70  virtual bool addMarkerLine(
71  visualization_msgs::Marker& marker,
72  const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
73  double minimum_line_length);
74  //virtual Segment::Ptr toSegment();
76  pcl::PointIndices::Ptr getIndices() { return indices_; }
77  pcl::ModelCoefficients::Ptr getCoefficients() { return coefficients_; }
78  pcl::PointCloud<pcl::PointXYZ>::Ptr getPoints() { return points_; }
79  pcl::PointCloud<pcl::PointXYZ>::Ptr getRawPoints() { return raw_points_; }
80  std_msgs::Header header;
81  protected:
82  pcl::PointIndices::Ptr indices_;
83  pcl::ModelCoefficients::Ptr coefficients_;
84  pcl::PointCloud<pcl::PointXYZ>::Ptr points_;
85  pcl::PointCloud<pcl::PointXYZ>::Ptr raw_points_;
86  private:
87 
88  };
89 
90  class LineSegmentDetector: public jsk_topic_tools::DiagnosticNodelet
91  {
92  public:
93  LineSegmentDetector(): DiagnosticNodelet("LineSegmentDetector")
94  {
95  }
97  // message_filters::Synchronizer needs to be called reset
98  // before message_filters::Subscriber is freed.
99  // Calling reset fixes the following error on shutdown of the nodelet:
100  // terminate called after throwing an instance of
101  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
102  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
103  // Also see https://github.com/ros/ros_comm/issues/720 .
104  sync_.reset();
105  async_.reset();
106  srv_.reset();
107  }
109  sensor_msgs::PointCloud2,
110  jsk_recognition_msgs::ClusterPointIndices> SyncPolicy;
112  sensor_msgs::PointCloud2,
113  jsk_recognition_msgs::ClusterPointIndices> ApproximateSyncPolicy;
114  typedef pcl::PointXYZ PointT;
115  typedef jsk_pcl_ros::LineSegmentDetectorConfig Config;
116  protected:
118  // methods
120  virtual void subscribe();
121  virtual void unsubscribe();
122  virtual void onInit();
123  virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
124  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_msg);
125  virtual void configCallback(Config &config, uint32_t level);
126  virtual void segmentLines(
127  const pcl::PointCloud<PointT>::Ptr& cloud,
128  const pcl::PointIndices::Ptr& indices,
129  std::vector<pcl::PointIndices::Ptr>& line_indices,
130  std::vector<pcl::ModelCoefficients::Ptr>& line_coefficients);
131  virtual void publishResult(
132  const std_msgs::Header& header,
133  const pcl::PointCloud<PointT>::Ptr& cloud,
134  const std::vector<LineSegment::Ptr>& segments);
136  // ROS variables
147  boost::recursive_mutex config_mutex_;
148 
150  // parameters
152  bool approximate_sync_;
153  double outlier_threshold_;
154  int max_iterations_;
155  int min_indices_;
156  double min_length_;
157  double line_width_;
158 
159  pcl::SACSegmentation<PointT> seg_;
160 
161  private:
162 
163  };
164 }
165 
166 #endif
jsk_pcl_ros::LineSegmentDetector::unsubscribe
virtual void unsubscribe()
Definition: line_segment_detector_nodelet.cpp:229
ros::Publisher
boost::shared_ptr
jsk_pcl_ros::LineSegmentDetector::publishResult
virtual void publishResult(const std_msgs::Header &header, const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< LineSegment::Ptr > &segments)
Definition: line_segment_detector_nodelet.cpp:235
jsk_pcl_ros::LineSegmentDetector::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: line_segment_detector.h:177
jsk_pcl_ros::LineSegmentDetector::outlier_threshold_
double outlier_threshold_
Definition: line_segment_detector.h:185
jsk_pcl_ros::LineSegment::raw_points_
pcl::PointCloud< pcl::PointXYZ >::Ptr raw_points_
Definition: line_segment_detector.h:149
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::LineSegmentDetector::pub_coefficients_
ros::Publisher pub_coefficients_
Definition: line_segment_detector.h:172
jsk_pcl_ros::LineSegmentDetector::min_indices_
int min_indices_
Definition: line_segment_detector.h:187
jsk_pcl_ros::LineSegmentDetector::ApproximateSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > ApproximateSyncPolicy
Definition: line_segment_detector.h:145
jsk_pcl_ros::LineSegment::toSegment
virtual jsk_recognition_utils::Line::Ptr toSegment()
Definition: line_segment_detector_nodelet.cpp:112
jsk_pcl_ros::LineSegment::getIndices
pcl::PointIndices::Ptr getIndices()
Definition: line_segment_detector.h:140
jsk_pcl_ros::LineSegment::LineSegment
LineSegment(const std_msgs::Header &input_header, pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr coefficients, pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)
Definition: line_segment_detector_nodelet.cpp:86
geo_util.h
jsk_pcl_ros::LineSegmentDetector::segmentLines
virtual void segmentLines(const pcl::PointCloud< PointT >::Ptr &cloud, const pcl::PointIndices::Ptr &indices, std::vector< pcl::PointIndices::Ptr > &line_indices, std::vector< pcl::ModelCoefficients::Ptr > &line_coefficients)
Definition: line_segment_detector_nodelet.cpp:275
jsk_pcl_ros::LineSegmentDetector::pub_line_marker_
ros::Publisher pub_line_marker_
Definition: line_segment_detector.h:170
time_synchronizer.h
jsk_pcl_ros::LineSegmentDetector::mutex_
boost::mutex mutex_
Definition: line_segment_detector.h:178
jsk_pcl_ros::LineSegmentDetector::PointT
pcl::PointXYZ PointT
Definition: line_segment_detector.h:146
jsk_pcl_ros::LineSegment::getCoefficients
pcl::ModelCoefficients::Ptr getCoefficients()
Definition: line_segment_detector.h:141
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::LineSegmentDetector::max_iterations_
int max_iterations_
Definition: line_segment_detector.h:186
jsk_pcl_ros::LineSegmentDetector::min_length_
double min_length_
Definition: line_segment_detector.h:188
jsk_pcl_ros::LineSegment::points_
pcl::PointCloud< pcl::PointXYZ >::Ptr points_
Definition: line_segment_detector.h:148
jsk_pcl_ros::LineSegmentDetector::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: line_segment_detector.h:173
jsk_pcl_ros::LineSegmentDetector::pub_indices_
ros::Publisher pub_indices_
Definition: line_segment_detector.h:171
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros::LineSegmentDetector::sub_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
Definition: line_segment_detector.h:176
jsk_pcl_ros::LineSegment::indices_
pcl::PointIndices::Ptr indices_
Definition: line_segment_detector.h:146
jsk_pcl_ros::LineSegment::Ptr
boost::shared_ptr< LineSegment > Ptr
Definition: line_segment_detector.h:126
jsk_pcl_ros::LineSegment::getPoints
pcl::PointCloud< pcl::PointXYZ >::Ptr getPoints()
Definition: line_segment_detector.h:142
jsk_pcl_ros
Definition: add_color_from_image.h:51
subscriber.h
jsk_pcl_ros::LineSegment::addMarkerLine
virtual bool addMarkerLine(visualization_msgs::Marker &marker, const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, double minimum_line_length)
Definition: line_segment_detector_nodelet.cpp:132
jsk_pcl_ros::LineSegment::~LineSegment
virtual ~LineSegment()
Definition: line_segment_detector_nodelet.cpp:108
jsk_pcl_ros::LineSegmentDetector::segment
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &cluster_msg)
Definition: line_segment_detector_nodelet.cpp:310
jsk_pcl_ros::LineSegmentDetector::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
Definition: line_segment_detector.h:142
jsk_pcl_ros::LineSegmentDetector::approximate_sync_
bool approximate_sync_
Definition: line_segment_detector.h:184
jsk_pcl_ros::LineSegment::header
std_msgs::Header header
Definition: line_segment_detector.h:144
jsk_pcl_ros::LineSegmentDetector::subscribe
virtual void subscribe()
Definition: line_segment_detector_nodelet.cpp:211
exact_time.h
jsk_pcl_ros::LineSegmentDetector::~LineSegmentDetector
~LineSegmentDetector()
Definition: line_segment_detector.h:128
jsk_pcl_ros::LineSegment::getRawPoints
pcl::PointCloud< pcl::PointXYZ >::Ptr getRawPoints()
Definition: line_segment_detector.h:143
jsk_pcl_ros::LineSegmentDetector::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: line_segment_detector.h:175
jsk_pcl_ros::LineSegmentDetector::seg_
pcl::SACSegmentation< PointT > seg_
Definition: line_segment_detector.h:191
jsk_pcl_ros::LineSegmentDetector::line_width_
double line_width_
Definition: line_segment_detector.h:189
jsk_pcl_ros::LineSegmentDetector::LineSegmentDetector
LineSegmentDetector()
Definition: line_segment_detector.h:125
synchronizer.h
approximate_time.h
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::LineSegmentDetector::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: line_segment_detector.h:174
message_filters::sync_policies::ExactTime
jsk_pcl_ros::LineSegment::coefficients_
pcl::ModelCoefficients::Ptr coefficients_
Definition: line_segment_detector.h:147
jsk_pcl_ros::LineSegmentDetector::onInit
virtual void onInit()
Definition: line_segment_detector_nodelet.cpp:164
jsk_pcl_ros::LineSegmentDetector::Config
jsk_pcl_ros::LineSegmentDetectorConfig Config
Definition: line_segment_detector.h:147
jsk_pcl_ros::LineSegmentDetector::config_mutex_
boost::recursive_mutex config_mutex_
Definition: line_segment_detector.h:179
jsk_pcl_ros::LineSegmentDetector::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: line_segment_detector_nodelet.cpp:188


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