Classes | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Friends
ParametricSurface::Topology Class Reference

#include <topology.h>

List of all members.

Classes

struct  Functor
struct  POINT

Public Member Functions

void add (cob_3d_marker::MarkerList_Line &ml) const
void add (cob_3d_marker::MarkerList_Triangles &mt, ParametricSurface::TriSpline2_Fade &tri, const Eigen::Vector3f &a, const Eigen::Vector3f &b, const Eigen::Vector3f &c, const int depth=0) const
void add (cob_3d_marker::MarkerList_Triangles &mt) const
void add (cob_3d_marker::MarkerList_Arrow &ma) const
void add (cob_3d_marker::MarkerList_Text &mt) const
void finish ()
void insertPoint (const POINT &pt)
void insertPointWithoutUpdate (const POINT &pt)
Eigen::Vector2f nextPoint (const Eigen::Vector3f &p, ParametricSurface::TriSpline2_Fade **used=NULL) const
Eigen::Matrix< float, 3, 2 > normal (const Eigen::Vector2f &uv) const
Eigen::Vector3f normalAt (const Eigen::Vector2f &uv) const
Eigen::Vector3f normalAt2 (const Eigen::Vector2f &uv, bool &inside, float &w) const
float operator+= (const Topology &o)
void operator= (const Topology &o)
void print () const
Eigen::Vector3f project2world (const Eigen::Vector2f &uv) const
 Topology (const float thr)
 Topology (const Topology &o)
void transform (const Eigen::Matrix3f &rot, const Eigen::Vector3f &tr)
void update ()

Private Types

typedef
CGAL::Delaunay_triangulation_2
< Kernel, Tds
Delaunay_d
typedef
Delaunay_d::All_edges_iterator 
Edge_iterator
typedef Delaunay_d::Face Face
typedef Delaunay_d::Face_circulator Face_circulator
typedef Delaunay_d::Face_handle Face_handle
typedef Delaunay_d::Face_iterator Face_iterator
typedef CGAL::Cartesian< float > Kernel
typedef Delaunay_d::Point Point
typedef float RT
typedef
CGAL::Triangulation_data_structure_2
< Vb, Vbb
Tds
typedef
CGAL::Triangulation_vertex_base_with_info_2
< boost::shared_ptr< POINT >
, Kernel
Vb
typedef
CGAL::Triangulation_face_base_with_info_2
< boost::shared_ptr
< ParametricSurface::TriSpline2_Fade >
, Kernel
Vbb
typedef Kernel::Vector_2 Vector
typedef Delaunay_d::Vertex Vertex
typedef
Delaunay_d::Vertex_circulator 
Vertex_circulator
typedef Delaunay_d::Vertex_handle Vertex_handle
typedef Delaunay_d::Vertex_iterator Vertex_iterator

Private Member Functions

bool canRemove (const boost::shared_ptr< POINT > &pt) const
bool isOnBorder (const boost::shared_ptr< POINT > &pt) const
ParametricSurface::TriSpline2_Fadelocate (const Eigen::Vector2f &uv) const
ParametricSurface::TriSpline2_Fadelocate (const Eigen::Vector2f &uv, bool &inside) const
void removePoint (const size_t i)

Static Private Member Functions

static float sqDistLinePt (const Eigen::Vector2f &uv, const Eigen::Vector2f &r1, const Eigen::Vector2f &r2)

Private Attributes

Delaunay_d del_
std::vector< boost::shared_ptr
< POINT > > 
pts_
float thr_
std::vector< boost::shared_ptr
< ParametricSurface::TriSpline2_Fade > > 
tris_

Friends

class Functor

Detailed Description

Definition at line 28 of file topology.h.


Member Typedef Documentation

typedef CGAL::Delaunay_triangulation_2<Kernel, Tds> ParametricSurface::Topology::Delaunay_d [private]

Definition at line 77 of file topology.h.

typedef Delaunay_d::All_edges_iterator ParametricSurface::Topology::Edge_iterator [private]

Definition at line 84 of file topology.h.

typedef Delaunay_d::Face ParametricSurface::Topology::Face [private]

Definition at line 81 of file topology.h.

typedef Delaunay_d::Face_circulator ParametricSurface::Topology::Face_circulator [private]

Definition at line 91 of file topology.h.

typedef Delaunay_d::Face_handle ParametricSurface::Topology::Face_handle [private]

Definition at line 82 of file topology.h.

typedef Delaunay_d::Face_iterator ParametricSurface::Topology::Face_iterator [private]

Definition at line 83 of file topology.h.

typedef CGAL::Cartesian<float> ParametricSurface::Topology::Kernel [private]

Definition at line 70 of file topology.h.

Definition at line 78 of file topology.h.

typedef float ParametricSurface::Topology::RT [private]

Definition at line 32 of file topology.h.

typedef CGAL::Triangulation_data_structure_2<Vb, Vbb> ParametricSurface::Topology::Tds [private]

Definition at line 75 of file topology.h.

typedef CGAL::Triangulation_vertex_base_with_info_2<boost::shared_ptr<POINT>, Kernel> ParametricSurface::Topology::Vb [private]

