#include <geometry.hpp>
Public Types | |
| enum | { Options = 0 } |
| typedef std::vector< CollisionPair > | CollisionPairVector |
| typedef ::pinocchio::GeometryObject | GeometryObject |
| typedef pinocchio::GeomIndex | GeomIndex |
| typedef Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic, Options > | MatrixXb |
| typedef SE3Tpl< Scalar, Options > | SE3 |
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 | 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 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) |
Definition at line 22 of file src/multibody/geometry.hpp.
| typedef std::vector<CollisionPair> pinocchio::GeometryModel::CollisionPairVector |
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.
| typedef SE3Tpl<Scalar,Options> pinocchio::GeometryModel::SE3 |
Definition at line 29 of file src/multibody/geometry.hpp.
| anonymous enum |
| Enumerator | |
|---|---|
| Options | |
Definition at line 27 of file src/multibody/geometry.hpp.
|
inline |
Definition at line 38 of file src/multibody/geometry.hpp.
|
inline |
Definition at line 44 of file src/multibody/geometry.hpp.
| void pinocchio::GeometryModel::addAllCollisionPairs | ( | ) |
Add all possible collision pairs.
| 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.
| [in] | pair | The CollisionPair to add. |
| 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.
| [in] | object | Object |
| [in] | model | Corresponding model, used to assert the attributes of object. |
| GeomIndex pinocchio::GeometryModel::addGeometryObject | ( | const GeometryObject & | object | ) |
Add a geometry object to a GeometryModel.
| [in] | object | Object |
| bool pinocchio::GeometryModel::existCollisionPair | ( | const CollisionPair & | pair | ) | const |
Check if a collision pair exists in collisionPairs. See also findCollisitionPair(const CollisionPair & pair).
| [in] | pair | The CollisionPair. |
| bool pinocchio::GeometryModel::existGeometryName | ( | const std::string & | name | ) | const |
Check if a GeometryObject given by its name exists.
| [in] | name | Name of the GeometryObject |
| PairIndex pinocchio::GeometryModel::findCollisionPair | ( | const CollisionPair & | pair | ) | const |
Return the index of a given collision pair in collisionPairs.
| [in] | pair | The CollisionPair. |
| GeomIndex pinocchio::GeometryModel::getGeometryId | ( | const std::string & | name | ) | const |
Return the index of a GeometryObject given by its name.
| [in] | name | Name of the GeometryObject |
|
inline |
Returns true if *this and other are not equal.
Definition at line 168 of file src/multibody/geometry.hpp.
|
inline |
Returns true if *this and other are equal.
Definition at line 156 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.
| [in] | pair | The CollisionPair to remove. |
| void pinocchio::GeometryModel::removeGeometryObject | ( | const std::string & | name | ) |
Remove a GeometryObject.
| [in] | name | Name of the GeometryObject |
Remove also the collision pairs that contain the object.
| 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).
| [in] | collision_map | Associative array. |
| [in] | upper | Wheter the collision_map is an upper or lower triangular filled array. |
|
friend |
| CollisionPairVector pinocchio::GeometryModel::collisionPairs |
Vector of collision pairs.
Definition at line 183 of file src/multibody/geometry.hpp.
| GeometryObjectVector pinocchio::GeometryModel::geometryObjects |
Vector of GeometryObjects used for collision computations.
Definition at line 180 of file src/multibody/geometry.hpp.
| Index pinocchio::GeometryModel::ngeoms |
The number of GeometryObjects.
Definition at line 177 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.