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 
11 
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 
43  #include <hpp/fcl/collision.h>
44  #include <hpp/fcl/distance.h>
45  #include <hpp/fcl/shape/geometric_shapes.h>
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 
66  : public std::pair<GeomIndex, GeomIndex>
67  {
68 
69  typedef std::pair<GeomIndex, GeomIndex> Base;
70 
72  CollisionPair();
73 
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 
95  {
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 
113 
114  }
115 
116 #else
117 
118  namespace fcl = hpp::fcl;
119 
120 #endif // PINOCCHIO_WITH_HPP_FCL
121 
123 {
126 };
127 
130 {
131 };
132 
136 {
137  GeometryPhongMaterial() = default;
138  GeometryPhongMaterial(const Eigen::Vector4d& meshEmissionColor,
139  const Eigen::Vector4d& meshSpecularColor,
140  double meshShininess)
144  {}
145 
147  Eigen::Vector4d meshEmissionColor{Eigen::Vector4d(0., 0., 0., 1.)};
148 
150  Eigen::Vector4d meshSpecularColor{Eigen::Vector4d(0., 0., 0., 1.)};
151 
155  double meshShininess{0.};
156 };
157 
158 typedef boost::variant<GeometryNoMaterial, GeometryPhongMaterial> GeometryMaterial;
159 
161 {
162  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
163 
164  typedef shared_ptr<fcl::CollisionGeometry> CollisionGeometryPtr;
165 
167  std::string name;
168 
175 
178 
180  CollisionGeometryPtr geometry;
181 
184  PINOCCHIO_DEPRECATED CollisionGeometryPtr & fcl;
185 
188 
190  std::string meshPath;
191 
193  Eigen::Vector3d meshScale;
194 
197 
199  Eigen::Vector4d meshColor;
200 
205 
207  std::string meshTexturePath;
208 
211 
229  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 = "",
240  : name(name)
241  , parentFrame(parent_frame)
242  , parentJoint(parent_joint)
243  , geometry(collision_geometry)
244  , fcl(geometry)
246  , meshPath(meshPath)
251  , meshTexturePath(meshTexturePath)
252  , disableCollision(false)
253  {}
255 
273  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 = "",
283  : name(name)
284  , parentFrame(std::numeric_limits<FrameIndex>::max())
285  , parentJoint(parent_joint)
286  , geometry(collision_geometry)
287  , fcl(geometry)
289  , meshPath(meshPath)
294  , meshTexturePath(meshTexturePath)
295  , disableCollision(false)
296  {}
298 
302  : fcl(geometry)
303  {
304  *this = other;
305 
306  }
308 
310  {
311  name = other.name;
312  parentFrame = other.parentFrame;
313  parentJoint = other.parentJoint;
314  geometry = other.geometry;
315  placement = other.placement;
316  meshPath = other.meshPath;
317  meshScale = other.meshScale;
318  overrideMaterial = other.overrideMaterial;
319  meshColor = other.meshColor;
320  meshMaterial = other.meshMaterial;
321  meshTexturePath = other.meshTexturePath;
322  disableCollision = other.disableCollision;
323  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
333  {
334  typedef ::hpp::fcl::ComputeCollision Base;
335  typedef shared_ptr<const fcl::CollisionGeometry> ConstCollisionGeometryPtr;
336 
337  ComputeCollision(const GeometryObject & o1, const GeometryObject & o2)
338  : Base(o1.geometry.get(),o2.geometry.get())
339  , o1(o1.geometry)
340  , o2(o2.geometry)
341  {}
342 
343  virtual ~ComputeCollision() {};
344 
345  protected:
346  ConstCollisionGeometryPtr o1;
347  ConstCollisionGeometryPtr o2;
348 
349  virtual std::size_t run(const fcl::Transform3f& tf1, const fcl::Transform3f& tf2,
350  const fcl::CollisionRequest& request, fcl::CollisionResult& result) const
351  {
353  const_cast<Pointer&>(Base::o1) = o1.get();
354  const_cast<Pointer&>(Base::o2) = o2.get();
355  return Base::run(tf1, tf2, request, result);
356  }
357  };
358 
359  struct ComputeDistance
361  {
362  typedef ::hpp::fcl::ComputeDistance Base;
363  typedef shared_ptr<fcl::CollisionGeometry> ConstCollisionGeometryPtr;
364 
365  ComputeDistance(const GeometryObject & o1, const GeometryObject & o2)
366  : Base(o1.geometry.get(),o2.geometry.get())
367  , o1(o1.geometry)
368  , o2(o2.geometry)
369  {}
370 
371  virtual ~ComputeDistance() {};
372 
373  protected:
374  ConstCollisionGeometryPtr o1;
375  ConstCollisionGeometryPtr o2;
376 
377  virtual hpp::fcl::FCL_REAL run(const fcl::Transform3f& tf1, const fcl::Transform3f& tf2,
378  const fcl::DistanceRequest& request, fcl::DistanceResult& result) const
379  {
381  const_cast<Pointer&>(Base::o1) = o1.get();
382  const_cast<Pointer&>(Base::o2) = o2.get();
383  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__
pinocchio::GeometryObject::GeometryObject
PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS GeometryObject(const GeometryObject &other)
Definition: fcl.hpp:301
display-shapes-meshcat.placement
placement
Definition: display-shapes-meshcat.py:22
hpp::fcl::ComputeCollision
pinocchio::FrameIndex
Index FrameIndex
Definition: multibody/fwd.hpp:30
pinocchio::GeometryObject::overrideMaterial
bool overrideMaterial
Decide whether to override the Material.
Definition: fcl.hpp:196
append-urdf-model-with-another-model.meshColor
meshColor
Definition: append-urdf-model-with-another-model.py:43
pinocchio::GeometryObject::placement
SE3 placement
Position of geometry object in parent joint frame.
Definition: fcl.hpp:187
pinocchio::GeometryObject::meshScale
Eigen::Vector3d meshScale
Scaling vector applied to the GeometryObject::geometry object.
Definition: fcl.hpp:193
meshcat-viewer.meshMaterial
meshMaterial
Definition: meshcat-viewer.py:67
omniidl_be_python_with_docstring.run
def run(tree, args)
Definition: cmake/hpp/idl/omniidl_be_python_with_docstring.py:140
aligned-vector.hpp
pinocchio::GeometryPhongMaterial::GeometryPhongMaterial
GeometryPhongMaterial(const Eigen::Vector4d &meshEmissionColor, const Eigen::Vector4d &meshSpecularColor, double meshShininess)
Definition: fcl.hpp:138
pinocchio::GeometryPhongMaterial::meshSpecularColor
Eigen::Vector4d meshSpecularColor
RGBA specular color value of the GeometryObject::geometry object.
Definition: fcl.hpp:150
pinocchio::SE3Tpl< double, 0 >
pinocchio::name
std::string name(const LieGroupGenericTpl< LieGroupCollection > &lg)
Visit a LieGroupVariant to get the name of it.
pinocchio::GeometryObject::meshColor
Eigen::Vector4d meshColor
RGBA diffuse color value of the GeometryObject::geometry object.
Definition: fcl.hpp:199
Base
BVNodeBase Base
pinocchio::CollisionPair::Base
std::pair< GeomIndex, GeomIndex > Base
Definition: fcl.hpp:69
PINOCCHIO_COMPILER_DIAGNOSTIC_POP
#define PINOCCHIO_COMPILER_DIAGNOSTIC_POP
Definition: include/pinocchio/macros.hpp:95
pinocchio::CollisionPair::operator<<
friend std::ostream & operator<<(std::ostream &os, const CollisionPair &X)
fcl-pinocchio-conversions.hpp
distance.h
pinocchio::GeometryNoMaterial
No material associated to a geometry.
Definition: fcl.hpp:129
pinocchio::VISUAL
@ VISUAL
Definition: fcl.hpp:124
pinocchio::GeometryPhongMaterial::meshShininess
double meshShininess
Shininess associated to the specular lighting model.
Definition: fcl.hpp:155
args
args
pinocchio::fcl::FakeCollisionGeometry::operator==
bool operator==(const FakeCollisionGeometry &) const
Definition: fcl.hpp:98
res
res
hpp::fcl::FCL_REAL
double FCL_REAL
pinocchio::CollisionPair
Definition: fcl.hpp:65
pinocchio::GeometryObject::meshMaterial
GeometryMaterial meshMaterial
Material associated to the mesh. This material should be used only if overrideMaterial is set to true...
Definition: fcl.hpp:204
meshcat-viewer-dae.meshScale
meshScale
Definition: meshcat-viewer-dae.py:28
collision-with-point-clouds.geometry
geometry
Definition: collision-with-point-clouds.py:71
collision-with-point-clouds.X
X
Definition: collision-with-point-clouds.py:30
pinocchio::fcl::FakeCollisionGeometry
Definition: fcl.hpp:94
se3.hpp
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
#define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
Definition: include/pinocchio/macros.hpp:96
pinocchio::GeometryObject::meshPath
std::string meshPath
Absolute path to the mesh file (if the geometry pointee is also a Mesh)
Definition: fcl.hpp:190
pinocchio::GeometryMaterial
boost::variant< GeometryNoMaterial, GeometryPhongMaterial > GeometryMaterial
Definition: fcl.hpp:158
pinocchio::GeometryPhongMaterial::GeometryPhongMaterial
GeometryPhongMaterial()=default
pinocchio::GeometryObject::meshTexturePath
std::string meshTexturePath
Absolute path to the mesh texture file.
Definition: fcl.hpp:207
pinocchio::GeometryObject::geometry
CollisionGeometryPtr geometry
The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
Definition: fcl.hpp:180
pinocchio::CollisionPair::CollisionPair
CollisionPair()
&#160;
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
#define PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
macros for pragma push/pop/ignore deprecated warnings
Definition: include/pinocchio/macros.hpp:94
pinocchio::CollisionPair::operator==
bool operator==(const CollisionPair &rhs) const
pinocchio::fcl::CollisionGeometry
FakeCollisionGeometry CollisionGeometry
Definition: fcl.hpp:112
pinocchio::operator<<
std::ostream & operator<<(std::ostream &os, const FrameTpl< Scalar, Options > &f)
Definition: multibody/frame.hpp:151
hpp::fcl
pinocchio::GeometryObject::GeometryObject
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="", const GeometryMaterial &meshMaterial=GeometryNoMaterial())
Reduced constructor.
Definition: fcl.hpp:273
pinocchio.deprecated.GeometryObject
Definition: deprecated.py:89
pinocchio::fcl::AABB::max_
int max_
Definition: fcl.hpp:109
pinocchio::GeometryPhongMaterial
Definition: fcl.hpp:135
pinocchio::CollisionPair::disp
void disp(std::ostream &os) const
pinocchio::GeometryObject::disableCollision
bool disableCollision
If true, no collision or distance check will be done between the Geometry and any other geometry.
Definition: fcl.hpp:210
pinocchio::GeometryObject::parentFrame
FrameIndex parentFrame
Index of the parent frame.
Definition: fcl.hpp:174
pinocchio::fcl::AABB::min_
int min_
Definition: fcl.hpp:106
hpp::fcl::ComputeDistance
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:28
pinocchio::fcl::FakeCollisionGeometry::FakeCollisionGeometry
FakeCollisionGeometry()
Definition: fcl.hpp:96
pinocchio::GeometryType
GeometryType
Definition: fcl.hpp:122
pinocchio::fcl::AABB
Definition: fcl.hpp:104
pinocchio::GeometryObject::name
std::string name
Name of the geometry object.
Definition: fcl.hpp:167
pinocchio::fcl::AABB::AABB
AABB()
Definition: fcl.hpp:106
pinocchio::COLLISION
@ COLLISION
Definition: fcl.hpp:125
pinocchio::GeometryObject::fcl
PINOCCHIO_DEPRECATED CollisionGeometryPtr & fcl
The former pointer to the FCL CollisionGeometry.
Definition: fcl.hpp:184
Base
collision.h
pinocchio.deprecated.GeometryObject.fcl
def fcl(self)
Definition: deprecated.py:92
collision_object.h
CppAD::max
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
Definition: autodiff/cppad.hpp:159
meshcat-viewer.overrideMaterial
overrideMaterial
Definition: meshcat-viewer.py:66
pinocchio::GeomIndex
Index GeomIndex
Definition: multibody/fwd.hpp:29
fwd.hpp
pinocchio::GeometryObject::operator=
PINOCCHIO_COMPILER_DIAGNOSTIC_POP GeometryObject & operator=(const GeometryObject &other)
Definition: fcl.hpp:309
pinocchio::GeometryObject::CollisionGeometryPtr
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef shared_ptr< fcl::CollisionGeometry > CollisionGeometryPtr
Definition: fcl.hpp:164
pinocchio::GeometryObject::parentJoint
JointIndex parentJoint
Index of the parent joint.
Definition: fcl.hpp:177
pinocchio::CollisionPair::operator!=
bool operator!=(const CollisionPair &rhs) const
pinocchio::GeometryPhongMaterial::meshEmissionColor
Eigen::Vector4d meshEmissionColor
RGBA emission (ambient) color value of the GeometryObject::geometry object.
Definition: fcl.hpp:147
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:28
pinocchio::GeometryObject::GeometryObject
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="", const GeometryMaterial &meshMaterial=GeometryNoMaterial())
Full constructor.
Definition: fcl.hpp:229


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:43:58