pinocchio  2.7.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
GeometryData Struct Reference
Inheritance diagram for GeometryData:
Collaboration diagram for GeometryData:

Public Types

enum  { Options = 0 }
 
typedef ::pinocchio::ComputeCollision ComputeCollision
 
typedef ::pinocchio::ComputeDistance ComputeDistance
 
typedef std::vector< GeomIndex > GeomIndexList
 
typedef Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXb
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
 
typedef double Scalar
 
typedef SE3Tpl< Scalar, Options > SE3
 

Public Member Functions

 GeometryData ()
 Empty constructor.
 
 GeometryData (const GeometryData &other)
 Copy constructor. More...
 
 GeometryData (const GeometryModel &geom_model)
 Default constructor from a GeometryModel. More...
 
 ~GeometryData ()
 Destructor.
 
void activateAllCollisionPairs ()
 Activate all collision pairs. More...
 
void activateCollisionPair (const PairIndex pair_id)
 
void deactivateAllCollisionPairs ()
 Deactivate all collision pairs. More...
 
void deactivateCollisionPair (const PairIndex pair_id)
 
void fillInnerOuterObjectMaps (const GeometryModel &geomModel)
 
bool operator!= (const GeometryData &other) const
 Returns true if *this and other are not equal.
 
GeometryDataoperator= (const GeometryData &other)
 Copy operator. More...
 
bool operator== (const GeometryData &other) const
 Returns true if *this and other are equal.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (ComputeCollision) collision_functors
   More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (ComputeDistance) distance_functors
   More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (SE3) oMg
 Vector gathering the SE3 placements of the geometry objects relative to the world. See updateGeometryPlacements to update the placements. More...
 
void setActiveCollisionPairs (const GeometryModel &geom_model, const MatrixXb &collision_map, const bool upper=true)
 Set the collision pair association from a given input array. Each entry of the input matrix defines the activation of a given collision pair. More...
 
void setGeometryCollisionStatus (const GeometryModel &geom_model, const GeomIndex geom_id, bool enable_collision)
 Enable or disable collision for the given geometry given by its geometry id with all the other geometries registered in the list of collision pairs. More...
 
void setSecurityMargins (const GeometryModel &geom_model, const MatrixXs &security_margin_map, const bool upper=true)
 Set the security margin of all the collision request in a row, according to the values stored in the associative map. More...
 
- Public Member Functions inherited from Serializable< GeometryData >
void loadFromBinary (boost::asio::streambuf &container)
 Loads a Derived object from a binary container.
 
void loadFromBinary (const std::string &filename)
 Loads a Derived object from an binary file.
 
void loadFromBinary (StaticBuffer &container)
 Loads a Derived object from a static binary container.
 
void loadFromString (const std::string &str)
 Loads a Derived object from a string.
 
void loadFromStringStream (std::istringstream &is)
 Loads a Derived object from a stream string.
 
void loadFromText (const std::string &filename)
 Loads a Derived object from a text file.
 
void loadFromXML (const std::string &filename, const std::string &tag_name)
 Loads a Derived object from an XML file.
 
void saveToBinary (boost::asio::streambuf &container) const
 Saves a Derived object as a binary container.
 
void saveToBinary (const std::string &filename) const
 Saves a Derived object as an binary file.
 
void saveToBinary (StaticBuffer &container) const
 Saves a Derived object as a static binary container.
 
std::string saveToString () const
 Saves a Derived object to a string.
 
void saveToStringStream (std::stringstream &ss) const
 Saves a Derived object to a string stream.
 
void saveToText (const std::string &filename) const
 Saves a Derived object as a text file.
 
void saveToXML (const std::string &filename, const std::string &tag_name) const
 Saves a Derived object as an XML file.
 

Public Attributes

std::vector< bool > activeCollisionPairs
 Vector of collision pairs.
 
PairIndex collisionPairIndex
 Index of the collision pair. More...
 
std::vector< fcl::CollisionRequest > collisionRequests
 Defines what information should be computed by collision test. There is one request per pair of geometries.
 
std::vector< fcl::CollisionResult > collisionResults
 Vector gathering the result of the collision computation for all the collision pairs.
 
