#include <edgebased_cube_finder.h>

| Public Types | |
| typedef boost::shared_ptr< CubeHypothesis > | Ptr | 
| Public Member Functions | |
| 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) | 
| CubeHypothesis (const IndicesPair &pair, const CoefficientsPair &coefficients_pair, const double outlier_threshold) | |
| virtual void | estimate (const pcl::PointCloud< pcl::PointXYZRGB > &cloud)=0 | 
| virtual double | evaluatePointOnPlanes (const pcl::PointCloud< pcl::PointXYZRGB > &cloud, jsk_recognition_utils::ConvexPolygon &polygon_a, jsk_recognition_utils::ConvexPolygon &polygon_b) | 
| virtual jsk_recognition_utils::Cube::Ptr | getCube () | 
| virtual double | getValue () | 
| virtual | ~CubeHypothesis () | 
| Protected Member Functions | |
| virtual jsk_recognition_utils::ConvexPolygon::Ptr | buildConvexPolygon (const jsk_recognition_utils::PointPair &a_edge_pair, const jsk_recognition_utils::PointPair &b_edge_pair) | 
| virtual void | computeCentroid (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointIndices::Ptr &indices, Eigen::Vector3f &output) | 
| 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) | 
| Protected Attributes | |
| const CoefficientsPair | coefficients_pair_ | 
| jsk_recognition_utils::Cube::Ptr | cube_ | 
| const IndicesPair | indices_pair_ | 
| double | outlier_threshold_ | 
| double | value_ | 
Definition at line 115 of file edgebased_cube_finder.h.
Definition at line 118 of file edgebased_cube_finder.h.
| jsk_pcl_ros::CubeHypothesis::CubeHypothesis | ( | const IndicesPair & | pair, | 
| const CoefficientsPair & | coefficients_pair, | ||
| const double | outlier_threshold | ||
| ) | 
Definition at line 89 of file edgebased_cube_finder_nodelet.cpp.
| 
 | virtual | 
Definition at line 98 of file edgebased_cube_finder_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 139 of file edgebased_cube_finder_nodelet.cpp.
| 
 | virtual | 
Definition at line 180 of file edgebased_cube_finder_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 102 of file edgebased_cube_finder_nodelet.cpp.
| 
 | pure virtual | 
Implemented in jsk_pcl_ros::DiagnoalCubeHypothesis, and jsk_pcl_ros::PlanarCubeHypothesis.
| 
 | virtual | 
Definition at line 156 of file edgebased_cube_finder_nodelet.cpp.
| 
 | inlinevirtual | 
Definition at line 124 of file edgebased_cube_finder.h.
| 
 | protectedvirtual | 
Definition at line 118 of file edgebased_cube_finder_nodelet.cpp.
| 
 | inlinevirtual | 
Definition at line 123 of file edgebased_cube_finder.h.
| 
 | protected | 
Definition at line 154 of file edgebased_cube_finder.h.
| 
 | protected | 
Definition at line 156 of file edgebased_cube_finder.h.
| 
 | protected | 
Definition at line 153 of file edgebased_cube_finder.h.
| 
 | protected | 
Definition at line 155 of file edgebased_cube_finder.h.
| 
 | protected | 
Definition at line 152 of file edgebased_cube_finder.h.