se3::GeometryData Class Reference

#include <multibody/geometry.hpp>

Collaboration diagram for se3::GeometryData:
[legend]

List of all members.

Public Types

typedef Model::Index Index
typedef std::pair< Index, IndexCollisionPair_t

Public Member Functions

 GeometryData (Data &data, GeometryModel &model_geom)
 ~GeometryData ()
void addCollisionPair (Index co1, Index co2)
void addCollisionPair (const CollisionPair_t &pair)
void removeCollisionPair (Index co1, Index co2)
void removeCollisionPair (const CollisionPair_t &pair)
bool isCollisionPair (Index co1, Index co2) const
bool isCollisionPair (const CollisionPair_t &pair) const
void fillAllPairsAsCollisions ()
void desactivateCollisionPairs ()
void initializeListOfCollisionPairs ()
bool collide (Index co1, Index co2) const
fcl::DistanceResult computeDistance (Index co1, Index co2) const
void resetDistances ()
std::vector< DistanceResultdistanceResults ()
void displayCollisionPairs () const

Public Attributes

Datadata_ref
GeometryModelmodel_geom
std::vector< se3::SE3oMg
std::vector< fcl::Transform3f > oMg_fcl
std::vector< CollisionPair_tcollision_pairs
Index nCollisionPairs
std::vector< DistanceResultdistances
std::vector< bool > collisions

Friends

std::ostream & operator<< (std::ostream &os, const GeometryData &data_geom)

Member Typedef Documentation


Constructor & Destructor Documentation

se3::GeometryData::GeometryData ( Data data,
GeometryModel model_geom 
) [inline]
se3::GeometryData::~GeometryData ( ) [inline]

Member Function Documentation

void se3::GeometryData::addCollisionPair ( Index  co1,
Index  co2 
) [inline]
void se3::GeometryData::addCollisionPair ( const CollisionPair_t pair) [inline]
bool se3::GeometryData::collide ( Index  co1,
Index  co2 
) const [inline]
fcl::DistanceResult se3::GeometryData::computeDistance ( Index  co1,
Index  co2 
) const [inline]
void se3::GeometryData::desactivateCollisionPairs ( ) [inline]
void se3::GeometryData::displayCollisionPairs ( ) const [inline]

References collision_pairs.

std::vector< DistanceResult > se3::GeometryData::distanceResults ( )
void se3::GeometryData::fillAllPairsAsCollisions ( ) [inline]
void se3::GeometryData::initializeListOfCollisionPairs ( ) [inline]
bool se3::GeometryData::isCollisionPair ( Index  co1,
Index  co2 
) const [inline]

Referenced by removeCollisionPair().

bool se3::GeometryData::isCollisionPair ( const CollisionPair_t pair) const [inline]

References collision_pairs.

void se3::GeometryData::removeCollisionPair ( Index  co1,
Index  co2 
) [inline]
void se3::GeometryData::removeCollisionPair ( const CollisionPair_t pair) [inline]
void se3::GeometryData::resetDistances ( ) [inline]

References distances.


Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  os,
const GeometryData data_geom 
) [friend]

Member Data Documentation

std::vector<fcl::Transform3f> se3::GeometryData::oMg_fcl