pinocchio  2.4.4
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
geometry.hpp
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_multibody_geometry_hpp__
6 #define __pinocchio_multibody_geometry_hpp__
7 
8 #include "pinocchio/multibody/fcl.hpp"
9 #include "pinocchio/multibody/fwd.hpp"
10 #include "pinocchio/container/aligned-vector.hpp"
11 
12 #include <boost/foreach.hpp>
13 #include <map>
14 #include <list>
15 #include <utility>
16 #include <assert.h>
17 
18 namespace pinocchio
19 {
20 
22  {
23  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
24 
25  typedef double Scalar;
26  enum { Options = 0 };
27 
29 
30  typedef ::pinocchio::GeometryObject GeometryObject;
31  typedef PINOCCHIO_ALIGNED_STD_VECTOR(GeometryObject) GeometryObjectVector;
32  typedef std::vector<CollisionPair> CollisionPairVector;
33 
34  typedef pinocchio::GeomIndex GeomIndex;
35 
37  : ngeoms(0)
38  , geometryObjects()
39  , collisionPairs()
40  {}
41 
42  ~GeometryModel() {};
43 
53  template<typename S2, int O2, template<typename,int> class _JointCollectionTpl>
54  GeomIndex addGeometryObject(const GeometryObject & object,
56 
64  GeomIndex addGeometryObject(const GeometryObject & object);
65 
73  GeomIndex getGeometryId(const std::string & name) const;
74 
75 
83  bool existGeometryName(const std::string & name) const;
84 
91  void addCollisionPair(const CollisionPair & pair);
92 
98  void addAllCollisionPairs();
99 
105  void removeCollisionPair(const CollisionPair& pair);
106 
111 
120  bool existCollisionPair(const CollisionPair & pair) const;
121 
129  PairIndex findCollisionPair(const CollisionPair & pair) const;
130 
131 
135  bool operator==(const GeometryModel & other) const
136  {
137  return
138  ngeoms == other.ngeoms
139  && geometryObjects == other.geometryObjects
140  && collisionPairs == other.collisionPairs
141  ;
142  }
143 
147  bool operator!=(const GeometryModel & other) const
148  {
149  return !(*this == other);
150  }
151 
152  friend std::ostream& operator<<(std::ostream & os,
153  const GeometryModel & model_geom);
154 
156  Index ngeoms;
157 
159  GeometryObjectVector geometryObjects;
163  CollisionPairVector collisionPairs;
164 
165  }; // struct GeometryModel
166 
168  {
169  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
170 
171  typedef double Scalar;
172  enum { Options = 0 };
173 
174  typedef SE3Tpl<Scalar,Options> SE3;
175  typedef std::vector<GeomIndex> GeomIndexList;
176 
184  PINOCCHIO_ALIGNED_STD_VECTOR(SE3) oMg;
185 
189  std::vector<bool> activeCollisionPairs;
190 
191 #ifdef PINOCCHIO_WITH_HPP_FCL
192  std::vector<fcl::CollisionObject> collisionObjects PINOCCHIO_DEPRECATED;
199 
204  fcl::DistanceRequest distanceRequest PINOCCHIO_DEPRECATED;
205 
209  std::vector<fcl::DistanceRequest> distanceRequests;
210 
214  std::vector<fcl::DistanceResult> distanceResults;
215 
220  fcl::CollisionRequest collisionRequest PINOCCHIO_DEPRECATED;
221 
225  std::vector<fcl::CollisionRequest> collisionRequests;
226 
230  std::vector<fcl::CollisionResult> collisionResults;
231 
236  std::vector<double> radius;
237 
245 #endif // PINOCCHIO_WITH_HPP_FCL
246 
251  std::map<JointIndex,GeomIndexList> innerObjects;
252 
257  std::map<JointIndex,GeomIndexList> outerObjects;
258 
259  GeometryData(const GeometryModel & geomModel);
260  GeometryData(const GeometryData & other);
261  ~GeometryData();
262 
272  void fillInnerOuterObjectMaps(const GeometryModel & geomModel);
273 
287  void activateCollisionPair(const PairIndex pairId);
288 
298  void deactivateCollisionPair(const PairIndex pairId);
299 
300  friend std::ostream & operator<<(std::ostream & os, const GeometryData & geomData);
301 
302  }; // struct GeometryData
303 
304 } // namespace pinocchio
305 
306 /* --- Details -------------------------------------------------------------- */
307 /* --- Details -------------------------------------------------------------- */
308 /* --- Details -------------------------------------------------------------- */
309 #include "pinocchio/multibody/geometry.hxx"
310 
311 #endif // ifndef __pinocchio_multibody_geometry_hpp__
GeomIndex getGeometryId(const std::string &name) const
Return the index of a GeometryObject given by its name.
bool operator==(const GeometryModel &other) const
Returns true if *this and other are equal.
Definition: geometry.hpp:135
GeomIndex addGeometryObject(const GeometryObject &object, const ModelTpl< S2, O2, _JointCollectionTpl > &model)
Add a geometry object to a GeometryModel and set its parent joint.
CollisionPairVector collisionPairs
Vector of collision pairs.
Definition: geometry.hpp:163
std::vector< fcl::DistanceResult > distanceResults
Vector gathering the result of the distance computation for all the collision pairs.
Definition: geometry.hpp:214
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.
Definition: geometry.hpp:230
fcl::DistanceRequest distanceRequest PINOCCHIO_DEPRECATED
Defines what information should be computed by distance computation.
Definition: geometry.hpp:204
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().
std::vector< double > radius
Radius of the bodies, i.e. distance of the further point of the geometry model attached to the body f...
Definition: geometry.hpp:236
void removeCollisionPair(const CollisionPair &pair)
Remove if exists the CollisionPair from the vector collision_pairs.
std::vector< fcl::DistanceRequest > distanceRequests
Defines what information should be computed by distance computation. There is one request per pair of...
Definition: geometry.hpp:209
std::map< JointIndex, GeomIndexList > outerObjects
A list of associated collision GeometryObjects to a given joint Id.
Definition: geometry.hpp:257
Index ngeoms
The number of GeometryObjects.
Definition: geometry.hpp:156
std::vector< bool > activeCollisionPairs
Vector of collision pairs.
Definition: geometry.hpp:189
std::map< JointIndex, GeomIndexList > innerObjects
Map over vector GeomModel::geometryObjects, indexed by joints.
Definition: geometry.hpp:251
void addAllCollisionPairs()
Add all possible collision pairs.
Main pinocchio namespace.
Definition: treeview.dox:24
fcl::CollisionRequest collisionRequest PINOCCHIO_DEPRECATED
Defines what information should be computed by collision test.
Definition: geometry.hpp:220
bool operator!=(const GeometryModel &other) const
Returns true if *this and other are not equal.
Definition: geometry.hpp:147
PairIndex collisionPairIndex
Index of the collision pair.
Definition: geometry.hpp:244
bool existGeometryName(const std::string &name) const
Check if a GeometryObject given by its name exists.
void addCollisionPair(const CollisionPair &pair)
Add a collision pair into the vector of collision_pairs. The method check before if the given Collisi...
PairIndex findCollisionPair(const CollisionPair &pair) const
Return the index of a given collision pair in collisionPairs.
std::vector< fcl::CollisionRequest > collisionRequests
Defines what information should be computed by collision test. There is one request per pair of geome...
Definition: geometry.hpp:225
GeometryObjectVector geometryObjects
Vector of GeometryObjects used for collision computations.
Definition: geometry.hpp:159