std::vector< fcl::DistanceRequest > distanceRequests
 Defines what information should be computed by distance computation. There is one request per pair of geometries.
 
std::vector< fcl::DistanceResult > distanceResults
 Vector gathering the result of the distance computation for all the collision pairs.
 
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...
 
std::vector< Scalar > radius
 Radius of the bodies, i.e. distance of the further point of the geometry model attached to the body from the joint center.
 

Friends

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

Detailed Description

Definition at line 187 of file geometry.hpp.

Constructor & Destructor Documentation

◆ GeometryData() [1/2]

GeometryData ( const GeometryModel geom_model)
explicit

Default constructor from a GeometryModel.

Parameters
[in]geom_modelGeometryModel associated to the new GeometryData

◆ GeometryData() [2/2]

GeometryData ( const GeometryData other)

Copy constructor.

Parameters
[in]otherGeometryData to copy

Member Function Documentation

◆ activateAllCollisionPairs()

void activateAllCollisionPairs ( )

Activate all collision pairs.

See also
GeomData::deactivateAllCollisionPairs, GeomData::activateCollisionPair, GeomData::deactivateCollisionPair

◆ activateCollisionPair()

void activateCollisionPair ( const PairIndex  pair_id)

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

The collision (resp distance) between two 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]pair_idthe index of the pair in GeomModel::collisionPairs vector.

 

See also
GeomData

◆ deactivateAllCollisionPairs()

void deactivateAllCollisionPairs ( )

Deactivate all collision pairs.

See also
GeomData::activateAllCollisionPairs, GeomData::activateCollisionPair, GeomData::deactivateCollisionPair

◆ deactivateCollisionPair()

void deactivateCollisionPair ( const PairIndex  pair_id)

Deactivate a collision pair.

Calls indeed GeomData::activateCollisionPair(pair_id)

Parameters
[in]pair_idthe index of the pair in GeomModel::collisionPairs vector.
See also
GeomData::activateCollisionPair

◆ fillInnerOuterObjectMaps()

void fillInnerOuterObjectMaps ( const GeometryModel geomModel)

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]).

◆ operator=()

GeometryData& operator= ( const GeometryData other)

Copy operator.

Parameters
[in]otherGeometryData to copy

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [1/3]

PINOCCHIO_ALIGNED_STD_VECTOR ( ComputeCollision  )

 

Functor associated to the computation of collisions.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [2/3]

PINOCCHIO_ALIGNED_STD_VECTOR ( ComputeDistance  )

 

Functor associated to the computation of distances.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [3/3]

PINOCCHIO_ALIGNED_STD_VECTOR ( SE3  )

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(.)

◆ setActiveCollisionPairs()

void setActiveCollisionPairs ( const GeometryModel geom_model,
const MatrixXb &  collision_map,
const bool  upper = true 
)

Set the collision pair association from a given input array. Each entry of the input matrix defines the activation of a given collision pair.

Parameters
[in]geom_modelGeometry model associated to the data.
[in]collision_mapAssociative array.
[in]upperWheter the collision_map is an upper or lower triangular filled array.

◆ setGeometryCollisionStatus()

void setGeometryCollisionStatus ( const GeometryModel geom_model,
const GeomIndex  geom_id,
bool  enable_collision 
)

Enable or disable collision for the given geometry given by its geometry id with all the other geometries registered in the list of collision pairs.

Parameters
[in]geom_modelGeometry model associated to the data.
[in]geom_idIndex of the geometry.
[in]enable_collisionIf true, the collision will be enable, otherwise disable.

◆ setSecurityMargins()

void setSecurityMargins ( const GeometryModel geom_model,
const MatrixXs &  security_margin_map,
const bool  upper = true 
)

Set the security margin of all the collision request in a row, according to the values stored in the associative map.

Parameters
[in]geom_modelGeometry model associated to the data.
[in]security_margin_mapAssociative map related the security margin of a given input collision pair (i,j).
[in]upperWheter the security_margin_map is an upper or lower triangular filled array.

Member Data Documentation

◆ collisionPairIndex

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 253 of file geometry.hpp.

◆ innerObjects

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 267 of file geometry.hpp.

◆ outerObjects

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 a given joint

Definition at line 273 of file geometry.hpp.


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