Public Types | Public Member Functions | Public Attributes
Segmentation::S_POLYGON< Degree > Struct Template Reference

#include <polygon.h>

List of all members.

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_

Detailed Description

template<int Degree>
struct Segmentation::S_POLYGON< Degree >

Definition at line 95 of file polygon.h.


Member Typedef Documentation

template<int Degree>
typedef SubStructure::Model<Degree> Segmentation::S_POLYGON< Degree >::Model

Definition at line 97 of file polygon.h.


Member Enumeration Documentation

template<int Degree>
anonymous enum
Enumerator:
DEGREE 

Definition at line 96 of file polygon.h.


Member Function Documentation

template<int Degree>
Eigen::Vector2f Segmentation::S_POLYGON< Degree >::_nextPoint ( const Eigen::Vector3f &  v,
Eigen::Vector3f  p,
const int  depth = 0 
) const [inline]

find nearest point to manifold (Newton)

Definition at line 522 of file polygon.h.

template<int Degree>
float Segmentation::S_POLYGON< Degree >::area ( ) const [inline]

Definition at line 619 of file polygon.h.

template<int Degree>
bool Segmentation::S_POLYGON< Degree >::getPose ( Eigen::Matrix3f &  P,
Eigen::Vector3f &  origin,
float &  h,
float &  w 
) const [inline]

Definition at line 563 of file polygon.h.

template<int Degree>
Eigen::Vector2f Segmentation::S_POLYGON< Degree >::nextPoint ( const Eigen::Vector3f &  v) const [inline]

find nearest point to manifold (Newton)

Definition at line 536 of file polygon.h.


Member Data Documentation

template<int Degree>
float Segmentation::S_POLYGON< Degree >::color_[3]

Definition at line 114 of file polygon.h.

template<int Degree>
Eigen::Vector3f Segmentation::S_POLYGON< Degree >::feature_

Definition at line 120 of file polygon.h.

template<int Degree>
sensor_msgs::ImagePtr Segmentation::S_POLYGON< Degree >::img_

Definition at line 113 of file polygon.h.

template<int Degree>
int Segmentation::S_POLYGON< Degree >::mark_

Definition at line 110 of file polygon.h.

template<int Degree>
Eigen::Vector3f Segmentation::S_POLYGON< Degree >::middle_

Definition at line 109 of file polygon.h.

template<int Degree>
SubStructure::Model<Degree> Segmentation::S_POLYGON< Degree >::model_

Definition at line 108 of file polygon.h.

template<int Degree>
SubStructure::Param<Degree>::VectorU Segmentation::S_POLYGON< Degree >::param_xy_

Definition at line 112 of file polygon.h.

template<int Degree>
std::vector<std::vector<Eigen::Vector2i> > Segmentation::S_POLYGON< Degree >::segments2d_

Definition at line 100 of file polygon.h.

template<int Degree>
std::vector<std::vector<Eigen::Vector3f> > Segmentation::S_POLYGON< Degree >::segments_

Definition at line 99 of file polygon.h.

template<int Degree>
float Segmentation::S_POLYGON< Degree >::weight_

Definition at line 104 of file polygon.h.


The documentation for this struct was generated from the following file:


cob_3d_segmentation
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:04