pinocchio  UNKNOWN
GeometryData Struct Reference
Collaboration diagram for GeometryData:
[legend]

Public Types

typedef std::vector< GeomIndex > GeomIndexList
 

Public Member Functions

 GeometryData (const GeometryModel &geomModel)
 
void fillInnerOuterObjectMaps (const GeometryModel &geomModel)
 
void activateCollisionPair (const PairIndex pairId, const bool flag=true)
 
void deactivateCollisionPair (const PairIndex pairId)
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW container::aligned_vector< se3::SE3oMg
 Vector gathering the SE3 placements of the geometry objects relative to the world. See updateGeometryPlacements to update the placements. More...
 
std::vector< fcl::CollisionObject > collisionObjects
 Collision objects (ie a fcl placed geometry). More...
 
std::vector< bool > activeCollisionPairs
 Vector of collision pairs.
 
fcl::DistanceRequest distanceRequest
 Defines what information should be computed by distance computation.
 
std::vector< fcl::DistanceResult > distanceResults
 Vector gathering the result of the distance computation for all the collision pairs.
 
fcl::CollisionRequest collisionRequest
 Defines what information should be computed by collision test.
 
std::vector< fcl::CollisionResult > collisionResults
 Vector gathering the result of the collision computation for all the collision pairs.
 
std::vector< double > radius
 Radius of the bodies, i.e. distance of the further point of the geometry model attached to the body from the joint center.
 
PairIndex collisionPairIndex
 index of the collision pair More...
 
std::map< JointIndex, GeomIndexList > innerObjects
 Map over vector GeomModel::geometryObjects, indexed by joints. More...
 
std::map< JointIndex, GeomIndexList > outerObjects
 A list of associated collision GeometryObjects to a given joint Id. More...
 

Friends

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

Detailed Description

Definition at line 158 of file multibody/geometry.hpp.

Member Function Documentation

void activateCollisionPair ( const PairIndex  pairId,
const bool  flag = true 
)
inline

Activate a collision pair, for which collisions and distances would now be computed.

A collision (resp distance) between to geometries of GeomModel::geometryObjects is computed iff the corresponding pair has been added in GeomModel::collisionPairs AND it is active, i.e. the corresponding boolean in GeomData::activePairs is true. The second condition can be used to temporarily remove a pair without touching the model, in a versatile manner.

Parameters
[in]pairIdthe index of the pair in GeomModel::collisionPairs vector.
[in]flagvalue of the activation boolean (true by default).

Definition at line 229 of file multibody/geometry.hxx.

void deactivateCollisionPair ( const PairIndex  pairId)
inline

Deactivate a collision pair.

Calls indeed GeomData::activateCollisionPair(pairId,false)

See also
activateCollisionPair

Definition at line 235 of file multibody/geometry.hxx.

void fillInnerOuterObjectMaps ( const GeometryModel geomModel)
inline

Fill both innerObjects and outerObjects maps, from vectors collisionObjects and collisionPairs.

This simply corresponds to storing in a re-arranged manner the information stored in geomModel.geometryObjects and geomModel.collisionPairs.

Parameters
[in]geomModelthe geometry model (const)
Warning
Outer objects are not duplicated (i.e. if a is in outerObjects[b], then b is not in outerObjects[a]).

Definition at line 134 of file multibody/geometry.hxx.

References GeometryData::activeCollisionPairs, GeometryModel::collisionPairs, GeometryModel::geometryObjects, GeometryModel::ngeoms, and GeometryData::oMg.

Member Data Documentation

std::vector<fcl::CollisionObject> collisionObjects

Collision objects (ie a fcl placed geometry).

The object contains a pointer on the collision geometries contained in geomModel.geometryObjects.

See also
GeometryModel::geometryObjects and GeometryObjects

Definition at line 178 of file multibody/geometry.hpp.

Referenced by se3::computeCollision(), se3::computeDistance(), and se3::updateGeometryPlacements().

PairIndex collisionPairIndex

index of the collision pair

It is used by some method to return additional information. For instance, the algo computeCollisions() sets it to the first colliding pair.

Definition at line 217 of file multibody/geometry.hpp.

std::map< JointIndex, GeomIndexList > innerObjects

Map over vector GeomModel::geometryObjects, indexed by joints.

The map lists the collision GeometryObjects associated to a given joint Id. Inner objects can be seen as geometry objects that directly move when the associated joint moves

Definition at line 225 of file multibody/geometry.hpp.

EIGEN_MAKE_ALIGNED_OPERATOR_NEW container::aligned_vector<se3::SE3> oMg

Vector gathering the SE3 placements of the geometry objects relative to the world. See updateGeometryPlacements to update the placements.

oMg is used for pinocchio (kinematics) computation but is translated to fcl type for fcl (collision) computation. The copy is done in collisionObjects[i]->setTransform(.)

Definition at line 169 of file multibody/geometry.hpp.

Referenced by GeometryData::fillInnerOuterObjectMaps(), and se3::updateGeometryPlacements().

std::map< JointIndex, GeomIndexList > outerObjects

A list of associated collision GeometryObjects to a given joint Id.

Outer objects can be seen as geometry objects that may often be obstacles to the Inner objects of given joint

Definition at line 231 of file multibody/geometry.hpp.


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