Go to the documentation of this file.
5 #ifndef __pinocchio_multibody_geometry_hpp__
6 #define __pinocchio_multibody_geometry_hpp__
24 typedef std::pair<GeomIndex, GeomIndex>
Base;
39 void disp(std::ostream & os)
const;
54 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
67 typedef Eigen::Matrix<bool, Eigen::Dynamic, Eigen::Dynamic, Options>
MatrixXb;
68 typedef Eigen::Matrix<int, Eigen::Dynamic, Eigen::Dynamic, Options>
MatrixXi;
92 template<
typename S2,
int O2,
template<
typename,
int>
class _JointCollectionTpl>
208 return !(*
this == other);
237 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
247 typedef Eigen::Matrix<bool, Eigen::Dynamic, Eigen::Dynamic, Options>
MatrixXb;
248 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options>
MatrixXs;
250 #ifdef PINOCCHIO_WITH_HPP_FCL
251 typedef ::pinocchio::ComputeCollision ComputeCollision;
252 typedef ::pinocchio::ComputeDistance ComputeDistance;
269 #ifdef PINOCCHIO_WITH_HPP_FCL
274 std::vector<fcl::DistanceRequest> distanceRequests;
279 std::vector<fcl::DistanceResult> distanceResults;
284 std::vector<fcl::CollisionRequest> collisionRequests;
289 std::vector<fcl::CollisionResult> collisionResults;
295 std::vector<Scalar>
radius;
311 #endif // PINOCCHIO_WITH_HPP_FCL
428 #ifdef PINOCCHIO_WITH_HPP_FCL
429 void setSecurityMargins(
441 const MatrixXs & security_margin_map,
442 const bool upper =
true,
443 const bool sync_distance_upper_bound =
false);
445 #endif // ifdef PINOCCHIO_WITH_HPP_FCL
455 #ifdef PINOCCHIO_WITH_HPP_FCL
456 && distanceRequests == other.distanceRequests
457 && distanceResults == other.distanceResults
458 && collisionRequests == other.collisionRequests
459 && collisionResults == other.collisionResults &&
radius == other.radius
460 && collisionPairIndex == other.collisionPairIndex
470 return !(*
this == other);
480 #include "pinocchio/multibody/geometry.hxx"
482 #endif // ifndef __pinocchio_multibody_geometry_hpp__
SE3Tpl< Scalar, Options > SE3
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
GeometryModel clone() const
Create a deep copy of *this.
GeomIndex getGeometryId(const std::string &name) const
Return the index of a GeometryObject given by its name.
void addCollisionPair(const CollisionPair &pair)
Add a collision pair into the vector of collision_pairs. The method check before if the given Collisi...
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 t...
pinocchio::GeomIndex GeomIndex
Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXb
typedef PINOCCHIO_ALIGNED_STD_VECTOR(GeometryObject) GeometryObjectVector
void fillInnerOuterObjectMaps(const GeometryModel &geomModel)
PINOCCHIO_ALIGNED_STD_VECTOR(SE3) oMg
Vector gathering the SE3 placements of the geometry objects relative to the world....
void removeGeometryObject(const std::string &name)
Remove a GeometryObject.
std::string name(const LieGroupGenericTpl< LieGroupCollection > &lg)
Visit a LieGroupVariant to get the name of it.
::pinocchio::GeometryObject GeometryObject
void activateCollisionPair(const PairIndex pair_id)
std::pair< GeomIndex, GeomIndex > Base
GeometryData()
Empty constructor.
bool operator==(const GeometryData &other) const
Returns true if *this and other are equal.
std::vector< CollisionPair > CollisionPairVector
bool operator==(const GeometryModel &other) const
Returns true if *this and other are equal.
friend std::ostream & operator<<(std::ostream &os, const CollisionPair &X)
std::map< JointIndex, GeomIndexList > outerObjects
A list of associated collision GeometryObjects to a given joint Id.
~GeometryData()
Destructor.
void addAllCollisionPairs()
Add all possible collision pairs.
bool existCollisionPair(const CollisionPair &pair) const
Check if a collision pair exists in collisionPairs. See also findCollisitionPair(const CollisionPair ...
void removeAllCollisionPairs()
Remove all collision pairs from collisionPairs. Same as collisionPairs.clear().
GeometryData & operator=(const GeometryData &other)
Copy operator.
friend std::ostream & operator<<(std::ostream &os, const GeometryModel &model_geom)
PINOCCHIO_COMPILER_DIAGNOSTIC_POP typedef std::size_t Index
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef context::Scalar Scalar
GeometryObjectVector geometryObjects
Vector of GeometryObjects used for collision computations.
MatrixXi collisionPairMapping
Matrix relating the collision pair ID to a pair of two GeometryObject indexes.
std::vector< bool > activeCollisionPairs
Vector of collision pairs.
PairIndex findCollisionPair(const CollisionPair &pair) const
Return the index of a given collision pair in collisionPairs.
void deactivateAllCollisionPairs()
Deactivate all collision pairs.
CollisionPair()
Empty constructor.
Index ngeoms
The number of GeometryObjects.
Eigen::Matrix< int, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXi
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 geomet...
friend std::ostream & operator<<(std::ostream &os, const GeometryData &geomData)
bool operator==(const CollisionPair &rhs) const
bool operator!=(const GeometryData &other) const
Returns true if *this and other are not equal.
void deactivateCollisionPair(const PairIndex pair_id)
GeomIndex addGeometryObject(const GeometryObject &object, const ModelTpl< S2, O2, _JointCollectionTpl > &model)
Add a geometry object to a GeometryModel and set its parent joint.
std::map< JointIndex, GeomIndexList > innerObjects
Map over vector GeomModel::geometryObjects, indexed by joints.
void activateAllCollisionPairs()
Activate all collision pairs.
CollisionPairVector collisionPairs
Vector of collision pairs.
Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXb
void disp(std::ostream &os) const
SE3Tpl< Scalar, Options > SE3
std::vector< GeomIndex > GeomIndexList
bool operator!=(const GeometryModel &other) const
Returns true if *this and other are not equal.
bool existGeometryName(const std::string &name) const
Check if a GeometryObject given by its name exists.
Common traits structure to fully define base classes for CRTP.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef context::Scalar Scalar
void removeCollisionPair(const CollisionPair &pair)
Remove if exists the CollisionPair from the vector collision_pairs.
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 activati...
PINOCCHIO_SCALAR_TYPE Scalar
JointCollectionTpl & model
bool operator!=(const CollisionPair &rhs) const
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:44