fcl.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2021 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 
36  #include <hpp/fcl/collision_object.h>
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 #include <boost/foreach.hpp>
51 #include <boost/shared_ptr.hpp>
52 
53 namespace pinocchio
54 {
56  : public std::pair<GeomIndex, GeomIndex>
57  {
58 
59  typedef std::pair<GeomIndex, GeomIndex> Base;
60 
62  CollisionPair();
63 
71  CollisionPair(const GeomIndex co1, const GeomIndex co2);
72  bool operator == (const CollisionPair& rhs) const;
73  bool operator != (const CollisionPair& rhs) const;
74  void disp (std::ostream & os) const;
75  friend std::ostream & operator << (std::ostream & os,const CollisionPair & X);
76 
77  }; // struct CollisionPair
78 
79 #ifndef PINOCCHIO_WITH_HPP_FCL
80 
81  namespace fcl
82  {
83 
85  {
87 
88  bool operator==(const FakeCollisionGeometry &) const
89  {
90  return true;
91  }
92  };
93 
94  struct AABB
95  {
96  AABB(): min_(0), max_(1){};
97 
98  int min_;
99  int max_;
100  };
101 
103 
104  }
105 
106 #else
107 
108  namespace fcl = hpp::fcl;
109 
110 #endif // PINOCCHIO_WITH_HPP_FCL
111 
113 {
116 };
117 
119 {
120  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
121 
122  typedef boost::shared_ptr<fcl::CollisionGeometry> CollisionGeometryPtr;
123 
125  std::string name;
126 
133 
136 
138  CollisionGeometryPtr geometry;
139 
142  PINOCCHIO_DEPRECATED CollisionGeometryPtr & fcl;
143 
146 
148  std::string meshPath;
149 
151  Eigen::Vector3d meshScale;
152 
155 
157  Eigen::Vector4d meshColor;
158 
160  std::string meshTexturePath;
161 
164 
181  GeometryObject(const std::string & name,
182  const FrameIndex parent_frame,
183  const JointIndex parent_joint,
184  const CollisionGeometryPtr & collision_geometry,
185  const SE3 & placement,
186  const std::string & meshPath = "",
187  const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
188  const bool overrideMaterial = false,
189  const Eigen::Vector4d & meshColor = Eigen::Vector4d::Zero(),
190  const std::string & meshTexturePath = "")
191  : name(name)
192  , parentFrame(parent_frame)
193  , parentJoint(parent_joint)
194  , geometry(collision_geometry)
195  , fcl(geometry)
196  , placement(placement)
197  , meshPath(meshPath)
198  , meshScale(meshScale)
199  , overrideMaterial(overrideMaterial)
200  , meshColor(meshColor)
201  , meshTexturePath(meshTexturePath)
202  , disableCollision(false)
203  {}
205 
222  GeometryObject(const std::string & name,
223  const JointIndex parent_joint,
224  const CollisionGeometryPtr & collision_geometry,
225  const SE3 & placement,
226  const std::string & meshPath = "",
227  const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
228  const bool overrideMaterial = false,
229  const Eigen::Vector4d & meshColor = Eigen::Vector4d::Zero(),
230  const std::string & meshTexturePath = "")
231  : name(name)
232  , parentFrame(std::numeric_limits<FrameIndex>::max())
233  , parentJoint(parent_joint)
234  , geometry(collision_geometry)
235  , fcl(geometry)
236  , placement(placement)
237  , meshPath(meshPath)
238  , meshScale(meshScale)
239  , overrideMaterial(overrideMaterial)
240  , meshColor(meshColor)
241  , meshTexturePath(meshTexturePath)
242  , disableCollision(false)
243  {}
245 
249  : fcl(geometry)
250  {
251  *this = other;
252 
253  }
255 
257  {
258  name = other.name;
259  parentFrame = other.parentFrame;
260  parentJoint = other.parentJoint;
261  geometry = other.geometry;
262  placement = other.placement;
263  meshPath = other.meshPath;
264  meshScale = other.meshScale;
265  overrideMaterial = other.overrideMaterial;
266  meshColor = other.meshColor;
267  meshTexturePath = other.meshTexturePath;
268  disableCollision = other.disableCollision;
269  return *this;
270  }
271 
272  friend std::ostream & operator<< (std::ostream & os, const GeometryObject & geomObject);
273 };
274 
275 #ifdef PINOCCHIO_WITH_HPP_FCL
276 
277  struct ComputeCollision
278  : ::hpp::fcl::ComputeCollision
279  {
280  typedef ::hpp::fcl::ComputeCollision Base;
281  typedef boost::shared_ptr<const fcl::CollisionGeometry> ConstCollisionGeometryPtr;
282 
283  ComputeCollision(const GeometryObject & o1, const GeometryObject & o2)
284  : Base(o1.geometry.get(),o2.geometry.get())
285  , o1(o1.geometry)
286  , o2(o2.geometry)
287  {}
288 
289  virtual ~ComputeCollision() {};
290 
291  protected:
292  ConstCollisionGeometryPtr o1;
293  ConstCollisionGeometryPtr o2;
294 
295  virtual std::size_t run(const fcl::Transform3f& tf1, const fcl::Transform3f& tf2,
296  const fcl::CollisionRequest& request, fcl::CollisionResult& result) const
297  {
299  const_cast<Pointer&>(Base::o1) = o1.get();
300  const_cast<Pointer&>(Base::o2) = o2.get();
301  return Base::run(tf1, tf2, request, result);
302  }
303  };
304 
305  struct ComputeDistance
306  : ::hpp::fcl::ComputeDistance
307  {
308  typedef ::hpp::fcl::ComputeDistance Base;
309  typedef boost::shared_ptr<fcl::CollisionGeometry> ConstCollisionGeometryPtr;
310 
311  ComputeDistance(const GeometryObject & o1, const GeometryObject & o2)
312  : Base(o1.geometry.get(),o2.geometry.get())
313  , o1(o1.geometry)
314  , o2(o2.geometry)
315  {}
316 
317  virtual ~ComputeDistance() {};
318 
319  protected:
320  ConstCollisionGeometryPtr o1;
321  ConstCollisionGeometryPtr o2;
322 
323  virtual hpp::fcl::FCL_REAL run(const fcl::Transform3f& tf1, const fcl::Transform3f& tf2,
324  const fcl::DistanceRequest& request, fcl::DistanceResult& result) const
325  {
327  const_cast<Pointer&>(Base::o1) = o1.get();
328  const_cast<Pointer&>(Base::o2) = o2.get();
329  return Base::run(tf1, tf2, request, result);
330  }
331  };
332 
333 #endif
334 
335 } // namespace pinocchio
336 
337 /* --- Details -------------------------------------------------------------- */
338 /* --- Details -------------------------------------------------------------- */
339 /* --- Details -------------------------------------------------------------- */
340 #include "pinocchio/multibody/fcl.hxx"
341 
342 #endif // ifndef __pinocchio_multibody_fcl_hpp__
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::Zero(), const std::string &meshTexturePath="")
Full constructor.
Definition: fcl.hpp:181
GeometryType
Definition: fcl.hpp:112
bool operator==(const FakeCollisionGeometry &) const
Definition: fcl.hpp:88
JointIndex parentJoint
Index of the parent joint.
Definition: fcl.hpp:135
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr< fcl::CollisionGeometry > CollisionGeometryPtr
Definition: fcl.hpp:122
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:248
#define PINOCCHIO_COMPILER_DIAGNOSTIC_POP
Definition: src/macros.hpp:89
FrameIndex parentFrame
Index of the parent frame.
Definition: fcl.hpp:132
CollisionGeometryPtr geometry
The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
Definition: fcl.hpp:138
std::pair< GeomIndex, GeomIndex > Base
Definition: fcl.hpp:59
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:157
bool overrideMaterial
Decide whether to override the Material.
Definition: fcl.hpp:154
def run(tree, args)
FakeCollisionGeometry CollisionGeometry
Definition: fcl.hpp:102
bool operator==(const aligned_vector< T > &lhs, const aligned_vector< T > &rhs)
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::Zero(), const std::string &meshTexturePath="")
Reduced constructor.
Definition: fcl.hpp:222
Main pinocchio namespace.
Definition: timings.cpp:30
std::string name
Name of the geometry object.
Definition: fcl.hpp:125
std::string meshPath
Absolute path to the mesh file (if the fcl pointee is also a Mesh)
Definition: fcl.hpp:148
res
EIGEN_DEVICE_FUNC bool operator!=(const array< T, n > &lhs, const array< T, n > &rhs)
Definition: tensor.hpp:55
#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
std::string meshTexturePath
Absolute path to the mesh texture file.
Definition: fcl.hpp:160
PINOCCHIO_COMPILER_DIAGNOSTIC_POP GeometryObject & operator=(const GeometryObject &other)
Definition: fcl.hpp:256
SE3 placement
Position of geometry object in parent joint frame.
Definition: fcl.hpp:145
Eigen::Vector3d meshScale
Scaling vector applied to the GeometryObject::fcl object.
Definition: fcl.hpp:151
PINOCCHIO_DEPRECATED CollisionGeometryPtr & fcl
The former pointer to the FCL CollisionGeometry.
Definition: fcl.hpp:142
bool disableCollision
If true, no collision or distance check will be done between the Geometry and any other geometry...
Definition: fcl.hpp:163


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:02