5 #ifndef __pinocchio_multibody_geometry_hpp__ 6 #define __pinocchio_multibody_geometry_hpp__ 8 #include "pinocchio/multibody/fcl.hpp" 9 #include "pinocchio/multibody/model.hpp" 10 #include "pinocchio/container/aligned-vector.hpp" 14 #include <boost/foreach.hpp> 25 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
27 typedef double Scalar;
33 typedef std::vector<CollisionPair> CollisionPairVector;
35 typedef pinocchio::GeomIndex GeomIndex;
52 const std::size_t num_max_collision_pairs = (ngeoms * (ngeoms-1))/2;
53 collisionPairs.reserve(num_max_collision_pairs);
69 template<
typename S2,
int O2,
template<
typename,
int>
class _JointCollectionTpl>
73 const bool autofillJointParent)
75 if(autofillJointParent)
90 template<
typename S2,
int O2,
template<
typename,
int>
class _JointCollectionTpl>
130 PINOCCHIO_DEPRECATED
const std::string &
getGeometryName(
const GeomIndex index)
const;
132 #ifdef PINOCCHIO_WITH_HPP_FCL 179 #endif // PINOCCHIO_WITH_HPP_FCL 181 friend std::ostream& operator<<(std::ostream & os,
const GeometryModel & model_geom);
186 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
188 typedef double Scalar;
189 enum { Options = 0 };
202 #ifdef PINOCCHIO_WITH_HPP_FCL 203 std::vector<fcl::CollisionObject> collisionObjects;
250 typedef std::vector<GeomIndex> GeomIndexList;
263 #endif // PINOCCHIO_WITH_HPP_FCL 268 #ifdef PINOCCHIO_WITH_HPP_FCL 279 void fillInnerOuterObjectMaps(
const GeometryModel & geomModel);
291 void activateCollisionPair(
const PairIndex pairId,
const bool flag);
306 void activateCollisionPair(
const PairIndex pairId);
317 void deactivateCollisionPair(
const PairIndex pairId);
319 #endif //PINOCCHIO_WITH_HPP_FCL 320 friend std::ostream & operator<<(std::ostream & os,
const GeometryData & geomData);
329 #include "pinocchio/multibody/geometry.hxx" 331 #endif // ifndef __pinocchio_multibody_geometry_hpp__
bool existGeometryName(const std::string &name) const
Check if a GeometryObject given by its name exists.
container::aligned_vector< SE3 > oMg
Vector gathering the SE3 placements of the geometry objects relative to the world. See updateGeometryPlacements to update the placements.
CollisionPairVector collisionPairs
Vector of collision pairs.
std::map< JointIndex, GeomIndexList > outerObjects
A list of associated collision GeometryObjects to a given joint Id.
GeomIndex getGeometryId(const std::string &name) const
Return the index of a GeometryObject given by its name.
std::vector< fcl::DistanceResult > distanceResults
Vector gathering the result of the distance computation for all the collision pairs.
std::string name(const LieGroupGenericTpl< LieGroupCollection > &lg)
Visit a LieGroupVariant to get the name of it.
std::vector< fcl::CollisionResult > collisionResults
Vector gathering the result of the collision computation for all the collision pairs.
void removeAllCollisionPairs()
Remove all collision pairs from collisionPairs. Same as collisionPairs.clear().
std::vector< double > radius
Radius of the bodies, i.e. distance of the further point of the geometry model attached to the body f...
void removeCollisionPair(const CollisionPair &pair)
Remove if exists the CollisionPair from the vector collision_pairs.
fcl::DistanceRequest distanceRequest
Defines what information should be computed by distance computation.
PINOCCHIO_DEPRECATED const std::string & getGeometryName(const GeomIndex index) const
Get the name of a GeometryObject given by its index.
Index ngeoms
The number of GeometryObjects.
std::vector< bool > activeCollisionPairs
Vector of collision pairs.
void addAllCollisionPairs()
Add all possible collision pairs.
PINOCCHIO_DEPRECATED GeomIndex addGeometryObject(GeometryObject object, const ModelTpl< S2, O2, _JointCollectionTpl > &model, const bool autofillJointParent)
Add a geometry object to a GeometryModel.
Main pinocchio namespace.
fcl::CollisionRequest collisionRequest
Defines what information should be computed by collision test.
std::map< JointIndex, GeomIndexList > innerObjects
Map over vector GeomModel::geometryObjects, indexed by joints.
PairIndex collisionPairIndex
index of the collision pair
PairIndex findCollisionPair(const CollisionPair &pair) const
Return the index of a given collision pair in collisionPairs.
bool existCollisionPair(const CollisionPair &pair) const
Check if a collision pair exists in collisionPairs. See also findCollisitionPair(const CollisionPair ...
void addCollisionPair(const CollisionPair &pair)
Add a collision pair into the vector of collision_pairs. The method check before if the given Collisi...
GeometryObjectVector geometryObjects
Vector of GeometryObjects used for collision computations.