edgebased_cube_finder.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_BASED_CUBE_FINDER_H_
38 #define JSK_PCL_ROS_EDGE_BASED_CUBE_FINDER_H_
39 
40 #include <pcl_ros/pcl_nodelet.h>
41 
43 // messages
45 #include <sensor_msgs/PointCloud2.h>
46 #include <jsk_recognition_msgs/ParallelEdge.h>
47 #include <jsk_recognition_msgs/PolygonArray.h>
48 #include <jsk_recognition_msgs/BoundingBoxArray.h>
49 #include <jsk_recognition_msgs/ParallelEdgeArray.h>
50 
54 
58 
59 #include <boost/tuple/tuple.hpp>
60 #include <jsk_pcl_ros/EdgebasedCubeFinderConfig.h>
61 #include <dynamic_reconfigure/server.h>
62 
63 #include <jsk_topic_tools/connection_based_nodelet.h>
64 
65 namespace jsk_pcl_ros
66 {
67  typedef boost::tuple<pcl::PointIndices::Ptr, pcl::PointIndices::Ptr>
69  typedef boost::tuple<pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr>
71 
72  typedef boost::tuple<pcl::PointIndices::Ptr, pcl::PointIndices::Ptr, pcl::PointIndices::Ptr>
74  typedef boost::tuple<pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr>
76  typedef boost::tuple<IndicesTriple, CoefficientsTriple>
78 
80  // class to represent a hypothesis
81  // value_ := 0.0 ~ 1.0
83  class CubeHypothesis
84  {
85  public:
87  CubeHypothesis(const IndicesPair& pair,
88  const CoefficientsPair& coefficients_pair,
89  const double outlier_threshold);
90  virtual ~CubeHypothesis();
91  virtual double getValue() { return value_; };
92  virtual jsk_recognition_utils::Cube::Ptr getCube() { return cube_; };
93  virtual void estimate(const pcl::PointCloud<pcl::PointXYZRGB>& cloud) = 0;
94 
95  virtual double evaluatePointOnPlanes(
96  const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
101  const jsk_recognition_utils::PointPair& a_candidates,
102  const jsk_recognition_utils::PointPair& b_candidates);
103  protected:
105  // methods
107  virtual void computeCentroid(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr& cloud,
108  const pcl::PointIndices::Ptr& indices,
109  Eigen::Vector3f& output);
110  virtual void getLinePoints(const jsk_recognition_utils::Line& line,
111  const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
112  const pcl::PointIndices::Ptr indices,
116 
118  // variables
120  double value_;
125  private:
126  };
127 
129  {
130  public:
132  PlanarCubeHypothesis(const IndicesPair& pair,
133  const CoefficientsPair& coefficients_pair,
134  const double outlier_threshold);
135  virtual void estimate(const pcl::PointCloud<pcl::PointXYZRGB>& cloud)
136  {
137  }
138 
139  protected:
140  private:
141  };
142 
143  class DiagnoalCubeHypothesis: public CubeHypothesis
144  {
145  public:
148  const CoefficientsPair& coefficients_pair,
149  const double outlier_threshold);
150  virtual void estimate(const pcl::PointCloud<pcl::PointXYZRGB>& cloud);
151  protected:
153  double min_angle_;
154  private:
155  };
156 
157  class EdgebasedCubeFinder: public jsk_topic_tools::ConnectionBasedNodelet
158  {
159  public:
161  sensor_msgs::PointCloud2,
162  jsk_recognition_msgs::ParallelEdgeArray > SyncPolicy;
163  typedef pcl::PointXYZRGB PointT;
164  typedef jsk_pcl_ros::EdgebasedCubeFinderConfig Config;
165  enum EdgeRelation
166  {
171  };
172  virtual ~EdgebasedCubeFinder();
173  protected:
174 
175 
177  // methods
179  virtual void onInit();
180 
181  virtual void estimate(
182  const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
183  const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr& input_edges);
184  virtual void estimate2(
185  const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
186  const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr& input_edges);
187 
189  // combinateIndices
190  // indices := list of pcl::PointIndices. the length of the
191  // list should be greater equal than 2.
193  virtual std::vector<IndicesPair> combinateIndices(
194  const std::vector<pcl::PointIndices::Ptr>& indices);
195 
196  virtual std::vector<CoefficientsPair> combinateCoefficients(
197  const std::vector<pcl::ModelCoefficients::Ptr>& coefficients);
198 
199  virtual bool isPerpendicularVector(
200  const Eigen::Vector3f& a,
201  const Eigen::Vector3f& b);
202 
203  virtual std::vector<IndicesCoefficientsTriple>
205  const std::vector<pcl::PointIndices::Ptr>& indices,
206  const std::vector<pcl::ModelCoefficients::Ptr>& coefficients);
207 
209  const jsk_recognition_utils::Line& edge_a,
210  const jsk_recognition_utils::Line& edge_b,
211  const jsk_recognition_utils::Line& edge_c);
212 
213 
214  virtual std::vector<IndicesCoefficientsTriple>
216  const std::vector<IndicesCoefficientsTriple>& triples);
217 
219  const CoefficientsPair& pair);
220 
222  const pcl::PointCloud<PointT>::Ptr cloud,
223  const CoefficientsPair& coefficients_pair,
224  const IndicesPair& indices_pair);
225  virtual int countInliers(
226  const pcl::PointCloud<PointT>::Ptr cloud,
228  virtual void filterBasedOnConvex(
229  const pcl::PointCloud<PointT>::Ptr cloud,
230  const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes,
231  std::vector<int>& output_indices);
233  const std::vector<IndicesPair>& pairs,
234  const std::vector<CoefficientsPair>& coefficients_pair,
235  std::vector<IndicesPair>& filtered_indices_pairs,
236  std::vector<CoefficientsPair>& filtered_coefficients_pairs);
237 
239  const pcl::PointCloud<PointT>::Ptr cloud,
240  const IndicesCoefficientsTriple& indices_coefficients_triple,
241  pcl::PointCloud<EdgebasedCubeFinder::PointT>::Ptr points_on_edge);
242 
243  virtual pcl::PointCloud<PointT>::Ptr extractPointCloud(
244  const pcl::PointCloud<PointT>::Ptr cloud,
245  const pcl::PointIndices::Ptr indices);
246 
249  const pcl::PointCloud<PointT>::Ptr cloud);
250 
251  virtual void estimateParallelPlane(
253  const pcl::PointCloud<PointT>::Ptr filtered_cloud,
254  pcl::PointIndices::Ptr output_inliers,
255  pcl::ModelCoefficients::Ptr output_coefficients);
256 
257  virtual void estimatePerpendicularPlane(
259  const CoefficientsPair& edge_coefficients,
260  const pcl::PointCloud<PointT>::Ptr filtered_cloud,
261  pcl::PointIndices::Ptr output_inliers,
262  pcl::ModelCoefficients::Ptr output_coefficients);
263 
264  //virtual pcl::PointCloud<EdgebasedCubeFinder::PointT>::Ptr
265  virtual pcl::PointIndices::Ptr
268  const CoefficientsPair& edge_coefficients_pair,
269  const pcl::PointCloud<PointT>::Ptr cloud);
270 
273  const pcl::PointCloud<PointT>::Ptr cloud,
274  const pcl::PointIndices::Ptr indices,
275  pcl::ModelCoefficients::Ptr coefficients,
276  pcl::PointIndices::Ptr inliers);
277 
278  virtual void configCallback (Config &config, uint32_t level);
279 
280  virtual void subscribe();
281  virtual void unsubscribe();
283  // ROS variables
295  // parameters for cube finnding
297  double outlier_threshold_;
298  double min_inliers_;
299  double convex_area_threshold_;
300  double convex_edge_threshold_;
302  private:
303 
304  };
305 }
306 
307 #endif
jsk_pcl_ros::DiagnoalCubeHypothesis::resolution_
int resolution_
Definition: edgebased_cube_finder.h:184
jsk_pcl_ros::CoefficientsPair
boost::tuple< pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr > CoefficientsPair
Definition: edgebased_cube_finder.h:102
jsk_pcl_ros::EdgebasedCubeFinder::minMaxPointOnLine
virtual jsk_recognition_utils::PointPair minMaxPointOnLine(const jsk_recognition_utils::Line &line, const pcl::PointCloud< PointT >::Ptr cloud)
Definition: edgebased_cube_finder_nodelet.cpp:495
jsk_pcl_ros::EdgebasedCubeFinder::pub_debug_polygons_
ros::Publisher pub_debug_polygons_
Definition: edgebased_cube_finder.h:324
ros::Publisher
jsk_recognition_utils::ConvexPolygon
jsk_pcl_ros::EdgebasedCubeFinder::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ParallelEdgeArray > SyncPolicy
Definition: edgebased_cube_finder.h:194
jsk_pcl_ros::EdgebasedCubeFinder::convex_edge_threshold_
double convex_edge_threshold_
Definition: edgebased_cube_finder.h:332
jsk_pcl_ros::CubeHypothesis::value_
double value_
Definition: edgebased_cube_finder.h:152
jsk_pcl_ros::CubeHypothesis::buildConvexPolygon
virtual jsk_recognition_utils::ConvexPolygon::Ptr buildConvexPolygon(const jsk_recognition_utils::PointPair &a_edge_pair, const jsk_recognition_utils::PointPair &b_edge_pair)
Definition: edgebased_cube_finder_nodelet.cpp:139
boost::shared_ptr
jsk_pcl_ros::EdgebasedCubeFinder::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: edgebased_cube_finder.h:318
jsk_pcl_ros::CubeHypothesis::estimate
virtual void estimate(const pcl::PointCloud< pcl::PointXYZRGB > &cloud)=0
jsk_pcl_ros::CubeHypothesis::evaluatePointOnPlanes
virtual double evaluatePointOnPlanes(const pcl::PointCloud< pcl::PointXYZRGB > &cloud, jsk_recognition_utils::ConvexPolygon &polygon_a, jsk_recognition_utils::ConvexPolygon &polygon_b)
Definition: edgebased_cube_finder_nodelet.cpp:156
jsk_pcl_ros::EdgebasedCubeFinder::cubeFromIndicesAndCoefficients
virtual jsk_recognition_utils::Cube::Ptr cubeFromIndicesAndCoefficients(const pcl::PointCloud< PointT >::Ptr cloud, const IndicesCoefficientsTriple &indices_coefficients_triple, pcl::PointCloud< EdgebasedCubeFinder::PointT >::Ptr points_on_edge)
Definition: edgebased_cube_finder_nodelet.cpp:639
jsk_pcl_ros::CubeHypothesis::computeAxisEndPoints
virtual jsk_recognition_utils::PointPair computeAxisEndPoints(const jsk_recognition_utils::Line &axis, const jsk_recognition_utils::PointPair &a_candidates, const jsk_recognition_utils::PointPair &b_candidates)
Definition: edgebased_cube_finder_nodelet.cpp:180
jsk_pcl_ros::EdgebasedCubeFinder::countInliers
virtual int countInliers(const pcl::PointCloud< PointT >::Ptr cloud, const jsk_recognition_utils::ConvexPolygon::Ptr convex)
Definition: edgebased_cube_finder_nodelet.cpp:365
jsk_pcl_ros::EdgebasedCubeFinder::filterPairsBasedOnParallelEdgeDistances
virtual void filterPairsBasedOnParallelEdgeDistances(const std::vector< IndicesPair > &pairs, const std::vector< CoefficientsPair > &coefficients_pair, std::vector< IndicesPair > &filtered_indices_pairs, std::vector< CoefficientsPair > &filtered_coefficients_pairs)
Definition: edgebased_cube_finder_nodelet.cpp:536
jsk_pcl_ros::IndicesPair
boost::tuple< pcl::PointIndices::Ptr, pcl::PointIndices::Ptr > IndicesPair
Definition: edgebased_cube_finder.h:100
jsk_pcl_ros::EdgebasedCubeFinder::sub_edges_
message_filters::Subscriber< jsk_recognition_msgs::ParallelEdgeArray > sub_edges_
Definition: edgebased_cube_finder.h:320
jsk_pcl_ros::EdgebasedCubeFinder::min_inliers_
double min_inliers_
Definition: edgebased_cube_finder.h:330
jsk_pcl_ros::PlanarCubeHypothesis::estimate
virtual void estimate(const pcl::PointCloud< pcl::PointXYZRGB > &cloud)
Definition: edgebased_cube_finder.h:167
geo_util.h
jsk_pcl_ros::CubeHypothesis::~CubeHypothesis
virtual ~CubeHypothesis()
Definition: edgebased_cube_finder_nodelet.cpp:98
time_synchronizer.h
jsk_pcl_ros::CubeHypothesis::CubeHypothesis
CubeHypothesis(const IndicesPair &pair, const CoefficientsPair &coefficients_pair, const double outlier_threshold)
Definition: edgebased_cube_finder_nodelet.cpp:89
jsk_pcl_ros::EdgebasedCubeFinder::combinateCoefficients
virtual std::vector< CoefficientsPair > combinateCoefficients(const std::vector< pcl::ModelCoefficients::Ptr > &coefficients)
Definition: edgebased_cube_finder_nodelet.cpp:1257
jsk_pcl_ros::EdgebasedCubeFinder::filterBasedOnConvex
virtual void filterBasedOnConvex(const pcl::PointCloud< PointT >::Ptr cloud, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes, std::vector< int > &output_indices)
Definition: edgebased_cube_finder_nodelet.cpp:382
jsk_pcl_ros::CubeHypothesis::outlier_threshold_
double outlier_threshold_
Definition: edgebased_cube_finder.h:155
jsk_pcl_ros::EdgebasedCubeFinder::B_PERPENDICULAR
@ B_PERPENDICULAR
Definition: edgebased_cube_finder.h:201
jsk_pcl_ros::CubeHypothesis::computeCentroid
virtual void computeCentroid(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointIndices::Ptr &indices, Eigen::Vector3f &output)
Definition: edgebased_cube_finder_nodelet.cpp:102
cloud
cloud
jsk_pcl_ros::EdgebasedCubeFinder::isPerpendicularVector
virtual bool isPerpendicularVector(const Eigen::Vector3f &a, const Eigen::Vector3f &b)
Definition: edgebased_cube_finder_nodelet.cpp:812
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::EdgebasedCubeFinder::C_PERPENDICULAR
@ C_PERPENDICULAR
Definition: edgebased_cube_finder.h:202
jsk_pcl_ros::EdgebasedCubeFinder::NOT_PERPENDICULAR
@ NOT_PERPENDICULAR
Definition: edgebased_cube_finder.h:199
jsk_pcl_ros::EdgebasedCubeFinder::outlier_threshold_
double outlier_threshold_
Definition: edgebased_cube_finder.h:329
pcl_nodelet.h
jsk_pcl_ros::EdgebasedCubeFinder::perpendicularEdgeTriple
virtual EdgeRelation perpendicularEdgeTriple(const jsk_recognition_utils::Line &edge_a, const jsk_recognition_utils::Line &edge_b, const jsk_recognition_utils::Line &edge_c)
Definition: edgebased_cube_finder_nodelet.cpp:832
jsk_pcl_ros::EdgebasedCubeFinder::estimate
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr &input_edges)
Definition: edgebased_cube_finder_nodelet.cpp:750
jsk_pcl_ros::DiagnoalCubeHypothesis::estimate
virtual void estimate(const pcl::PointCloud< pcl::PointXYZRGB > &cloud)
Definition: edgebased_cube_finder_nodelet.cpp:237
jsk_pcl_ros::EdgebasedCubeFinder::Config
jsk_pcl_ros::EdgebasedCubeFinderConfig Config
Definition: edgebased_cube_finder.h:196
jsk_pcl_ros::EdgebasedCubeFinder::parallel_edge_distance_max_threshold_
double parallel_edge_distance_max_threshold_
Definition: edgebased_cube_finder.h:333
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::EdgebasedCubeFinder::subscribe
virtual void subscribe()
Definition: edgebased_cube_finder_nodelet.cpp:454
jsk_pcl_ros::CubeHypothesis
Definition: edgebased_cube_finder.h:115
jsk_pcl_ros::EdgebasedCubeFinder::parallel_edge_distance_min_threshold_
double parallel_edge_distance_min_threshold_
Definition: edgebased_cube_finder.h:333
jsk_pcl_ros::EdgebasedCubeFinder::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: edgebased_cube_finder.h:319
subscriber.h
jsk_pcl_ros::PlanarCubeHypothesis::Ptr
boost::shared_ptr< PlanarCubeHypothesis > Ptr
Definition: edgebased_cube_finder.h:163
jsk_pcl_ros::CubeHypothesis::getLinePoints
virtual void getLinePoints(const jsk_recognition_utils::Line &line, const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const pcl::PointIndices::Ptr indices, jsk_recognition_utils::Vertices &output)
Definition: edgebased_cube_finder_nodelet.cpp:118
jsk_pcl_ros::EdgebasedCubeFinder::midLineFromCoefficientsPair
virtual jsk_recognition_utils::Line::Ptr midLineFromCoefficientsPair(const CoefficientsPair &pair)
Definition: edgebased_cube_finder_nodelet.cpp:473
jsk_pcl_ros::EdgebasedCubeFinder::pub_pose_array_
ros::Publisher pub_pose_array_
Definition: edgebased_cube_finder.h:322
jsk_pcl_ros::EdgebasedCubeFinder::onInit
virtual void onInit()
Definition: edgebased_cube_finder_nodelet.cpp:414
jsk_pcl_ros::CubeHypothesis::coefficients_pair_
const CoefficientsPair coefficients_pair_
Definition: edgebased_cube_finder.h:154
pcl_conversion_util.h
line
jsk_pcl_ros::EdgebasedCubeFinder::filterPerpendicularEdgeTriples
virtual std::vector< IndicesCoefficientsTriple > filterPerpendicularEdgeTriples(const std::vector< IndicesCoefficientsTriple > &triples)
Definition: edgebased_cube_finder_nodelet.cpp:865
jsk_pcl_ros::IndicesCoefficientsTriple
boost::tuple< IndicesTriple, CoefficientsTriple > IndicesCoefficientsTriple
Definition: edgebased_cube_finder.h:109
jsk_pcl_ros::EdgebasedCubeFinder::PointT
pcl::PointXYZRGB PointT
Definition: edgebased_cube_finder.h:195
jsk_pcl_ros::EdgebasedCubeFinder::estimateConvexPolygon
virtual jsk_recognition_utils::ConvexPolygon::Ptr estimateConvexPolygon(const pcl::PointCloud< PointT >::Ptr cloud, const pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr coefficients, pcl::PointIndices::Ptr inliers)
Definition: edgebased_cube_finder_nodelet.cpp:1214
jsk_pcl_ros::EdgebasedCubeFinder::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: edgebased_cube_finder_nodelet.cpp:403
jsk_pcl_ros::EdgebasedCubeFinder::tripleIndicesAndCoefficients
virtual std::vector< IndicesCoefficientsTriple > tripleIndicesAndCoefficients(const std::vector< pcl::PointIndices::Ptr > &indices, const std::vector< pcl::ModelCoefficients::Ptr > &coefficients)
Definition: edgebased_cube_finder_nodelet.cpp:1179
jsk_pcl_ros::EdgebasedCubeFinder::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: edgebased_cube_finder.h:317
jsk_pcl_ros::EdgebasedCubeFinder::convexFromPairs
virtual jsk_recognition_utils::ConvexPolygon::Ptr convexFromPairs(const pcl::PointCloud< PointT >::Ptr cloud, const CoefficientsPair &coefficients_pair, const IndicesPair &indices_pair)
Definition: edgebased_cube_finder_nodelet.cpp:510
jsk_pcl_ros::EdgebasedCubeFinder::preparePointCloudForRANSAC
virtual pcl::PointIndices::Ptr preparePointCloudForRANSAC(const jsk_recognition_utils::ConvexPolygon::Ptr convex, const CoefficientsPair &edge_coefficients_pair, const pcl::PointCloud< PointT >::Ptr cloud)
Definition: edgebased_cube_finder_nodelet.cpp:571
jsk_pcl_ros::EdgebasedCubeFinder::unsubscribe
virtual void unsubscribe()
Definition: edgebased_cube_finder_nodelet.cpp:467
jsk_pcl_ros::EdgebasedCubeFinder::convex_area_threshold_
double convex_area_threshold_
Definition: edgebased_cube_finder.h:331
pcl_util.h
jsk_pcl_ros::PlanarCubeHypothesis
Definition: edgebased_cube_finder.h:160
jsk_pcl_ros::EdgebasedCubeFinder::A_PERPENDICULAR
@ A_PERPENDICULAR
Definition: edgebased_cube_finder.h:200
jsk_pcl_ros::CubeHypothesis::getCube
virtual jsk_recognition_utils::Cube::Ptr getCube()
Definition: edgebased_cube_finder.h:124
jsk_pcl_ros::EdgebasedCubeFinder::~EdgebasedCubeFinder
virtual ~EdgebasedCubeFinder()
Definition: edgebased_cube_finder_nodelet.cpp:443
jsk_pcl_ros::EdgebasedCubeFinder::combinateIndices
virtual std::vector< IndicesPair > combinateIndices(const std::vector< pcl::PointIndices::Ptr > &indices)
Definition: edgebased_cube_finder_nodelet.cpp:1243
jsk_pcl_ros::EdgebasedCubeFinder
Definition: edgebased_cube_finder.h:189
jsk_pcl_ros::EdgebasedCubeFinder::pub_
ros::Publisher pub_
Definition: edgebased_cube_finder.h:321
jsk_pcl_ros::PlanarCubeHypothesis::PlanarCubeHypothesis
PlanarCubeHypothesis(const IndicesPair &pair, const CoefficientsPair &coefficients_pair, const double outlier_threshold)
Definition: edgebased_cube_finder_nodelet.cpp:222
jsk_pcl_ros::EdgebasedCubeFinder::extractPointCloud
virtual pcl::PointCloud< PointT >::Ptr extractPointCloud(const pcl::PointCloud< PointT >::Ptr cloud, const pcl::PointIndices::Ptr indices)
Definition: edgebased_cube_finder_nodelet.cpp:483
synchronizer.h
jsk_pcl_ros::EdgebasedCubeFinder::mutex_
boost::mutex mutex_
Definition: edgebased_cube_finder.h:325
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_recognition_utils::Line
jsk_pcl_ros::CubeHypothesis::indices_pair_
const IndicesPair indices_pair_
Definition: edgebased_cube_finder.h:153
jsk_pcl_ros::EdgebasedCubeFinder::EdgeRelation
EdgeRelation
Definition: edgebased_cube_finder.h:197
jsk_pcl_ros::CoefficientsTriple
boost::tuple< pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr > CoefficientsTriple
Definition: edgebased_cube_finder.h:107
message_filters::sync_policies::ExactTime
jsk_pcl_ros::DiagnoalCubeHypothesis::Ptr
boost::shared_ptr< DiagnoalCubeHypothesis > Ptr
Definition: edgebased_cube_finder.h:178
jsk_pcl_ros::DiagnoalCubeHypothesis::DiagnoalCubeHypothesis
DiagnoalCubeHypothesis(const IndicesPair &pair, const CoefficientsPair &coefficients_pair, const double outlier_threshold)
Definition: edgebased_cube_finder_nodelet.cpp:229
jsk_recognition_utils::PointPair
boost::tuple< Point, Point > PointPair
jsk_pcl_ros::CubeHypothesis::getValue
virtual double getValue()
Definition: edgebased_cube_finder.h:123
jsk_pcl_ros::EdgebasedCubeFinder::estimateParallelPlane
virtual void estimateParallelPlane(const jsk_recognition_utils::ConvexPolygon::Ptr convex, const pcl::PointCloud< PointT >::Ptr filtered_cloud, pcl::PointIndices::Ptr output_inliers, pcl::ModelCoefficients::Ptr output_coefficients)
Definition: edgebased_cube_finder_nodelet.cpp:596
jsk_pcl_ros::CubeHypothesis::cube_
jsk_recognition_utils::Cube::Ptr cube_
Definition: edgebased_cube_finder.h:156
jsk_pcl_ros::EdgebasedCubeFinder::pub_debug_clusers_
ros::Publisher pub_debug_clusers_
Definition: edgebased_cube_finder.h:324
jsk_pcl_ros::EdgebasedCubeFinder::estimatePerpendicularPlane
virtual void estimatePerpendicularPlane(const jsk_recognition_utils::ConvexPolygon::Ptr convex, const CoefficientsPair &edge_coefficients, const pcl::PointCloud< PointT >::Ptr filtered_cloud, pcl::PointIndices::Ptr output_inliers, pcl::ModelCoefficients::Ptr output_coefficients)
Definition: edgebased_cube_finder_nodelet.cpp:615
jsk_pcl_ros::EdgebasedCubeFinder::pub_debug_filtered_cloud_
ros::Publisher pub_debug_filtered_cloud_
Definition: edgebased_cube_finder.h:323
jsk_pcl_ros::CubeHypothesis::Ptr
boost::shared_ptr< CubeHypothesis > Ptr
Definition: edgebased_cube_finder.h:118
jsk_pcl_ros::IndicesTriple
boost::tuple< pcl::PointIndices::Ptr, pcl::PointIndices::Ptr, pcl::PointIndices::Ptr > IndicesTriple
Definition: edgebased_cube_finder.h:105
jsk_pcl_ros::EdgebasedCubeFinder::estimate2
virtual void estimate2(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr &input_edges)
Definition: edgebased_cube_finder_nodelet.cpp:920
jsk_recognition_utils::Vertices
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
jsk_pcl_ros::EdgebasedCubeFinder::pub_debug_marker_
ros::Publisher pub_debug_marker_
Definition: edgebased_cube_finder.h:323
jsk_pcl_ros::DiagnoalCubeHypothesis::min_angle_
double min_angle_
Definition: edgebased_cube_finder.h:185


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