Public Member Functions | Private Attributes | Friends
ICR::ContactPoint Class Reference

Contains the coordinates of a ICR::TargetObject's vertex and its corresponding vertex normal, as well as a unique id and a list of id's of neighboring points. More...

#include <contact_point.h>

List of all members.

Public Member Functions

void addNeighbor (uint neighbor)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ContactPoint ()
 ContactPoint (double const vertex[3])
 ContactPoint (Eigen::Vector3d const &vertex)
 ContactPoint (double const vertex[3], uint id)
 ContactPoint (Eigen::Vector3d const &vertex, uint id)
 ContactPoint (double const vertex[3], double const vertex_normal[3], uint id)
 ContactPoint (Eigen::Vector3d const &vertex, Eigen::Vector3d const &vertex_normal, uint id)
 ContactPoint (double const vertex[3], double const vertex_normal[3], IndexList const &neighbors, uint id)
 ContactPoint (Eigen::Vector3d const &vertex, Eigen::Vector3d const &vertex_normal, IndexList const &neighbors, uint id)
 ContactPoint (ContactPoint const &src)
void filterDuplicateNeighbors ()
uint getId () const
ConstIndexListIterator getNeighborItBegin () const
ConstIndexListIterator getNeighborItEnd () const
IndexListgetNeighbors ()
IndexList const * getNeighbors () const
uint getNumNeighbors () const
Eigen::Vector3d * getVertex ()
Eigen::Vector3d const * getVertex () const
Eigen::Vector3d * getVertexNormal ()
Eigen::Vector3d const * getVertexNormal () const
ContactPointoperator= (ContactPoint const &src)
void setId (uint id)
void setVertex (Eigen::Vector3d const &vertex)
void setVertex (double const vertex[3])
void setVertexNormal (Eigen::Vector3d const &vertex_normal)
void setVertexNormal (double const vertex_normal[3])
 ~ContactPoint ()

Private Attributes

uint id_
IndexList neighbors_
Eigen::Vector3d vertex_
Eigen::Vector3d vertex_normal_

Friends

std::ostream & operator<< (std::ostream &stream, ContactPoint const &cp)

Detailed Description

Contains the coordinates of a ICR::TargetObject's vertex and its corresponding vertex normal, as well as a unique id and a list of id's of neighboring points.

The id in ICR::ContactPoint::id_ corresponds to the index of the contact point in ICR::TargetObject::contact_points_. Neighboring points are defined as the ones connected to the considered point by an edge of the mesh of the target object.

Definition at line 19 of file contact_point.h.


Constructor & Destructor Documentation

Definition at line 8 of file contact_point.cpp.

ICR::ContactPoint::ContactPoint ( double const  vertex[3])

Definition at line 10 of file contact_point.cpp.

ICR::ContactPoint::ContactPoint ( Eigen::Vector3d const &  vertex)

Definition at line 12 of file contact_point.cpp.

ICR::ContactPoint::ContactPoint ( double const  vertex[3],
uint  id 
)

Definition at line 14 of file contact_point.cpp.

ICR::ContactPoint::ContactPoint ( Eigen::Vector3d const &  vertex,
uint  id 
)

Definition at line 16 of file contact_point.cpp.

ICR::ContactPoint::ContactPoint ( double const  vertex[3],
double const  vertex_normal[3],
uint  id 
)

Definition at line 18 of file contact_point.cpp.

ICR::ContactPoint::ContactPoint ( Eigen::Vector3d const &  vertex,
Eigen::Vector3d const &  vertex_normal,
uint  id 
)

Definition at line 23 of file contact_point.cpp.

ICR::ContactPoint::ContactPoint ( double const  vertex[3],
double const  vertex_normal[3],
IndexList const &  neighbors,
uint  id 
)

Definition at line 28 of file contact_point.cpp.

ICR::ContactPoint::ContactPoint ( Eigen::Vector3d const &  vertex,
Eigen::Vector3d const &  vertex_normal,
IndexList const &  neighbors,
uint  id 
)

Definition at line 31 of file contact_point.cpp.

Definition at line 33 of file contact_point.cpp.

Definition at line 72 of file contact_point.cpp.


Member Function Documentation

Definition at line 90 of file contact_point.cpp.

Removes duplicated id's from ICR::ContactPoint::neighbors_; Has no effect if there aren't any duplicates;

Definition at line 100 of file contact_point.cpp.

Definition at line 106 of file contact_point.cpp.

Definition at line 92 of file contact_point.cpp.

Definition at line 94 of file contact_point.cpp.

Definition at line 96 of file contact_point.cpp.

Definition at line 98 of file contact_point.cpp.

Definition at line 110 of file contact_point.cpp.

Eigen::Vector3d * ICR::ContactPoint::getVertex ( )

Definition at line 74 of file contact_point.cpp.

Eigen::Vector3d const * ICR::ContactPoint::getVertex ( ) const

Definition at line 76 of file contact_point.cpp.

Eigen::Vector3d * ICR::ContactPoint::getVertexNormal ( )

Definition at line 78 of file contact_point.cpp.

Eigen::Vector3d const * ICR::ContactPoint::getVertexNormal ( ) const

Definition at line 80 of file contact_point.cpp.

ContactPoint & ICR::ContactPoint::operator= ( ContactPoint const &  src)

Definition at line 35 of file contact_point.cpp.

Definition at line 108 of file contact_point.cpp.

void ICR::ContactPoint::setVertex ( Eigen::Vector3d const &  vertex)

Definition at line 82 of file contact_point.cpp.

void ICR::ContactPoint::setVertex ( double const  vertex[3])

Definition at line 84 of file contact_point.cpp.

void ICR::ContactPoint::setVertexNormal ( Eigen::Vector3d const &  vertex_normal)

Definition at line 86 of file contact_point.cpp.

void ICR::ContactPoint::setVertexNormal ( double const  vertex_normal[3])

Definition at line 88 of file contact_point.cpp.


Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  stream,
ContactPoint const &  cp 
) [friend]

Definition at line 48 of file contact_point.cpp.


Member Data Documentation

Definition at line 26 of file contact_point.h.

Definition at line 25 of file contact_point.h.

Eigen::Vector3d ICR::ContactPoint::vertex_ [private]

Definition at line 23 of file contact_point.h.

Eigen::Vector3d ICR::ContactPoint::vertex_normal_ [private]

Definition at line 24 of file contact_point.h.


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


libicr
Author(s): Robert Krug
autogenerated on Mon Jan 6 2014 11:34:32