pinocchio  2.4.4
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
fcl.hpp
1 //
2 // Copyright (c) 2015-2019 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  #include <hpp/fcl/collision_object.h>
14  #include <hpp/fcl/collision.h>
15  #include <hpp/fcl/distance.h>
16  #include <hpp/fcl/shape/geometric_shapes.h>
17  #include "pinocchio/spatial/fcl-pinocchio-conversions.hpp"
18 #endif
19 
20 #include <iostream>
21 #include <map>
22 #include <vector>
23 #include <utility>
24 #include <limits>
25 #include <assert.h>
26 
27 #include <boost/foreach.hpp>
28 #include <boost/shared_ptr.hpp>
29 
30 namespace pinocchio
31 {
32  struct CollisionPair: public std::pair<GeomIndex, GeomIndex>
33  {
34 
35  typedef std::pair<GeomIndex, GeomIndex> Base;
36 
37  CollisionPair(const GeomIndex co1, const GeomIndex co2);
38  bool operator == (const CollisionPair& rhs) const;
39  void disp (std::ostream & os) const;
40  friend std::ostream & operator << (std::ostream & os,const CollisionPair & X);
41 
42  }; // struct CollisionPair
43 
44 #ifndef PINOCCHIO_WITH_HPP_FCL
45 
46  namespace fcl
47  {
48 
49  struct FakeCollisionGeometry
50  {
51  FakeCollisionGeometry(){};
52 
53  bool operator==(const FakeCollisionGeometry &) const
54  {
55  return true;
56  }
57  };
58 
59  struct AABB
60  {
61  AABB(): min_(0), max_(1){};
62 
63  int min_;
64  int max_;
65  };
66 
67  typedef FakeCollisionGeometry CollisionGeometry;
68 
69  }
70 
71 #else
72 
73  namespace fcl = hpp::fcl;
74 
75 #endif // PINOCCHIO_WITH_HPP_FCL
76 
77 enum GeometryType
78 {
79  VISUAL,
80  COLLISION
81 };
82 
84 {
85  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
86 
87  typedef boost::shared_ptr<fcl::CollisionGeometry> CollisionGeometryPtr;
88 
90  std::string name;
91 
97  FrameIndex parentFrame;
98 
100  JointIndex parentJoint;
101 
103  CollisionGeometryPtr geometry;
104 
107  PINOCCHIO_DEPRECATED CollisionGeometryPtr & fcl;
108 
111 
113  std::string meshPath;
114 
116  Eigen::Vector3d meshScale;
117 
120 
122  Eigen::Vector4d meshColor;
123 
125  std::string meshTexturePath;
126 
127 #pragma GCC diagnostic push
128 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
129  GeometryObject(const std::string & name,
144  const FrameIndex parent_frame,
145  const JointIndex parent_joint,
146  const CollisionGeometryPtr & collision_geometry,
147  const SE3 & placement,
148  const std::string & meshPath = "",
149  const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
150  const bool overrideMaterial = false,
151  const Eigen::Vector4d & meshColor = Eigen::Vector4d::Zero(),
152  const std::string & meshTexturePath = "")
153  : name(name)
154  , parentFrame(parent_frame)
155  , parentJoint(parent_joint)
156  , geometry(collision_geometry)
157  , fcl(geometry)
158  , placement(placement)
159  , meshPath(meshPath)
160  , meshScale(meshScale)
161  , overrideMaterial(overrideMaterial)
162  , meshColor(meshColor)
163  , meshTexturePath(meshTexturePath)
164  {}
165 #pragma GCC diagnostic pop
166 
167 #pragma GCC diagnostic push
168 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
169  GeometryObject(const std::string & name,
184  const JointIndex parent_joint,
185  const CollisionGeometryPtr & collision_geometry,
186  const SE3 & placement,
187  const std::string & meshPath = "",
188  const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
189  const bool overrideMaterial = false,
190  const Eigen::Vector4d & meshColor = Eigen::Vector4d::Zero(),
191  const std::string & meshTexturePath = "")
192  : name(name)
193  , parentFrame(std::numeric_limits<FrameIndex>::max())
194  , parentJoint(parent_joint)
195  , geometry(collision_geometry)
196  , fcl(geometry)
197  , placement(placement)
198  , meshPath(meshPath)
199  , meshScale(meshScale)
200  , overrideMaterial(overrideMaterial)
201  , meshColor(meshColor)
202  , meshTexturePath(meshTexturePath)
203  {}
204 #pragma GCC diagnostic pop
205 
206 #pragma GCC diagnostic push
207 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
208  GeometryObject(const GeometryObject & other)
209  : fcl(geometry)
210  {
211  *this = other;
212  }
213 #pragma GCC diagnostic pop
214 
215  GeometryObject & operator=(const GeometryObject & other)
216  {
217  name = other.name;
218  parentFrame = other.parentFrame;
219  parentJoint = other.parentJoint;
220  geometry = other.geometry;
221  placement = other.placement;
222  meshPath = other.meshPath;
223  meshScale = other.meshScale;
224  overrideMaterial = other.overrideMaterial;
225  meshColor = other.meshColor;
226  meshTexturePath = other.meshTexturePath;
227  return *this;
228  }
229 
230  friend std::ostream & operator<< (std::ostream & os, const GeometryObject & geomObject);
231 };
232 
233 
234 } // namespace pinocchio
235 
236 /* --- Details -------------------------------------------------------------- */
237 /* --- Details -------------------------------------------------------------- */
238 /* --- Details -------------------------------------------------------------- */
239 #include "pinocchio/multibody/fcl.hxx"
240 
241 #endif // ifndef __pinocchio_multibody_fcl_hpp__
CollisionGeometryPtr geometry
The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
Definition: fcl.hpp:103
std::string name(const LieGroupGenericTpl< LieGroupCollection > &lg)
Visit a LieGroupVariant to get the name of it.
bool overrideMaterial
Decide whether to override the Material.
Definition: fcl.hpp:119
Eigen::Vector3d meshScale
Scaling vector applied to the GeometryObject::fcl object.
Definition: fcl.hpp:116
std::string meshTexturePath
Absolute path to the mesh texture file.
Definition: fcl.hpp:125
JointIndex parentJoint
Index of the parent joint.
Definition: fcl.hpp:100
std::string name
Name of the geometry object.
Definition: fcl.hpp:90
std::string meshPath
Absolute path to the mesh file (if the fcl pointee is also a Mesh)
Definition: fcl.hpp:113
Main pinocchio namespace.
Definition: treeview.dox:24
SE3 placement
Position of geometry object in parent joint frame.
Definition: fcl.hpp:110
Eigen::Vector4d meshColor
RGBA color value of the GeometryObject::fcl object.
Definition: fcl.hpp:122
FrameIndex parentFrame
Index of the parent frame.
Definition: fcl.hpp:97
PINOCCHIO_DEPRECATED CollisionGeometryPtr & fcl
The former pointer to the FCL CollisionGeometry.
Definition: fcl.hpp:107