#include <edgebased_cube_finder.h>
Public Types | |
typedef boost::shared_ptr < CubeHypothesis > | Ptr |
Public Member Functions | |
virtual PointPair | computeAxisEndPoints (const Line &axis, const PointPair &a_candidates, const 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, ConvexPolygon &polygon_a, ConvexPolygon &polygon_b) |
virtual Cube::Ptr | getCube () |
virtual double | getValue () |
virtual | ~CubeHypothesis () |
Protected Member Functions | |
virtual ConvexPolygon::Ptr | buildConvexPolygon (const PointPair &a_edge_pair, const 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 Line &line, const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const pcl::PointIndices::Ptr indices, Vertices &output) |
Protected Attributes | |
const CoefficientsPair | coefficients_pair_ |
Cube::Ptr | cube_ |
const IndicesPair | indices_pair_ |
double | outlier_threshold_ |
double | value_ |
Definition at line 83 of file edgebased_cube_finder.h.
typedef boost::shared_ptr<CubeHypothesis> jsk_pcl_ros::CubeHypothesis::Ptr |
Reimplemented in jsk_pcl_ros::DiagnoalCubeHypothesis, and jsk_pcl_ros::PlanarCubeHypothesis.
Definition at line 86 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 57 of file edgebased_cube_finder_nodelet.cpp.
jsk_pcl_ros::CubeHypothesis::~CubeHypothesis | ( | ) | [virtual] |
Definition at line 66 of file edgebased_cube_finder_nodelet.cpp.
ConvexPolygon::Ptr jsk_pcl_ros::CubeHypothesis::buildConvexPolygon | ( | const PointPair & | a_edge_pair, |
const PointPair & | b_edge_pair | ||
) | [protected, virtual] |
Definition at line 107 of file edgebased_cube_finder_nodelet.cpp.
PointPair jsk_pcl_ros::CubeHypothesis::computeAxisEndPoints | ( | const Line & | axis, |
const PointPair & | a_candidates, | ||
const PointPair & | b_candidates | ||
) | [virtual] |
Definition at line 143 of file edgebased_cube_finder_nodelet.cpp.
void jsk_pcl_ros::CubeHypothesis::computeCentroid | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::PointIndices::Ptr & | indices, | ||
Eigen::Vector3f & | output | ||
) | [protected, virtual] |
Definition at line 70 of file edgebased_cube_finder_nodelet.cpp.
virtual void jsk_pcl_ros::CubeHypothesis::estimate | ( | const pcl::PointCloud< pcl::PointXYZRGB > & | cloud | ) | [pure virtual] |
Implemented in jsk_pcl_ros::DiagnoalCubeHypothesis, and jsk_pcl_ros::PlanarCubeHypothesis.
double jsk_pcl_ros::CubeHypothesis::evaluatePointOnPlanes | ( | const pcl::PointCloud< pcl::PointXYZRGB > & | cloud, |
ConvexPolygon & | polygon_a, | ||
ConvexPolygon & | polygon_b | ||
) | [virtual] |
Definition at line 119 of file edgebased_cube_finder_nodelet.cpp.
virtual Cube::Ptr jsk_pcl_ros::CubeHypothesis::getCube | ( | ) | [inline, virtual] |
Definition at line 92 of file edgebased_cube_finder.h.
void jsk_pcl_ros::CubeHypothesis::getLinePoints | ( | const Line & | line, |
const pcl::PointCloud< pcl::PointXYZRGB > & | cloud, | ||
const pcl::PointIndices::Ptr | indices, | ||
Vertices & | output | ||
) | [protected, virtual] |
Definition at line 86 of file edgebased_cube_finder_nodelet.cpp.
virtual double jsk_pcl_ros::CubeHypothesis::getValue | ( | ) | [inline, virtual] |
Definition at line 91 of file edgebased_cube_finder.h.
const CoefficientsPair jsk_pcl_ros::CubeHypothesis::coefficients_pair_ [protected] |
Definition at line 122 of file edgebased_cube_finder.h.
Cube::Ptr jsk_pcl_ros::CubeHypothesis::cube_ [protected] |
Definition at line 124 of file edgebased_cube_finder.h.
const IndicesPair jsk_pcl_ros::CubeHypothesis::indices_pair_ [protected] |
Definition at line 121 of file edgebased_cube_finder.h.
double jsk_pcl_ros::CubeHypothesis::outlier_threshold_ [protected] |
Definition at line 123 of file edgebased_cube_finder.h.
double jsk_pcl_ros::CubeHypothesis::value_ [protected] |
Definition at line 120 of file edgebased_cube_finder.h.