Struct GeometryData
Defined in File geometry.hpp
Inheritance Relationships
Base Type
public pinocchio::serialization::Serializable< GeometryData >
(Template Struct Serializable)
Struct Documentation
-
struct GeometryData : public pinocchio::serialization::Serializable<GeometryData>
Public Types
Values:
-
enumerator Options
-
enumerator Options
-
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
Public Functions
- 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.
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(.)
-
explicit GeometryData(const GeometryModel &geom_model)
Default constructor from a GeometryModel.
- Parameters:
geom_model – [in] GeometryModel associated to the new GeometryData
-
GeometryData(const GeometryData &other)
Copy constructor.
- Parameters:
other – [in] GeometryData to copy
-
GeometryData &operator=(const GeometryData &other)
Copy operator.
- Parameters:
other – [in] GeometryData to copy
-
inline GeometryData()
Empty constructor.
-
~GeometryData()
Destructor.
-
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.
Warning
Outer objects are not duplicated (i.e. if a is in outerObjects[b], then b is not in outerObjects[a]).
- Parameters:
geomModel – [in] the geometry model (const)
-
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.
See also
GeomData
- Parameters:
pair_id – [in] the index of the pair in GeomModel::collisionPairs vector.
-
void activateAllCollisionPairs()
Activate all collision pairs.
See also
GeomData::deactivateAllCollisionPairs, GeomData::activateCollisionPair, GeomData::deactivateCollisionPair
-
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:
geom_model – [in] Geometry model associated to the data.
collision_map – [in] Associative array.
upper – [in] Wheter the collision_map is an upper or lower triangular filled array.
-
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:
geom_model – [in] Geometry model associated to the data.
geom_id – [in] Index of the geometry.
enable_collision – [in] If true, the collision will be enable, otherwise disable.
-
void deactivateCollisionPair(const PairIndex pair_id)
Deactivate a collision pair.
Calls indeed GeomData::activateCollisionPair(pair_id)
See also
GeomData::activateCollisionPair
- Parameters:
pair_id – [in] the index of the pair in GeomModel::collisionPairs vector.
-
void deactivateAllCollisionPairs()
Deactivate all collision pairs.
See also
GeomData::activateAllCollisionPairs, GeomData::activateCollisionPair, GeomData::deactivateCollisionPair
-
inline bool operator==(const GeometryData &other) const
Returns true if *this and other are equal.
-
inline bool operator!=(const GeometryData &other) const
Returns true if *this and other are not equal.
Public Members
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef double Scalar
-
std::vector<bool> activeCollisionPairs
Vector of collision pairs.
-
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
-
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
Friends
-
friend std::ostream &operator<<(std::ostream &os, const GeometryData &geomData)