GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: include/pinocchio/multibody/fcl.hpp Lines: 49 56 87.5 %
Date: 2024-01-23 21:41:47 Branches: 16 32 50.0 %

Line Branch Exec Source
1
//
2
// Copyright (c) 2015-2023 CNRS INRIA
3
//
4
5
#ifndef __pinocchio_multibody_fcl_hpp__
6
#define __pinocchio_multibody_fcl_hpp__
7
8
#include "pinocchio/spatial/se3.hpp"
9
#include "pinocchio/multibody/fwd.hpp"
10
#include "pinocchio/container/aligned-vector.hpp"
11
12
/// Be carefull to include this header after fwd.hpp.
13
/// fwd.hpp contains some define to change the boost::variant max size.
14
/// If we don't include it before, default size is choosed that can
15
/// make all the build fail.
16
#include <boost/variant.hpp>
17
18
#ifdef PINOCCHIO_WITH_HPP_FCL
19
20
  #if(WIN32)
21
    // It appears that std::snprintf is missing for Windows.
22
    #if !(( defined(_MSC_VER) && _MSC_VER < 1900 ) || ( defined(__MINGW32__) && !defined(__MINGW64_VERSION_MAJOR) ))
23
      #include <cstdio>
24
      #include <stdarg.h>
25
      namespace std
26
      {
27
        inline int _snprintf(char* buffer, std::size_t buf_size, const char* format, ...)
28
        {
29
          int res;
30
31
          va_list args;
32
          va_start(args, format);
33
          res = vsnprintf(buffer, buf_size, format, args);
34
          va_end(args);
35
36
          return res;
37
        }
38
      }
39
    #endif
40
  #endif
41
42
  #include <hpp/fcl/collision_object.h>
43
  #include <hpp/fcl/collision.h>
44
  #include <hpp/fcl/distance.h>
45
  #include <hpp/fcl/shape/geometric_shapes.h>
46
  #include "pinocchio/spatial/fcl-pinocchio-conversions.hpp"
