multibody/geometry-object.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2023 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_multibody_geometry_object_hpp__
6 #define __pinocchio_multibody_geometry_object_hpp__
7 
14 
19 #include <boost/variant.hpp>
20 
21 namespace pinocchio
22 {
23 
25  {
28  };
29 
32  {
33  bool operator==(const GeometryNoMaterial &) const
34  {
35  return true;
36  }
37  };
38 
42  {
43  GeometryPhongMaterial() = default;
45  const Eigen::Vector4d & meshEmissionColor,
46  const Eigen::Vector4d & meshSpecularColor,
47  double meshShininess)
51  {
52  }
53 
54  bool operator==(const GeometryPhongMaterial & other) const
55  {
56  return meshEmissionColor == other.meshEmissionColor
58  && meshShininess == other.meshShininess;
59  }
60 
62  Eigen::Vector4d meshEmissionColor{Eigen::Vector4d(0., 0., 0., 1.)};
63 
65  Eigen::Vector4d meshSpecularColor{Eigen::Vector4d(0., 0., 0., 1.)};
66 
70  double meshShininess{0.};
71  };
72 
73  typedef boost::variant<GeometryNoMaterial, GeometryPhongMaterial> GeometryMaterial;
74 
75  struct GeometryObject; // fwd
76 
77  template<>
79  {
81  enum
82  {
84  };
85  };
86 
88  : public ModelItem<GeometryObject>
89  , serialization::Serializable<GeometryObject>
90  {
91  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
92 
95  enum
96  {
98  };
99 
101 
102  typedef std::shared_ptr<fcl::CollisionGeometry> CollisionGeometryPtr;
103 
104  using Base::name;
105  using Base::parentFrame;
106  using Base::parentJoint;
107  using Base::placement;
108 
111 
113  std::string meshPath;
114 
116  Eigen::Vector3d meshScale;
117 
120 
122  Eigen::Vector4d meshColor;
123 
128 
130  std::string meshTexturePath;
131 
135 
152  const std::string & name,
153  const JointIndex parent_joint,
154  const FrameIndex parent_frame,
155  const SE3 & placement,
156  const CollisionGeometryPtr & collision_geometry,
157  const std::string & meshPath = "",
158  const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
159  const bool overrideMaterial = false,
160  const Eigen::Vector4d & meshColor = Eigen::Vector4d(0, 0, 0, 1),
161  const std::string & meshTexturePath = "",
163  : Base(name, parent_joint, parent_frame, placement)
164  , geometry(collision_geometry)
165  , meshPath(meshPath)
171  , disableCollision(false)
172  {
173  }
174 
192  const std::string & name,
193  const JointIndex parent_joint,
194  const SE3 & placement,
195  const CollisionGeometryPtr & collision_geometry,
196  const std::string & meshPath = "",
197  const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
198  const bool overrideMaterial = false,
199  const Eigen::Vector4d & meshColor = Eigen::Vector4d(0, 0, 0, 1),
200  const std::string & meshTexturePath = "",
202  : Base(name, parent_joint, std::numeric_limits<FrameIndex>::max(), placement)
203  , geometry(collision_geometry)
204  , meshPath(meshPath)
210  , disableCollision(false)
211  {
212  }
213 
231  PINOCCHIO_DEPRECATED GeometryObject(
232  const std::string & name,
233  const FrameIndex parent_frame,
234  const JointIndex parent_joint,
235  const CollisionGeometryPtr & collision_geometry,
236  const SE3 & placement,
237  const std::string & meshPath = "",
238  const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
239  const bool overrideMaterial = false,
240  const Eigen::Vector4d & meshColor = Eigen::Vector4d(0, 0, 0, 1),
241  const std::string & meshTexturePath = "",
243  : Base(name, parent_joint, parent_frame, placement)
244  , geometry(collision_geometry)
245  , meshPath(meshPath)
251  , disableCollision(false)
252  {
253  }
254 
273  PINOCCHIO_DEPRECATED GeometryObject(
274  const std::string & name,
275  const JointIndex parent_joint,
276  const CollisionGeometryPtr & collision_geometry,
277  const SE3 & placement,
278  const std::string & meshPath = "",
279  const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
280  const bool overrideMaterial = false,
281  const Eigen::Vector4d & meshColor = Eigen::Vector4d(0, 0, 0, 1),
282  const std::string & meshTexturePath = "",
284  : Base(name, parent_joint, std::numeric_limits<FrameIndex>::max(), placement)
285  , geometry(collision_geometry)
286  , meshPath(meshPath)
292  , disableCollision(false)
293  {
294  }
295 
296  GeometryObject(const GeometryObject & other) = default;
297  GeometryObject & operator=(const GeometryObject & other) = default;
298 
303  {
304  GeometryObject res(*this);
305 
306 #ifdef PINOCCHIO_WITH_HPP_FCL
307  if (geometry)
308  res.geometry = CollisionGeometryPtr(geometry->clone());
309 #endif
310 
311  return res;
312  }
313 
314  bool operator==(const GeometryObject & other) const
315  {
316  if (this == &other)
317  return true;
318  return name == other.name && parentFrame == other.parentFrame
319  && parentJoint == other.parentJoint && placement == other.placement
320  && meshPath == other.meshPath && meshScale == other.meshScale
321  && overrideMaterial == other.overrideMaterial && meshColor == other.meshColor
325  }
326 
327  bool operator!=(const GeometryObject & other) const
328  {
329  return !(*this == other);
330  }
331 
332  friend std::ostream & operator<<(std::ostream & os, const GeometryObject & geomObject);
333  };
334 
335 #ifdef PINOCCHIO_WITH_HPP_FCL
336 
338  {
340  typedef SE3Tpl<double> SE3;
341 
343  : Base(nullptr, false)
344  , geometryObjectIndex((std::numeric_limits<size_t>::max)())
345  {
346  }
347 
348  explicit CollisionObject(
349  const std::shared_ptr<::hpp::fcl::CollisionGeometry> & collision_geometry,
350  const size_t geometryObjectIndex = (std::numeric_limits<size_t>::max)(),
351  bool compute_local_aabb = true)
352  : Base(collision_geometry, compute_local_aabb)
353  , geometryObjectIndex(geometryObjectIndex)
354  {
355  }
356 
358  const std::shared_ptr<::hpp::fcl::CollisionGeometry> & collision_geometry,
359  const SE3 & transform,
360  const size_t geometryObjectIndex = (std::numeric_limits<size_t>::max)(),
361  bool compute_local_aabb = true)
362  : Base(collision_geometry, toFclTransform3f(transform), compute_local_aabb)
363  , geometryObjectIndex(geometryObjectIndex)
364  {
365  }
366 
367  bool operator==(const CollisionObject & other) const
368  {
369  return Base::operator==(other) && geometryObjectIndex == other.geometryObjectIndex;
370  }
371 
372  bool operator!=(const CollisionObject & other) const
373  {
374  return !(*this == other);
375  }
376 
378  size_t geometryObjectIndex;
379  };
380 
381  struct ComputeCollision : ::hpp::fcl::ComputeCollision
382  {
383  typedef ::hpp::fcl::ComputeCollision Base;
384 
385  ComputeCollision(const GeometryObject & go1, const GeometryObject & go2)
386  : Base(go1.geometry.get(), go2.geometry.get())
387  , go1_ptr(&go1)
388  , go2_ptr(&go2)
389  {
390  }
391 
392  virtual ~ComputeCollision() {};
393 
394  virtual std::size_t run(
395  const fcl::Transform3f & tf1,
396  const fcl::Transform3f & tf2,
397  const fcl::CollisionRequest & request,
398  fcl::CollisionResult & result) const
399  {
401  const_cast<Pointer &>(Base::o1) = go1_ptr->geometry.get();
402  const_cast<Pointer &>(Base::o2) = go2_ptr->geometry.get();
403  return Base::run(tf1, tf2, request, result);
404  }
405 
406  bool operator==(const ComputeCollision & other) const
407  {
408  return Base::operator==(other) && go1_ptr == other.go1_ptr
409  && go2_ptr == other.go2_ptr; // Maybe, it would be better to just check *go2_ptr ==
410  // *other.go2_ptr
411  }
412 
413  bool operator!=(const ComputeCollision & other) const
414  {
415  return !(*this == other);
416  }
417 
418  const GeometryObject & getGeometryObject1() const
419  {
420  return *go1_ptr;
421  }
422  const GeometryObject & getGeometryObject2() const
423  {
424  return *go2_ptr;
425  }
426 
427  protected:
428  const GeometryObject * go1_ptr;
429  const GeometryObject * go2_ptr;
430  };
431 
432  struct ComputeDistance : ::hpp::fcl::ComputeDistance
433  {
434  typedef ::hpp::fcl::ComputeDistance Base;
435 
436  ComputeDistance(const GeometryObject & go1, const GeometryObject & go2)
437  : Base(go1.geometry.get(), go2.geometry.get())
438  , go1_ptr(&go1)
439  , go2_ptr(&go2)
440  {
441  }
442 
443  virtual ~ComputeDistance() {};
444 
445  virtual hpp::fcl::FCL_REAL run(
446  const fcl::Transform3f & tf1,
447  const fcl::Transform3f & tf2,
448  const fcl::DistanceRequest & request,
449  fcl::DistanceResult & result) const
450  {
452  const_cast<Pointer &>(Base::o1) = go1_ptr->geometry.get();
453  const_cast<Pointer &>(Base::o2) = go2_ptr->geometry.get();
454  return Base::run(tf1, tf2, request, result);
455  }
456 
457  bool operator==(const ComputeDistance & other) const
458  {
459  return Base::operator==(other) && go1_ptr == other.go1_ptr && go2_ptr == other.go2_ptr;
460  }
461 
462  bool operator!=(const ComputeDistance & other) const
463  {
464  return !(*this == other);
465  }
466 
467  const GeometryObject & getGeometryObject1() const
468  {
469  return *go1_ptr;
470  }
471  const GeometryObject & getGeometryObject2() const
472  {
473  return *go2_ptr;
474  }
475 
476  protected:
477  const GeometryObject * go1_ptr;
478  const GeometryObject * go2_ptr;
479  };
480 
481 #endif
482 
483 } // namespace pinocchio
484 
485 /* --- Details -------------------------------------------------------------- */
486 /* --- Details -------------------------------------------------------------- */
487 /* --- Details -------------------------------------------------------------- */
488 #include "pinocchio/multibody/geometry-object.hxx"
489 
490 #endif // ifndef __pinocchio_multibody_geometry_object_hpp__
pinocchio::GeometryObject::GeometryObject
PINOCCHIO_DEPRECATED 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: multibody/geometry-object.hpp:231
pinocchio::GeometryObject::Base
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ModelItem< GeometryObject > Base
Definition: multibody/geometry-object.hpp:93
display-shapes-meshcat.placement
placement
Definition: display-shapes-meshcat.py:24
hpp::fcl::ComputeCollision
pinocchio::FrameIndex
Index FrameIndex
Definition: multibody/fwd.hpp:28
pinocchio::GeometryObject::overrideMaterial
bool overrideMaterial
Decide whether to override the Material.
Definition: multibody/geometry-object.hpp:119
pinocchio::GeometryObject::GeometryObject
PINOCCHIO_DEPRECATED 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(0, 0, 0, 1), const std::string &meshTexturePath="", const GeometryMaterial &meshMaterial=GeometryNoMaterial())
Reduced constructor.
Definition: multibody/geometry-object.hpp:273
transform
HPP_FCL_DLLAPI Halfspace transform(const Halfspace &a, const Transform3f &tf)
pinocchio::ModelItem< GeometryObject >::parentJoint
JointIndex parentJoint
Index of the parent joint.
Definition: model-item.hpp:28
pinocchio::GeometryObject::meshScale
Eigen::Vector3d meshScale
Scaling vector applied to the GeometryObject::geometry object.
Definition: multibody/geometry-object.hpp:116
omniidl_be_python_with_docstring.run
def run(tree, args)
Definition: cmake/hpp/idl/omniidl_be_python_with_docstring.py:140
pinocchio::GeometryObject::SE3
SE3Tpl< Scalar, Options > SE3
Definition: multibody/geometry-object.hpp:100
pinocchio::GeometryPhongMaterial::GeometryPhongMaterial
GeometryPhongMaterial(const Eigen::Vector4d &meshEmissionColor, const Eigen::Vector4d &meshSpecularColor, double meshShininess)
Definition: multibody/geometry-object.hpp:44
pinocchio::Options
Options
Definition: joint-configuration.hpp:1082
pinocchio::GeometryPhongMaterial::meshSpecularColor
Eigen::Vector4d meshSpecularColor
RGBA specular color value of the GeometryObject::geometry object.
Definition: multibody/geometry-object.hpp:65
CollisionObject
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, bool compute_local_aabb=true)
pinocchio::SE3Tpl< Scalar, Options >
pinocchio::operator==
bool operator==(const ConstraintDataBase< ConstraintDataDerived > &data1, const ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > &data2)
Definition: constraint-data-generic.hpp:104
pinocchio::GeometryObject::meshColor
Eigen::Vector4d meshColor
RGBA color value of the GeometryObject::geometry object.
Definition: multibody/geometry-object.hpp:122
Base
BVNodeBase Base
serializable.hpp
nullptr
#define nullptr
pinocchio::GeometryNoMaterial::operator==
bool operator==(const GeometryNoMaterial &) const
Definition: multibody/geometry-object.hpp:33
pinocchio::ModelItem
Definition: model-item.hpp:13
pinocchio::compare_shared_ptr
bool compare_shared_ptr(const std::shared_ptr< T > &ptr1, const std::shared_ptr< T > &ptr2)
Compares two std::shared_ptr.
Definition: shared-ptr.hpp:16
pinocchio::GeometryObject
Definition: multibody/geometry-object.hpp:87
pinocchio::res
ReturnType res
Definition: spatial/classic-acceleration.hpp:57
shared-ptr.hpp
fcl.hpp
pinocchio::GeometryNoMaterial
No material associated to a geometry.
Definition: multibody/geometry-object.hpp:31
pinocchio::VISUAL
@ VISUAL
Definition: multibody/geometry-object.hpp:26
pinocchio::GeometryObject::GeometryObject
GeometryObject(const std::string &name, const JointIndex parent_joint, const SE3 &placement, const CollisionGeometryPtr &collision_geometry, 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())
Reduced constructor.
Definition: multibody/geometry-object.hpp:191
pinocchio::GeometryPhongMaterial::meshShininess
double meshShininess
Shininess associated to the specular lighting model.
Definition: multibody/geometry-object.hpp:70
pinocchio::ModelItem< GeometryObject >::placement
SE3 placement
Position of kinematic element in parent joint frame.
Definition: model-item.hpp:39
pinocchio::toFclTransform3f
hpp::fcl::Transform3f toFclTransform3f(const SE3Tpl< Scalar > &m)
Definition: collision/fcl-pinocchio-conversions.hpp:14
hpp::fcl::FCL_REAL
double FCL_REAL
pinocchio::GeometryPhongMaterial::operator==
bool operator==(const GeometryPhongMaterial &other) const
Definition: multibody/geometry-object.hpp:54
pinocchio::ModelItem< GeometryObject >::parentFrame
FrameIndex parentFrame
Index of the parent frame.
Definition: model-item.hpp:36
pinocchio::GeometryObject::meshMaterial
GeometryMaterial meshMaterial
Material associated to the mesh. This material should be used only if overrideMaterial is set to true...
Definition: multibody/geometry-object.hpp:127
reachable-workspace-with-collisions.parentJoint
parentJoint
Definition: reachable-workspace-with-collisions.py:48
collision-with-point-clouds.geometry
geometry
Definition: collision-with-point-clouds.py:82
se3.hpp
pinocchio::GeometryObject::GeometryObject
GeometryObject(const std::string &name, const JointIndex parent_joint, const FrameIndex parent_frame, const SE3 &placement, const CollisionGeometryPtr &collision_geometry, 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: multibody/geometry-object.hpp:151
hpp::fcl::CollisionObject
pinocchio::GeometryObject::meshPath
std::string meshPath
Absolute path to the mesh file (if the geometry pointee is also a Mesh)
Definition: multibody/geometry-object.hpp:113
pinocchio::GeometryMaterial
boost::variant< GeometryNoMaterial, GeometryPhongMaterial > GeometryMaterial
Definition: multibody/geometry-object.hpp:73
pinocchio::GeometryPhongMaterial::GeometryPhongMaterial
GeometryPhongMaterial()=default
pinocchio::GeometryObject::meshTexturePath
std::string meshTexturePath
Absolute path to the mesh texture file.
Definition: multibody/geometry-object.hpp:130
pinocchio::GeometryObject::geometry
CollisionGeometryPtr geometry
The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
Definition: multibody/geometry-object.hpp:110
setup.name
name
Definition: cmake/cython/setup.in.py:179
pinocchio::GeometryObject::operator==
bool operator==(const GeometryObject &other) const
Definition: multibody/geometry-object.hpp:314
pinocchio::fcl::CollisionGeometry
FakeCollisionGeometry CollisionGeometry
Definition: multibody/fcl.hpp:83
pinocchio::GeometryObject::clone
GeometryObject clone() const
Perform a deep copy of this. It will create a copy of the underlying FCL geometry.
Definition: multibody/geometry-object.hpp:302
pinocchio::GeometryObject::Options
@ Options
Definition: multibody/geometry-object.hpp:97
pinocchio::GeometryObject::Scalar
traits< GeometryObject >::Scalar Scalar
Definition: multibody/geometry-object.hpp:94
pinocchio::context::Options
@ Options
Definition: context/generic.hpp:45
pinocchio::operator!=
bool operator!=(const JointDataBase< JointDataDerived > &joint_data, const JointDataTpl< Scalar, Options, JointCollectionTpl > &joint_data_generic)
Definition: joint-generic.hpp:447
pinocchio::GeometryPhongMaterial
Definition: multibody/geometry-object.hpp:41
std
Definition: autodiff/casadi/utils/static-if.hpp:64
pinocchio::GeometryObject::disableCollision
bool disableCollision
If true, no collision or distance check will be done between the Geometry and any other geometry.
Definition: multibody/geometry-object.hpp:134
model-item.hpp
pinocchio::GeometryObject::operator=
GeometryObject & operator=(const GeometryObject &other)=default
hpp::fcl::ComputeDistance
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
pinocchio::GeometryType
GeometryType
Definition: multibody/geometry-object.hpp:24
pinocchio::GeometryObject::operator<<
friend std::ostream & operator<<(std::ostream &os, const GeometryObject &geomObject)
pinocchio::traits
Common traits structure to fully define base classes for CRTP.
Definition: fwd.hpp:71
pinocchio::COLLISION
@ COLLISION
Definition: multibody/geometry-object.hpp:27
pinocchio::GeometryObject::CollisionGeometryPtr
std::shared_ptr< fcl::CollisionGeometry > CollisionGeometryPtr
Definition: multibody/geometry-object.hpp:102
Base
pinocchio::SE3
SE3Tpl< context::Scalar, context::Options > SE3
Definition: spatial/fwd.hpp:64
pinocchio::GeometryObject::operator!=
bool operator!=(const GeometryObject &other) const
Definition: multibody/geometry-object.hpp:327
CppAD::max
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
Definition: autodiff/cppad.hpp:181
fwd.hpp
pinocchio::ModelItem< GeometryObject >::name
std::string name
Name of the kinematic element.
Definition: model-item.hpp:25
pinocchio::context::Scalar
PINOCCHIO_SCALAR_TYPE Scalar
Definition: context/generic.hpp:42
pinocchio::traits< GeometryObject >::Scalar
context::Scalar Scalar
Definition: multibody/geometry-object.hpp:80
pinocchio::serialization::Serializable
Definition: serialization/serializable.hpp:16
pinocchio::GeometryPhongMaterial::meshEmissionColor
Eigen::Vector4d meshEmissionColor
RGBA emission (ambient) color value of the GeometryObject::geometry object.
Definition: multibody/geometry-object.hpp:62
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
operator==
bool operator==(const AABB &other) const


pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:44