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

#include <geometry.hpp>

Public Types

enum  { Options = 0 }
 
typedef std::vector< CollisionPairCollisionPairVector
 
typedef ::pinocchio::GeometryObject GeometryObject
 
typedef pinocchio::GeomIndex GeomIndex
 
typedef Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic, OptionsMatrixXb
 
typedef SE3Tpl< Scalar, OptionsSE3
 

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...
 
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...
 
GeomIndex addGeometryObject (const GeometryObject &object)
 Add a geometry object to a GeometryModel. 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 ()
 
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 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 Attributes

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 double Scalar
 

Friends

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

Detailed Description

Definition at line 22 of file src/multibody/geometry.hpp.

Member Typedef Documentation

Definition at line 33 of file src/multibody/geometry.hpp.

Definition at line 31 of file src/multibody/geometry.hpp.

Definition at line 36 of file src/multibody/geometry.hpp.

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

Definition at line 34 of file src/multibody/geometry.hpp.

Definition at line 29 of file src/multibody/geometry.hpp.

Member Enumeration Documentation

anonymous enum
Enumerator
Options 

Definition at line 27 of file src/multibody/geometry.hpp.

Constructor & Destructor Documentation

pinocchio::GeometryModel::GeometryModel ( )
inline

Definition at line 38 of file src/multibody/geometry.hpp.

pinocchio::GeometryModel::~GeometryModel ( )
inline

Definition at line 44 of file src/multibody/geometry.hpp.

Member Function Documentation

void pinocchio::GeometryModel::addAllCollisionPairs ( )

Add all possible collision pairs.

Note
Collision pairs between geometries having the same parent joint are not added.
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.
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.
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.
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.
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.
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.
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
bool pinocchio::GeometryModel::operator!= ( const GeometryModel other) const
inline

Returns true if *this and other are not equal.

Definition at line 159 of file src/multibody/geometry.hpp.

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

Returns true if *this and other are equal.

Definition at line 147 of file src/multibody/geometry.hpp.

typedef pinocchio::GeometryModel::PINOCCHIO_ALIGNED_STD_VECTOR ( GeometryObject  )
void pinocchio::GeometryModel::removeAllCollisionPairs ( )

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

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

Remove if exists the CollisionPair from the vector collision_pairs.

Parameters
[in]pairThe CollisionPair to remove.
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

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

Member Data Documentation

CollisionPairVector pinocchio::GeometryModel::collisionPairs

Vector of collision pairs.

Definition at line 174 of file src/multibody/geometry.hpp.

GeometryObjectVector pinocchio::GeometryModel::geometryObjects

Vector of GeometryObjects used for collision computations.

Definition at line 171 of file src/multibody/geometry.hpp.

Index pinocchio::GeometryModel::ngeoms

The number of GeometryObjects.

Definition at line 168 of file src/multibody/geometry.hpp.

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef double pinocchio::GeometryModel::Scalar

Definition at line 26 of file src/multibody/geometry.hpp.


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


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:05