5 #ifndef __pinocchio_multibody_geometry_hpp__ 6 #define __pinocchio_multibody_geometry_hpp__ 8 #include "pinocchio/multibody/fcl.hpp" 9 #include "pinocchio/multibody/fwd.hpp" 10 #include "pinocchio/container/aligned-vector.hpp" 12 #include "pinocchio/serialization/serializable.hpp" 24 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
34 typedef Eigen::Matrix<bool,Eigen::Dynamic,Eigen::Dynamic,Options>
MatrixXb;
55 template<
typename S2,
int O2,
template<
typename,
int>
class _JointCollectionTpl>
120 const bool upper =
true);
170 return !(*
this == other);
173 friend std::ostream&
operator<<(std::ostream & os,
190 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
197 typedef Eigen::Matrix<bool,Eigen::Dynamic,Eigen::Dynamic,Options>
MatrixXb;
198 typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic,Options>
MatrixXs;
200 #ifdef PINOCCHIO_WITH_HPP_FCL 201 typedef ::pinocchio::ComputeCollision ComputeCollision;
202 typedef ::pinocchio::ComputeDistance ComputeDistance;
219 #ifdef PINOCCHIO_WITH_HPP_FCL 224 std::vector<fcl::DistanceRequest> distanceRequests;
229 std::vector<fcl::DistanceResult> distanceResults;
234 std::vector<fcl::CollisionRequest> collisionRequests;
239 std::vector<fcl::CollisionResult> collisionResults;
245 std::vector<Scalar>
radius;
261 #endif // PINOCCHIO_WITH_HPP_FCL 311 void fillInnerOuterObjectMaps(
const GeometryModel & geomModel);
326 void activateCollisionPair(
const PairIndex pair_id);
333 void activateAllCollisionPairs();
344 const MatrixXb & collision_map,
345 const bool upper =
true);
354 void setGeometryCollisionStatus(
const GeometryModel & geom_model,
356 bool enable_collision);
367 void deactivateCollisionPair(
const PairIndex pair_id);
374 void deactivateAllCollisionPairs();
376 #ifdef PINOCCHIO_WITH_HPP_FCL 385 const MatrixXs & security_margin_map,
386 const bool upper =
true);
387 #endif // ifdef PINOCCHIO_WITH_HPP_FCL 399 #ifdef PINOCCHIO_WITH_HPP_FCL 400 && distanceRequests == other.distanceRequests
401 && distanceResults == other.distanceResults
402 && collisionRequests == other.collisionRequests
403 && collisionResults == other.collisionResults
404 && radius == other.radius
405 && collisionPairIndex == other.collisionPairIndex
417 return !(*
this == other);
427 #include "pinocchio/multibody/geometry.hxx" 429 #endif // ifndef __pinocchio_multibody_geometry_hpp__ GeometryData()
Empty constructor.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef double Scalar
Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXb
Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXb
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef double Scalar
SE3Tpl< Scalar, Options > SE3
CollisionPairVector collisionPairs
Vector of collision pairs.
std::string name(const LieGroupGenericTpl< LieGroupCollection > &lg)
Visit a LieGroupVariant to get the name of it.
bool existCollisionPair(const CollisionPair &pair) const
Check if a collision pair exists in collisionPairs. See also findCollisitionPair(const CollisionPair ...
std::map< JointIndex, GeomIndexList > innerObjects
Map over vector GeomModel::geometryObjects, indexed by joints.
std::vector< bool > activeCollisionPairs
Vector of collision pairs.
bool operator==(const GeometryModel &other) const
Returns true if *this and other are equal.
PairIndex findCollisionPair(const CollisionPair &pair) const
Return the index of a given collision pair in collisionPairs.
bool operator!=(const GeometryModel &other) const
Returns true if *this and other are not equal.
void removeCollisionPair(const CollisionPair &pair)
Remove if exists the CollisionPair from the vector collision_pairs.
std::vector< GeomIndex > GeomIndexList
bool operator!=(const GeometryData &other) const
Returns true if *this and other are not equal.
void removeGeometryObject(const std::string &name)
Remove a GeometryObject.
GeometryObjectVector geometryObjects
Vector of GeometryObjects used for collision computations.
GeomIndex getGeometryId(const std::string &name) const
Return the index of a GeometryObject given by its name.
bool existGeometryName(const std::string &name) const
Check if a GeometryObject given by its name exists.
std::map< JointIndex, GeomIndexList > outerObjects
A list of associated collision GeometryObjects to a given joint Id.
Index ngeoms
The number of GeometryObjects.
void addAllCollisionPairs()
Add all possible 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...
typedef PINOCCHIO_ALIGNED_STD_VECTOR(GeometryObject) GeometryObjectVector
Main pinocchio namespace.
void addCollisionPair(const CollisionPair &pair)
Add a collision pair into the vector of collision_pairs. The method check before if the given Collisi...
AABB & operator=(const AABB &other)=default
std::vector< CollisionPair > CollisionPairVector
pinocchio::GeomIndex GeomIndex
void removeAllCollisionPairs()
Remove all collision pairs from collisionPairs. Same as collisionPairs.clear().
friend std::ostream & operator<<(std::ostream &os, const GeometryModel &model_geom)
::pinocchio::GeometryObject GeometryObject
bool operator==(const GeometryData &other) const
Returns true if *this and other are equal.
JointCollectionTpl & model
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
GeomIndex addGeometryObject(const GeometryObject &object, const ModelTpl< S2, O2, _JointCollectionTpl > &model)
Add a geometry object to a GeometryModel and set its parent joint.
SE3Tpl< Scalar, Options > SE3