Public Types | Public Member Functions | Public Attributes | Friends | List of all members
pinocchio::GeometryModel Struct Reference

#include <geometry.hpp>

Inheritance diagram for pinocchio::GeometryModel:
Inheritance graph
[legend]

Public Types

enum  { Options = context::Options }
 
typedef std::vector< CollisionPairCollisionPairVector
 
typedef ::pinocchio::GeometryObject GeometryObject
 
typedef pinocchio::GeomIndex GeomIndex
 
typedef Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic, OptionsMatrixXb
 
typedef Eigen::Matrix< int, Eigen::Dynamic, Eigen::Dynamic, OptionsMatrixXi
 
typedef SE3Tpl< Scalar, OptionsSE3
 
- Public Types inherited from pinocchio::NumericalBase< GeometryModel >
typedef traits< GeometryModel >::Scalar Scalar
 

Public Member Functions

void addAllCollisionPairs ()
 Add all possible collision pairs. More...
 
void addCollisionPair (const CollisionPair &pair)
 Add a collision pair into the vector of collision_pairs. The method check before if the given CollisionPair is already included. More...
 
GeomIndex addGeometryObject (const GeometryObject &object)
 Add a geometry object to a GeometryModel. More...
 
template<typename S2 , int O2, template< typename, int > class _JointCollectionTpl>
GeomIndex addGeometryObject (const GeometryObject &object, const ModelTpl< S2, O2, _JointCollectionTpl > &model)
 Add a geometry object to a GeometryModel and set its parent joint. More...
 
GeometryModel clone () const
 Create a deep copy of *this. More...
 
bool existCollisionPair (const CollisionPair &pair) const
 Check if a collision pair exists in collisionPairs. See also findCollisitionPair(const CollisionPair & pair). More...
 
bool existGeometryName (const std::string &name) const
 Check if a GeometryObject given by its name exists. More...
 
PairIndex findCollisionPair (const CollisionPair &pair) const
 Return the index of a given collision pair in collisionPairs. More...
 
 GeometryModel ()
 
 GeometryModel (const GeometryModel &other)=default
 
GeomIndex getGeometryId (const std::string &name) const
 Return the index of a GeometryObject given by its name. More...
 
bool operator!= (const GeometryModel &other) const
 Returns true if *this and other are not equal. More...
 
bool operator== (const GeometryModel &other) const
 Returns true if *this and other are equal. More...
 
typedef PINOCCHIO_ALIGNED_STD_VECTOR (GeometryObject) GeometryObjectVector
 
void removeAllCollisionPairs ()
 Remove all collision pairs from collisionPairs. Same as collisionPairs.clear(). More...
 
void removeCollisionPair (const CollisionPair &pair)
 Remove if exists the CollisionPair from the vector collision_pairs. More...
 
void removeGeometryObject (const std::string &name)
 Remove a GeometryObject. More...
 
void setCollisionPairs (const MatrixXb &collision_map, const bool upper=true)
 Set the collision pairs from a given input array. Each entry of the input matrix defines the activation of a given collision pair (map[i,j] == true means that the pair (i,j) is active). More...
 
 ~GeometryModel ()
 
- Public Member Functions inherited from pinocchio::serialization::Serializable< GeometryModel >
void loadFromBinary (boost::asio::streambuf &container)
 Loads a Derived object from a binary container. More...
 
void loadFromBinary (const std::string &filename)
 Loads a Derived object from an binary file. More...
 
void loadFromBinary (StaticBuffer &container)
 Loads a Derived object from a static binary container. More...
 
void loadFromString (const std::string &str)
 Loads a Derived object from a string. More...
 
void loadFromStringStream (std::istringstream &is)
 Loads a Derived object from a stream string. More...
 
void loadFromText (const std::string &filename)
 Loads a Derived object from a text file. More...
 
void loadFromXML (const std::string &filename, const std::string &tag_name)
 Loads a Derived object from an XML file. More...
 
void saveToBinary (boost::asio::streambuf &container) const
 Saves a Derived object as a binary container. More...
 
void saveToBinary (const std::string &filename) const
 Saves a Derived object as an binary file. More...
 
void saveToBinary (StaticBuffer &container) const
 Saves a Derived object as a static binary container. More...
 
std::string saveToString () const
 Saves a Derived object to a string. More...
 
void saveToStringStream (std::stringstream &ss) const
 Saves a Derived object to a string stream. More...
 
void saveToText (const std::string &filename) const
 Saves a Derived object as a text file. More...
 
void saveToXML (const std::string &filename, const std::string &tag_name) const
 Saves a Derived object as an XML file. More...
 

Public Attributes

MatrixXi collisionPairMapping
 Matrix relating the collision pair ID to a pair of two GeometryObject indexes. More...
 
CollisionPairVector collisionPairs
 Vector of collision pairs. More...
 
GeometryObjectVector geometryObjects
 Vector of GeometryObjects used for collision computations. More...
 
Index ngeoms
 The number of GeometryObjects. More...
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef context::Scalar Scalar
 

Friends

std::ostream & operator<< (std::ostream &os, const GeometryModel &model_geom)
 

Detailed Description

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

Member Typedef Documentation

◆ CollisionPairVector

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

◆ GeometryObject

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

◆ GeomIndex

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

◆ MatrixXb

typedef Eigen::Matrix<bool, Eigen::Dynamic, Eigen::Dynamic, Options> pinocchio::GeometryModel::MatrixXb

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

◆ MatrixXi

typedef Eigen::Matrix<int, Eigen::Dynamic, Eigen::Dynamic, Options> pinocchio::GeometryModel::MatrixXi

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

