fcl.hpp
Go to the documentation of this file.
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 #ifdef PINOCCHIO_WITH_HPP_FCL
13 
14  #if(WIN32)
15  // It appears that std::snprintf is missing for Windows.
16  #if !(( defined(_MSC_VER) && _MSC_VER < 1900 ) || ( defined(__MINGW32__) && !defined(__MINGW64_VERSION_MAJOR) ))
17  #include <cstdio>
18  #include <stdarg.h>
19  namespace std
20  {
21  inline int _snprintf(char* buffer, std::size_t buf_size, const char* format, ...)
22  {
23  int res;
24 
25  va_list args;
26  va_start(args, format);
27  res = vsnprintf(buffer, buf_size, format, args);
28  va_end(args);
29 
30  return res;
31  }
32  }
33  #endif
34  #endif
35 
37  #include <hpp/fcl/collision.h>
38  #include <hpp/fcl/distance.h>
39  #include <hpp/fcl/shape/geometric_shapes.h>
40  #include "pinocchio/spatial/fcl-pinocchio-conversions.hpp"
41 #endif
42 
43 #include <iostream>
44 #include <map>
45 #include <vector>
46 #include <utility>
47 #include <limits>
48 #include <assert.h>
49 
50 #ifdef PINOCCHIO_WITH_HPP_FCL
51 #if HPP_FCL_VERSION_AT_LEAST(2,0,0)
52 #define PINOCCHIO_HPPFCL_USE_STD_SHARED_PTR
53 #endif
54 #endif
55 
56 #ifdef PINOCCHIO_HPPFCL_USE_STD_SHARED_PTR
57 #include <memory>
58 #else
59 #include <boost/shared_ptr.hpp>
60 #include <boost/make_shared.hpp>
61 #endif
62 
63 #include <boost/foreach.hpp>
64 
65 namespace pinocchio
66 {
67 #ifdef PINOCCHIO_HPPFCL_USE_STD_SHARED_PTR
68  using std::shared_ptr;
69  using std::make_shared;
70 #else
71  using boost::shared_ptr;
72  using boost::make_shared;
73 #endif
75  : public std::pair<GeomIndex, GeomIndex>
76  {
77 
78  typedef std::pair<GeomIndex, GeomIndex> Base;
79 
81  CollisionPair();
82 
90  CollisionPair(const GeomIndex co1, const GeomIndex co2);
91  bool operator == (const CollisionPair& rhs) const;
92  bool operator != (const CollisionPair& rhs) const;
93  void disp (std::ostream & os) const;
94  friend std::ostream & operator << (std::ostream & os,const CollisionPair & X);
95 
96  }; // struct CollisionPair
97 
98 #ifndef PINOCCHIO_WITH_HPP_FCL
99 
100  namespace fcl
101  {
102 
104  {
106 
107  bool operator==(const FakeCollisionGeometry &) const
108  {
109  return true;
110  }
111  };
112 
113  struct AABB
114  {
115  AABB(): min_(0), max_(1){};
116 
117  int min_;
118  int max_;
119  };
120 
122 
123  }
124 
125 #else
126 
127  namespace fcl = hpp::fcl;
128 
129 #endif // PINOCCHIO_WITH_HPP_FCL
130 
132 {
135 };
136 
138 {
139  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
140 
141  typedef shared_ptr<fcl::CollisionGeometry> CollisionGeometryPtr;
142 
144  std::string name;
145 
152 
155 
157  CollisionGeometryPtr geometry;
158 
161  PINOCCHIO_DEPRECATED CollisionGeometryPtr & fcl;
162 
165 
167  std::string meshPath;
168 
170  Eigen::Vector3d meshScale;
171 
174 
176  Eigen::Vector4d meshColor;
177 
179  std::string meshTexturePath;
180 
183 
200  GeometryObject(const std::string & name,
201  const FrameIndex parent_frame,
202  const JointIndex parent_joint,
203  const CollisionGeometryPtr & collision_geometry,
204  const SE3 & placement,
205  const std::string & meshPath = "",
206  const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
207  const bool overrideMaterial = false,
208  const Eigen::Vector4d & meshColor = Eigen::Vector4d(0,0,0,1),
209  const std::string & meshTexturePath = "")
210  : name(name)
211  , parentFrame(parent_frame)
212  , parentJoint(parent_joint)
213  , geometry(collision_geometry)
214  , fcl(geometry)
215  , placement(placement)
216  , meshPath(meshPath)
217  , meshScale(meshScale)
218  , overrideMaterial(overrideMaterial)
219  , meshColor(meshColor)
220  , meshTexturePath(meshTexturePath)
221  , disableCollision(false)
222  {}
224 
241  GeometryObject(const std::string & name,
242  const JointIndex parent_joint,
243  const CollisionGeometryPtr & collision_geometry,
244  const SE3 & placement,
245  const std::string & meshPath = "",
246  const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
247  const bool overrideMaterial = false,
248  const Eigen::Vector4d & meshColor = Eigen::Vector4d::Ones(),
249  const std::string & meshTexturePath = "")
250  : name(name)
251  , parentFrame(std::numeric_limits<FrameIndex>::max())
252  , parentJoint(parent_joint)
253  , geometry(collision_geometry)
254  , fcl(geometry)
255  , placement(placement)
256  , meshPath(meshPath)
257  , meshScale(meshScale)
258  , overrideMaterial(overrideMaterial)
259  , meshColor(meshColor)
260  , meshTexturePath(meshTexturePath)
261  , disableCollision(false)
262  {}
264 
268  : fcl(geometry)
269  {
270  *this = other;
271 
272  }
274 
276  {
277  name = other.name;
278  parentFrame = other.parentFrame;
279  parentJoint = other.parentJoint;
280  geometry = other.geometry;
281  placement = other.placement;
282  meshPath = other.meshPath;
283  meshScale = other.meshScale;
284  overrideMaterial = other.overrideMaterial;
285  meshColor = other.meshColor;
286  meshTexturePath = other.meshTexturePath;
287  disableCollision = other.disableCollision;
288  return *this;
289  }
290 
291  friend std::ostream & operator<< (std::ostream & os, const GeometryObject & geomObject);
292 };
293 
294 #ifdef PINOCCHIO_WITH_HPP_FCL
295 
296  struct ComputeCollision
298  {
299  typedef ::hpp::fcl::ComputeCollision Base;
300  typedef shared_ptr<const fcl::CollisionGeometry> ConstCollisionGeometryPtr;
301 
302  ComputeCollision(const GeometryObject & o1, const GeometryObject & o2)
303  : Base(o1.geometry.get(),o2.geometry.get())
304  , o1(o1.geometry)
305  , o2(o2.geometry)
306  {}
307 
308  virtual ~ComputeCollision() {};
309 
310  protected:
311  ConstCollisionGeometryPtr o1;
312  ConstCollisionGeometryPtr o2;
313 
314  virtual std::size_t run(const fcl::Transform3f& tf1, const fcl::Transform3f& tf2,
315  const fcl::CollisionRequest& request, fcl::CollisionResult& result) const
316  {
318  const_cast<Pointer&>(Base::o1) = o1.get();
319  const_cast<Pointer&>(Base::o2) = o2.get();
320  return Base::run(tf1, tf2, request, result);
321  }
322  };
323 
324  struct ComputeDistance
326  {
327  typedef ::hpp::fcl::ComputeDistance Base;
328  typedef shared_ptr<fcl::CollisionGeometry> ConstCollisionGeometryPtr;
329 
330  ComputeDistance(const GeometryObject & o1, const GeometryObject & o2)
331  : Base(o1.geometry.get(),o2.geometry.get())
332  , o1(o1.geometry)
333  , o2(o2.geometry)
334  {}
335 
336  virtual ~ComputeDistance() {};
337 
338  protected:
339  ConstCollisionGeometryPtr o1;
340  ConstCollisionGeometryPtr o2;
341 
342  virtual hpp::fcl::FCL_REAL run(const fcl::Transform3f& tf1, const fcl::Transform3f& tf2,
343  const fcl::DistanceRequest& request, fcl::DistanceResult& result) const
344  {
346  const_cast<Pointer&>(Base::o1) = o1.get();
347  const_cast<Pointer&>(Base::o2) = o2.get();
348  return Base::run(tf1, tf2, request, result);
349  }
350  };
351 
352 #endif
353 
354 } // namespace pinocchio
355 
356 /* --- Details -------------------------------------------------------------- */
357 /* --- Details -------------------------------------------------------------- */
358 /* --- Details -------------------------------------------------------------- */
359 #include "pinocchio/multibody/fcl.hxx"
360 
361 #endif // ifndef __pinocchio_multibody_fcl_hpp__
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef shared_ptr< fcl::CollisionGeometry > CollisionGeometryPtr
Definition: fcl.hpp:141
GeometryType
Definition: fcl.hpp:131
Vec3f min_
JointIndex parentJoint
Index of the parent joint.
Definition: fcl.hpp:154
bool operator==(const FakeCollisionGeometry &) const
Definition: fcl.hpp:107
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS GeometryObject(const std::string &name, const FrameIndex parent_frame, const JointIndex parent_joint, const CollisionGeometryPtr &collision_geometry, const SE3 &placement, const std::string &meshPath="", const Eigen::Vector3d &meshScale=Eigen::Vector3d::Ones(), const bool overrideMaterial=false, const Eigen::Vector4d &meshColor=Eigen::Vector4d(0, 0, 0, 1), const std::string &meshTexturePath="")
Full constructor.
Definition: fcl.hpp:200
bool operator!=(const kIOS_Sphere &other) const
tuple tf2
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS GeometryObject(const GeometryObject &other)
Definition: fcl.hpp:267
BVNodeBase Base
#define PINOCCHIO_COMPILER_DIAGNOSTIC_POP
Definition: src/macros.hpp:89
FrameIndex parentFrame
Index of the parent frame.
Definition: fcl.hpp:151
CollisionGeometryPtr geometry
The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
Definition: fcl.hpp:157
std::pair< GeomIndex, GeomIndex > Base
Definition: fcl.hpp:78
AABB()
double FCL_REAL
std::ostream & operator<<(std::ostream &os, const FrameTpl< Scalar, Options > &f)
Eigen::Vector4d meshColor
RGBA color value of the GeometryObject::fcl object.
Definition: fcl.hpp:176
bool overrideMaterial
Decide whether to override the Material.
Definition: fcl.hpp:173
Vec3f max_
FakeCollisionGeometry CollisionGeometry
Definition: fcl.hpp:121
args
Main pinocchio namespace.
Definition: timings.cpp:28
std::string name
Name of the geometry object.
Definition: fcl.hpp:144
std::string meshPath
Absolute path to the mesh file (if the fcl pointee is also a Mesh)
Definition: fcl.hpp:167
res
#define PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
macros for pragma push/pop/ignore deprecated warnings
Definition: src/macros.hpp:88
#define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
Definition: src/macros.hpp:90
PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS GeometryObject(const std::string &name, const JointIndex parent_joint, const CollisionGeometryPtr &collision_geometry, const SE3 &placement, const std::string &meshPath="", const Eigen::Vector3d &meshScale=Eigen::Vector3d::Ones(), const bool overrideMaterial=false, const Eigen::Vector4d &meshColor=Eigen::Vector4d::Ones(), const std::string &meshTexturePath="")
Reduced constructor.
Definition: fcl.hpp:241
std::string meshTexturePath
Absolute path to the mesh texture file.
Definition: fcl.hpp:179
bool operator==(const kIOS_Sphere &other) const
PINOCCHIO_COMPILER_DIAGNOSTIC_POP GeometryObject & operator=(const GeometryObject &other)
Definition: fcl.hpp:275
SE3 placement
Position of geometry object in parent joint frame.
Definition: fcl.hpp:164
tuple tf1
Eigen::Vector3d meshScale
Scaling vector applied to the GeometryObject::fcl object.
Definition: fcl.hpp:170
PINOCCHIO_DEPRECATED CollisionGeometryPtr & fcl
The former pointer to the FCL CollisionGeometry.
Definition: fcl.hpp:161
bool disableCollision
If true, no collision or distance check will be done between the Geometry and any other geometry...
Definition: fcl.hpp:182


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:30