#include <polygon.h>
Public Types | |
enum | { DEGREE = Degree } |
typedef SubStructure::Model < Degree > | Model |
Public Member Functions | |
Eigen::Vector2f | _nextPoint (const Eigen::Vector3f &v, Eigen::Vector3f p, const int depth=0) const |
find nearest point to manifold (Newton) | |
float | area () const |
bool | getPose (Eigen::Matrix3f &P, Eigen::Vector3f &origin, float &h, float &w) const |
Eigen::Vector2f | nextPoint (const Eigen::Vector3f &v) const |
find nearest point to manifold (Newton) | |
Public Attributes | |
float | color_ [3] |
Eigen::Vector3f | feature_ |
sensor_msgs::ImagePtr | img_ |
int | mark_ |
Eigen::Vector3f | middle_ |
SubStructure::Model< Degree > | model_ |
SubStructure::Param< Degree > ::VectorU | param_xy_ |
std::vector< std::vector < Eigen::Vector2i > > | segments2d_ |
std::vector< std::vector < Eigen::Vector3f > > | segments_ |
float | weight_ |
typedef SubStructure::Model<Degree> Segmentation::S_POLYGON< Degree >::Model |
Eigen::Vector2f Segmentation::S_POLYGON< Degree >::_nextPoint | ( | const Eigen::Vector3f & | v, |
Eigen::Vector3f | p, | ||
const int | depth = 0 |
||
) | const [inline] |
float Segmentation::S_POLYGON< Degree >::area | ( | ) | const [inline] |
bool Segmentation::S_POLYGON< Degree >::getPose | ( | Eigen::Matrix3f & | P, |
Eigen::Vector3f & | origin, | ||
float & | h, | ||
float & | w | ||
) | const [inline] |
Eigen::Vector2f Segmentation::S_POLYGON< Degree >::nextPoint | ( | const Eigen::Vector3f & | v | ) | const [inline] |
float Segmentation::S_POLYGON< Degree >::color_[3] |
Eigen::Vector3f Segmentation::S_POLYGON< Degree >::feature_ |
sensor_msgs::ImagePtr Segmentation::S_POLYGON< Degree >::img_ |
int Segmentation::S_POLYGON< Degree >::mark_ |
Eigen::Vector3f Segmentation::S_POLYGON< Degree >::middle_ |
SubStructure::Model<Degree> Segmentation::S_POLYGON< Degree >::model_ |
SubStructure::Param<Degree>::VectorU Segmentation::S_POLYGON< Degree >::param_xy_ |
std::vector<std::vector<Eigen::Vector2i> > Segmentation::S_POLYGON< Degree >::segments2d_ |
std::vector<std::vector<Eigen::Vector3f> > Segmentation::S_POLYGON< Degree >::segments_ |
float Segmentation::S_POLYGON< Degree >::weight_ |