#include <multibody/geometry.hpp>
typedef std::pair< Index, Index > se3::GeometryData::CollisionPair_t |
typedef Model::Index se3::GeometryData::Index |
se3::GeometryData::GeometryData | ( | Data & | data, |
GeometryModel & | model_geom | ||
) | [inline] |
References collisions, distances, initializeListOfCollisionPairs(), and nCollisionPairs.
se3::GeometryData::~GeometryData | ( | ) | [inline] |
References model_geom, and se3::GeometryModel::ngeom.
Referenced by fillAllPairsAsCollisions().
void se3::GeometryData::addCollisionPair | ( | const CollisionPair_t & | pair | ) | [inline] |
References collision_pairs, model_geom, nCollisionPairs, and se3::GeometryModel::ngeom.
References se3::GeometryModel::collision_objects, model_geom, and oMg_fcl.
Referenced by se3::computeCollisions().
References se3::GeometryModel::collision_objects, model_geom, and oMg_fcl.
Referenced by se3::computeDistances().
void se3::GeometryData::desactivateCollisionPairs | ( | ) | [inline] |
Referenced by initializeListOfCollisionPairs().
void se3::GeometryData::displayCollisionPairs | ( | ) | const [inline] |
References collision_pairs.
std::vector< DistanceResult > se3::GeometryData::distanceResults | ( | ) |
void se3::GeometryData::fillAllPairsAsCollisions | ( | ) | [inline] |
References addCollisionPair(), model_geom, and se3::GeometryModel::ngeom.
Referenced by initializeListOfCollisionPairs().
void se3::GeometryData::initializeListOfCollisionPairs | ( | ) | [inline] |
References collision_pairs, desactivateCollisionPairs(), fillAllPairsAsCollisions(), and nCollisionPairs.
Referenced by GeometryData().
Referenced by removeCollisionPair().
bool se3::GeometryData::isCollisionPair | ( | const CollisionPair_t & | pair | ) | const [inline] |
References collision_pairs.
References isCollisionPair(), model_geom, and se3::GeometryModel::ngeom.
void se3::GeometryData::removeCollisionPair | ( | const CollisionPair_t & | pair | ) | [inline] |
References collision_pairs, isCollisionPair(), model_geom, nCollisionPairs, and se3::GeometryModel::ngeom.
void se3::GeometryData::resetDistances | ( | ) | [inline] |
References distances.
std::ostream& operator<< | ( | std::ostream & | os, |
const GeometryData & | data_geom | ||
) | [friend] |
std::vector< CollisionPair_t > se3::GeometryData::collision_pairs |
std::vector< bool > se3::GeometryData::collisions |
Referenced by se3::computeCollisions(), and GeometryData().
std::vector< DistanceResult > se3::GeometryData::distances |
Referenced by se3::computeDistances(), GeometryData(), and resetDistances().
Referenced by addCollisionPair(), GeometryData(), initializeListOfCollisionPairs(), and removeCollisionPair().
std::vector<se3::SE3> se3::GeometryData::oMg |
Referenced by se3::operator<<(), and se3::updateCollisionGeometry().
std::vector<fcl::Transform3f> se3::GeometryData::oMg_fcl |
Referenced by collide(), computeDistance(), and se3::updateCollisionGeometry().