◆ SE3

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

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
Options 

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

Constructor & Destructor Documentation

◆ GeometryModel() [1/2]

pinocchio::GeometryModel::GeometryModel ( )
inline

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

◆ GeometryModel() [2/2]

pinocchio::GeometryModel::GeometryModel ( const GeometryModel other)
default

◆ ~GeometryModel()

pinocchio::GeometryModel::~GeometryModel ( )
inline

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

Member Function Documentation

◆ addAllCollisionPairs()

void pinocchio::GeometryModel::addAllCollisionPairs ( )

Add all possible collision pairs.

Note
Collision pairs between geometries having the same parent joint are not added.

◆ addCollisionPair()

void pinocchio::GeometryModel::addCollisionPair ( const CollisionPair pair)

Add a collision pair into the vector of collision_pairs. The method check before if the given CollisionPair is already included.

Parameters
[in]pairThe CollisionPair to add.

◆ addGeometryObject() [1/2]

GeomIndex pinocchio::GeometryModel::addGeometryObject ( const GeometryObject object)

Add a geometry object to a GeometryModel.

Parameters
[in]objectObject
Returns
The index of the new added GeometryObject in geometryObjects.

◆ addGeometryObject() [2/2]

template<typename S2 , int O2, template< typename, int > class _JointCollectionTpl>
GeomIndex pinocchio::GeometryModel::addGeometryObject ( const GeometryObject object,
const ModelTpl< S2, O2, _JointCollectionTpl > &  model 
)

Add a geometry object to a GeometryModel and set its parent joint.

Parameters
[in]objectObject
[in]modelCorresponding model, used to assert the attributes of object.
Returns
The index of the new added GeometryObject in geometryObjects
Note
object is a nonconst copy to ease the insertion code.

◆ clone()

GeometryModel pinocchio::GeometryModel::clone ( ) const

Create a deep copy of *this.

◆ existCollisionPair()

bool pinocchio::GeometryModel::existCollisionPair ( const CollisionPair pair) const

Check if a collision pair exists in collisionPairs. See also findCollisitionPair(const CollisionPair & pair).

Parameters
[in]pairThe CollisionPair.
Returns
True if the CollisionPair exists, false otherwise.

◆ existGeometryName()

bool pinocchio::GeometryModel::existGeometryName ( const std::string &  name) const

Check if a GeometryObject given by its name exists.

Parameters
[in]nameName of the GeometryObject
Returns
True if the GeometryObject exists in the geometryObjects.

◆ findCollisionPair()

PairIndex pinocchio::GeometryModel::findCollisionPair ( const CollisionPair pair) const

Return the index of a given collision pair in collisionPairs.

Parameters
[in]pairThe CollisionPair.
Returns
The index of the CollisionPair in collisionPairs.

◆ getGeometryId()

GeomIndex pinocchio::GeometryModel::getGeometryId ( const std::string &  name) const

Return the index of a GeometryObject given by its name.

Parameters
[in]nameName of the GeometryObject
Returns
Index of the corresponding GeometryObject

◆ operator!=()

bool pinocchio::GeometryModel::operator!= ( const GeometryModel other) const
inline

Returns true if *this and other are not equal.

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

◆ operator==()

bool pinocchio::GeometryModel::operator== ( const GeometryModel other) const
inline

Returns true if *this and other are equal.

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR()

typedef pinocchio::GeometryModel::PINOCCHIO_ALIGNED_STD_VECTOR ( GeometryObject  )

◆ removeAllCollisionPairs()

void pinocchio::GeometryModel::removeAllCollisionPairs ( )

Remove all collision pairs from collisionPairs. Same as collisionPairs.clear().

◆ removeCollisionPair()

void pinocchio::GeometryModel::removeCollisionPair ( const CollisionPair pair)

Remove if exists the CollisionPair from the vector collision_pairs.

Parameters
[in]pairThe CollisionPair to remove.

◆ removeGeometryObject()

void pinocchio::GeometryModel::removeGeometryObject ( const std::string &  name)

Remove a GeometryObject.

Parameters
[in]nameName of the GeometryObject

@node Remove also the collision pairs that contain the object.

◆ setCollisionPairs()

void pinocchio::GeometryModel::setCollisionPairs ( const MatrixXb collision_map,
const bool  upper = true 
)

Set the collision pairs from a given input array. Each entry of the input matrix defines the activation of a given collision pair (map[i,j] == true means that the pair (i,j) is active).

Parameters
[in]collision_mapAssociative array.
[in]upperWheter the collision_map is an upper or lower triangular filled array.

Friends And Related Function Documentation

◆ operator<<

std::ostream& operator<< ( std::ostream &  os,
const GeometryModel model_geom 
)
friend

Member Data Documentation

◆ collisionPairMapping

MatrixXi pinocchio::GeometryModel::collisionPairMapping

Matrix relating the collision pair ID to a pair of two GeometryObject indexes.

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

◆ collisionPairs

CollisionPairVector pinocchio::GeometryModel::collisionPairs

Vector of collision pairs.

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

◆ geometryObjects

GeometryObjectVector pinocchio::GeometryModel::geometryObjects

Vector of GeometryObjects used for collision computations.

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

◆ ngeoms

Index pinocchio::GeometryModel::ngeoms

The number of GeometryObjects.

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

◆ Scalar

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef context::Scalar pinocchio::GeometryModel::Scalar

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


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


pinocchio
Author(s):
autogenerated on Fri Jun 7 2024 02:40:52