47
#endif
48
49
#include <iostream>
50
#include <map>
51
#include <vector>
52
#include <utility>
53
#include <limits>
54
#include <assert.h>
55
56
#include <memory>
57
58
#include <boost/foreach.hpp>
59
60
namespace pinocchio
61
{
62
  using std::shared_ptr;
63
  using std::make_shared;
64
65
  struct CollisionPair
66
  : public std::pair<GeomIndex, GeomIndex>
67
  {
68
69
    typedef std::pair<GeomIndex, GeomIndex> Base;
70
71
    /// \brief Empty constructor
72
    CollisionPair();
73
74
    ///
75
    /// \brief Default constructor of a collision pair from two collision object indexes.
76
    /// \remarks The two indexes must be different, otherwise the constructor throws.
77
    ///
78
    /// \param[in] co1 Index of the first collision object.
79
    /// \param[in] co2 Index of the second collision object.
80
    ///
81
    CollisionPair(const GeomIndex co1, const GeomIndex co2);
82
    bool                  operator == (const CollisionPair& rhs) const;
83
    bool                  operator != (const CollisionPair& rhs) const;
84
    void                  disp        (std::ostream & os)        const;
85
    friend std::ostream & operator << (std::ostream & os,const CollisionPair & X);
86
87
  }; // struct CollisionPair
88
89
#ifndef PINOCCHIO_WITH_HPP_FCL
90
91
  namespace fcl
92
  {
93
94
    struct FakeCollisionGeometry
95
    {
96
      FakeCollisionGeometry(){};
97
98
      bool operator==(const FakeCollisionGeometry &) const
99
      {
100
        return true;
101
      }
102
    };
103
104
    struct AABB
105
    {
106
      AABB(): min_(0), max_(1){};
107
108
      int min_;
109
      int max_;
110
    };
111
112
    typedef FakeCollisionGeometry CollisionGeometry;
113
114
  }
115
116
#else
117
118
  namespace fcl = hpp::fcl;
119
120
#endif // PINOCCHIO_WITH_HPP_FCL
121
122
enum GeometryType
123
{
124
  VISUAL,
125
  COLLISION
126
};
127
128
/// No material associated to a geometry.
129
struct GeometryNoMaterial
130
{
131
};
132
133
/// Mesh material based on the Phong lighting model.
134
/// Diffuse color is stored in \p GeometryObject::meshColor.
135
struct GeometryPhongMaterial
136
{
137
  GeometryPhongMaterial() = default;
138
  GeometryPhongMaterial(const Eigen::Vector4d& meshEmissionColor,
139
                        const Eigen::Vector4d& meshSpecularColor,
140
                        double meshShininess)
141
    : meshEmissionColor(meshEmissionColor)
142
    , meshSpecularColor(meshSpecularColor)
143
    , meshShininess(meshShininess)
144
  {}
145
146
  /// \brief RGBA emission (ambient) color value of the GeometryObject::geometry object.
147
  Eigen::Vector4d meshEmissionColor{Eigen::Vector4d(0., 0., 0., 1.)};
148
149
  /// \brief RGBA specular color value of the GeometryObject::geometry object.
150
  Eigen::Vector4d meshSpecularColor{Eigen::Vector4d(0., 0., 0., 1.)};
151
152
  /// \brief Shininess associated to the specular lighting model.
153
  ///
154
  /// This value must normalized between 0 and 1.
155
  double meshShininess{0.};
156
};
157
158
typedef boost::variant<GeometryNoMaterial, GeometryPhongMaterial> GeometryMaterial;
159
160
struct GeometryObject
161
{
162
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
163
164
  typedef shared_ptr<fcl::CollisionGeometry> CollisionGeometryPtr;
165
166
  /// \brief Name of the geometry object
167
  std::string name;
168
169
  /// \brief Index of the parent frame
170
  ///
171
  /// Parent frame may be unset (to the std::numeric_limits<FrameIndex>::max() value) as it is mostly used as a documentation of the tree, or in third-party libraries.
172
  /// The URDF parser of Pinocchio is setting it to the proper value according to the urdf link-joint tree.
173
  /// In particular, anchor joints of URDF would cause parent frame to be different to joint frame.
174
  FrameIndex parentFrame;
175
176
  /// \brief Index of the parent joint
177
  JointIndex parentJoint;
178
179
  /// \brief The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
180
  CollisionGeometryPtr geometry;
181
182
  /// \brief The former pointer to the FCL CollisionGeometry.
183
  /// \deprecated It is now deprecated and has been renamed GeometryObject::geometry
184
  PINOCCHIO_DEPRECATED CollisionGeometryPtr & fcl;
185
186
  /// \brief Position of geometry object in parent joint frame
187
  SE3 placement;
188
189
  /// \brief Absolute path to the mesh file (if the geometry pointee is also a Mesh)
190
  std::string meshPath;
191
192
  /// \brief Scaling vector applied to the GeometryObject::geometry object.
193
  Eigen::Vector3d meshScale;
194
195
  /// \brief Decide whether to override the Material.
196
  bool overrideMaterial;
197
198
  /// \brief RGBA diffuse color value of the GeometryObject::geometry object.
199
  Eigen::Vector4d meshColor;
200
201
  /// \brief Material associated to the mesh.
202
  /// This material should be used only if overrideMaterial is set to true.
203
  /// In other case, the mesh default material must be used.
204
  GeometryMaterial meshMaterial;
205
206
  /// \brief Absolute path to the mesh texture file.
207
  std::string meshTexturePath;
208
209
  /// \brief If true, no collision or distance check will be done between the Geometry and any other geometry
210
  bool disableCollision;
211
212
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
213
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
214
  ///
215
  /// \brief Full constructor.
216
  ///
217
  /// \param[in] name  Name of the geometry object.
218
  /// \param[in] parent_frame  Index of the parent frame.
219
  /// \param[in] parent_joint  Index of the parent joint (that supports the geometry).
220
  /// \param[in] collision_geometry The FCL collision geometry object.
221
  /// \param[in] placement Placement of the geometry with respect to the joint frame.
222
  /// \param[in] meshPath Path of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable].
223
  /// \param[in] meshScale Scale of the mesh [if applicable].
224
  /// \param[in] overrideMaterial If true, this option allows to overrite the material [if applicable].
225
  /// \param[in] meshColor Color of the mesh [if applicable].
226
  /// \param[in] meshTexturePath Path to the file containing the texture information [if applicable].
227
  /// \param[in] meshMaterial Material of the mesh [if applicable].
228
  ///
229
918
  GeometryObject(const std::string & name,
230
                 const FrameIndex parent_frame,
231
                 const JointIndex parent_joint,
232
                 const CollisionGeometryPtr & collision_geometry,
233
                 const SE3 & placement,
234
                 const std::string & meshPath = "",
235
                 const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
236
                 const bool overrideMaterial = false,
237
                 const Eigen::Vector4d & meshColor = Eigen::Vector4d(0,0,0,1),
238
                 const std::string & meshTexturePath = "",
239
                 const GeometryMaterial& meshMaterial = GeometryNoMaterial())
240
918
  : name(name)
241
  , parentFrame(parent_frame)
242
  , parentJoint(parent_joint)
243
  , geometry(collision_geometry)
244
918
  , fcl(geometry)
245
  , placement(placement)
246
  , meshPath(meshPath)
247
  , meshScale(meshScale)
248
  , overrideMaterial(overrideMaterial)
249
  , meshColor(meshColor)
250
  , meshMaterial(meshMaterial)
251
  , meshTexturePath(meshTexturePath)
252



918
  , disableCollision(false)
253
918
  {}
254
PINOCCHIO_COMPILER_DIAGNOSTIC_POP
255
256
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
257
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
258
  ///
259
  /// \brief Reduced constructor.
260
  /// \remarks Compared to the other constructor, this one assumes that there is no parentFrame associated to the geometry.
261
  ///
262
  /// \param[in] name  Name of the geometry object.
263
  /// \param[in] parent_joint  Index of the parent joint (that supports the geometry).
264
  /// \param[in] collision_geometry The FCL collision geometry object.
265
  /// \param[in] placement Placement of the geometry with respect to the joint frame.
266
  /// \param[in] meshPath Path of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable].
267
  /// \param[in] meshScale Scale of the mesh [if applicable].
268
  /// \param[in] overrideMaterial If true, this option allows to overrite the material [if applicable].
269
  /// \param[in] meshColor Color of the mesh [if applicable].
270
  /// \param[in] meshTexturePath Path to the file containing the texture information [if applicable].
271
  /// \param[in] meshMaterial Material of the mesh [if applicable].
272
  ///
273
7
  GeometryObject(const std::string & name,
274
                 const JointIndex parent_joint,
275
                 const CollisionGeometryPtr & collision_geometry,
276
                 const SE3 & placement,
277
                 const std::string & meshPath = "",
278
                 const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
279
                 const bool overrideMaterial = false,
280
                 const Eigen::Vector4d & meshColor = Eigen::Vector4d::Ones(),
281
                 const std::string & meshTexturePath = "",
282
                 const GeometryMaterial& meshMaterial = GeometryNoMaterial())
283
7
  : name(name)
284
7
  , parentFrame(std::numeric_limits<FrameIndex>::max())
285
  , parentJoint(parent_joint)
286
  , geometry(collision_geometry)
287
7
  , fcl(geometry)
288
  , placement(placement)
289
  , meshPath(meshPath)
290
  , meshScale(meshScale)
291
  , overrideMaterial(overrideMaterial)
292
  , meshColor(meshColor)
293
  , meshMaterial(meshMaterial)
294
  , meshTexturePath(meshTexturePath)
295



14
  , disableCollision(false)
296
7
  {}
297
PINOCCHIO_COMPILER_DIAGNOSTIC_POP
298
299
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
300
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
301
5366
  GeometryObject(const GeometryObject & other)
302

5366
  : fcl(geometry)
303
  {
304
5366
    *this = other;
305
306
5366
  }
307
PINOCCHIO_COMPILER_DIAGNOSTIC_POP
308
309
5367
  GeometryObject & operator=(const GeometryObject & other)
310
  {
311
5367
    name                = other.name;
312
5367
    parentFrame         = other.parentFrame;
313
5367
    parentJoint         = other.parentJoint;
314
5367
    geometry            = other.geometry;
315
5367
    placement           = other.placement;
316
5367
    meshPath            = other.meshPath;
317
5367
    meshScale           = other.meshScale;
318
5367
    overrideMaterial    = other.overrideMaterial;
319
5367
    meshColor           = other.meshColor;
320
5367
    meshMaterial        = other.meshMaterial;
321
5367
    meshTexturePath     = other.meshTexturePath;
322
5367
    disableCollision   = other.disableCollision;
323
5367
    return *this;
324
  }
325
326
  friend std::ostream & operator<< (std::ostream & os, const GeometryObject & geomObject);
327
};
328
329
#ifdef PINOCCHIO_WITH_HPP_FCL
330
331
  struct ComputeCollision
332
  : ::hpp::fcl::ComputeCollision
333
  {
334
    typedef ::hpp::fcl::ComputeCollision Base;
335
    typedef shared_ptr<const fcl::CollisionGeometry> ConstCollisionGeometryPtr;
336
337
3170
    ComputeCollision(const GeometryObject & o1, const GeometryObject & o2)
338
3170
    : Base(o1.geometry.get(),o2.geometry.get())
339
3170
    , o1(o1.geometry)
340
6340
    , o2(o2.geometry)
341
3170
    {}
342
343
12738
    virtual ~ComputeCollision() {};
344
345
  protected:
346
    ConstCollisionGeometryPtr o1;
347
    ConstCollisionGeometryPtr o2;
348
349
2131
    virtual std::size_t run(const fcl::Transform3f& tf1, const fcl::Transform3f& tf2,
350
                            const fcl::CollisionRequest& request, fcl::CollisionResult& result) const
351
    {
352
      typedef ::hpp::fcl::CollisionGeometry const * Pointer;
353
2131
      const_cast<Pointer&>(Base::o1) = o1.get();
354
2131
      const_cast<Pointer&>(Base::o2) = o2.get();
355
2131
      return Base::run(tf1, tf2, request, result);
356
    }
357
  };
358
359
  struct ComputeDistance
360
  : ::hpp::fcl::ComputeDistance
361
  {
362
    typedef ::hpp::fcl::ComputeDistance Base;
363
    typedef shared_ptr<fcl::CollisionGeometry> ConstCollisionGeometryPtr;
364
365
3170
    ComputeDistance(const GeometryObject & o1, const GeometryObject & o2)
366
3170
    : Base(o1.geometry.get(),o2.geometry.get())
367
3170
    , o1(o1.geometry)
368
6340
    , o2(o2.geometry)
369
3170
    {}
370
371
12738
    virtual ~ComputeDistance() {};
372
373
  protected:
374
    ConstCollisionGeometryPtr o1;
375
    ConstCollisionGeometryPtr o2;
376
377
141
    virtual hpp::fcl::FCL_REAL run(const fcl::Transform3f& tf1, const fcl::Transform3f& tf2,
378
                                   const fcl::DistanceRequest& request, fcl::DistanceResult& result) const
379
    {
380
      typedef ::hpp::fcl::CollisionGeometry const * Pointer;
381
141
      const_cast<Pointer&>(Base::o1) = o1.get();
382
141
      const_cast<Pointer&>(Base::o2) = o2.get();
383
141
      return Base::run(tf1, tf2, request, result);
384
    }
385
  };
386
387
#endif
388
389
} // namespace pinocchio
390
391
/* --- Details -------------------------------------------------------------- */
392
/* --- Details -------------------------------------------------------------- */
393
/* --- Details -------------------------------------------------------------- */
394
#include "pinocchio/multibody/fcl.hxx"
395
396
#endif // ifndef __pinocchio_multibody_fcl_hpp__