Definition at line 73 of file topology.h.

typedef CGAL::Triangulation_face_base_with_info_2<boost::shared_ptr<ParametricSurface::TriSpline2_Fade>, Kernel> ParametricSurface::Topology::Vbb [private]

Definition at line 74 of file topology.h.

typedef Kernel::Vector_2 ParametricSurface::Topology::Vector [private]

Definition at line 79 of file topology.h.

typedef Delaunay_d::Vertex ParametricSurface::Topology::Vertex [private]

Definition at line 80 of file topology.h.

typedef Delaunay_d::Vertex_circulator ParametricSurface::Topology::Vertex_circulator [private]

Definition at line 92 of file topology.h.

typedef Delaunay_d::Vertex_handle ParametricSurface::Topology::Vertex_handle [private]

Definition at line 90 of file topology.h.

typedef Delaunay_d::Vertex_iterator ParametricSurface::Topology::Vertex_iterator [private]

Definition at line 93 of file topology.h.


Constructor & Destructor Documentation

ParametricSurface::Topology::Topology ( const float  thr) [inline]

Definition at line 380 of file topology.h.

Definition at line 384 of file topology.h.


Member Function Documentation

Definition at line 859 of file topology.h.

void ParametricSurface::Topology::add ( cob_3d_marker::MarkerList_Triangles mt,
ParametricSurface::TriSpline2_Fade tri,
const Eigen::Vector3f &  a,
const Eigen::Vector3f &  b,
const Eigen::Vector3f &  c,
const int  depth = 0 
) const [inline]

Definition at line 877 of file topology.h.

Definition at line 899 of file topology.h.

Definition at line 910 of file topology.h.

Definition at line 922 of file topology.h.

bool ParametricSurface::Topology::canRemove ( const boost::shared_ptr< POINT > &  pt) const [inline, private]

Definition at line 187 of file topology.h.

Definition at line 412 of file topology.h.

void ParametricSurface::Topology::insertPoint ( const POINT pt) [inline]

Definition at line 407 of file topology.h.

Definition at line 544 of file topology.h.

bool ParametricSurface::Topology::isOnBorder ( const boost::shared_ptr< POINT > &  pt) const [inline, private]

Definition at line 122 of file topology.h.

ParametricSurface::TriSpline2_Fade* ParametricSurface::Topology::locate ( const Eigen::Vector2f &  uv) const [inline, private]

Definition at line 330 of file topology.h.

ParametricSurface::TriSpline2_Fade* ParametricSurface::Topology::locate ( const Eigen::Vector2f &  uv,
bool &  inside 
) const [inline, private]

Definition at line 334 of file topology.h.

Eigen::Vector2f ParametricSurface::Topology::nextPoint ( const Eigen::Vector3f &  p,
ParametricSurface::TriSpline2_Fade **  used = NULL 
) const [inline]

Definition at line 587 of file topology.h.

Eigen::Matrix<float,3,2> ParametricSurface::Topology::normal ( const Eigen::Vector2f &  uv) const [inline]

Definition at line 677 of file topology.h.

Eigen::Vector3f ParametricSurface::Topology::normalAt ( const Eigen::Vector2f &  uv) const [inline]

Definition at line 669 of file topology.h.

Eigen::Vector3f ParametricSurface::Topology::normalAt2 ( const Eigen::Vector2f &  uv,
bool &  inside,
float &  w 
) const [inline]

Definition at line 682 of file topology.h.

float ParametricSurface::Topology::operator+= ( const Topology o) [inline]

Definition at line 697 of file topology.h.

void ParametricSurface::Topology::operator= ( const Topology o) [inline]

Definition at line 388 of file topology.h.

void ParametricSurface::Topology::print ( ) const [inline]

Definition at line 852 of file topology.h.

Eigen::Vector3f ParametricSurface::Topology::project2world ( const Eigen::Vector2f &  uv) const [inline]

Definition at line 655 of file topology.h.

void ParametricSurface::Topology::removePoint ( const size_t  i) [inline, private]

Definition at line 215 of file topology.h.

static float ParametricSurface::Topology::sqDistLinePt ( const Eigen::Vector2f &  uv,
const Eigen::Vector2f &  r1,
const Eigen::Vector2f &  r2 
) [inline, static, private]

Definition at line 323 of file topology.h.

void ParametricSurface::Topology::transform ( const Eigen::Matrix3f &  rot,
const Eigen::Vector3f &  tr 
) [inline]

Definition at line 840 of file topology.h.

Definition at line 557 of file topology.h.


Friends And Related Function Documentation

friend class Functor [friend]

Definition at line 321 of file topology.h.


Member Data Documentation

Definition at line 115 of file topology.h.

std::vector< boost::shared_ptr<POINT> > ParametricSurface::Topology::pts_ [private]

Definition at line 116 of file topology.h.

Definition at line 120 of file topology.h.

std::vector< boost::shared_ptr<ParametricSurface::TriSpline2_Fade> > ParametricSurface::Topology::tris_ [private]

Definition at line 117 of file topology.h.


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


cob_3d_mapping_slam
Author(s): Joshua Hampp
autogenerated on Wed Aug 26 2015 11:04:51