Go to the documentation of this file.
5 #ifndef __pinocchio_multibody_geometry_object_hpp__
6 #define __pinocchio_multibody_geometry_object_hpp__
19 #include <boost/variant.hpp>
91 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
105 using Base::parentFrame;
152 const std::string &
name,
158 const Eigen::Vector3d &
meshScale = Eigen::Vector3d::Ones(),
160 const Eigen::Vector4d &
meshColor = Eigen::Vector4d(0, 0, 0, 1),
192 const std::string &
name,
197 const Eigen::Vector3d &
meshScale = Eigen::Vector3d::Ones(),
199 const Eigen::Vector4d &
meshColor = Eigen::Vector4d(0, 0, 0, 1),
232 const std::string &
name,
238 const Eigen::Vector3d &
meshScale = Eigen::Vector3d::Ones(),
240 const Eigen::Vector4d &
meshColor = Eigen::Vector4d(0, 0, 0, 1),
274 const std::string &
name,
279 const Eigen::Vector3d &
meshScale = Eigen::Vector3d::Ones(),
281 const Eigen::Vector4d &
meshColor = Eigen::Vector4d(0, 0, 0, 1),
306 #ifdef PINOCCHIO_WITH_HPP_FCL
329 return !(*
this == other);
335 #ifdef PINOCCHIO_WITH_HPP_FCL
340 typedef SE3Tpl<double>
SE3;
344 , geometryObjectIndex((
std::numeric_limits<size_t>::
max)())
349 const std::shared_ptr<::hpp::fcl::CollisionGeometry> & collision_geometry,
351 bool compute_local_aabb =
true)
352 :
Base(collision_geometry, compute_local_aabb)
353 , geometryObjectIndex(geometryObjectIndex)
358 const std::shared_ptr<::hpp::fcl::CollisionGeometry> & collision_geometry,
359 const SE3 & transform,
361 bool compute_local_aabb =
true)
363 , geometryObjectIndex(geometryObjectIndex)
369 return Base::operator==(other) && geometryObjectIndex == other.geometryObjectIndex;
374 return !(*
this == other);
378 size_t geometryObjectIndex;
383 typedef ::hpp::fcl::ComputeCollision
Base;
385 ComputeCollision(
const GeometryObject & go1,
const GeometryObject & go2)
392 virtual ~ComputeCollision() {};
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
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);
406 bool operator==(
const ComputeCollision & other)
const
409 && go2_ptr == other.go2_ptr;
413 bool operator!=(
const ComputeCollision & other)
const
415 return !(*
this == other);
418 const GeometryObject & getGeometryObject1()
const
422 const GeometryObject & getGeometryObject2()
const
428 const GeometryObject * go1_ptr;
429 const GeometryObject * go2_ptr;
434 typedef ::hpp::fcl::ComputeDistance
Base;
436 ComputeDistance(
const GeometryObject & go1,
const GeometryObject & go2)
443 virtual ~ComputeDistance() {};
446 const fcl::Transform3f & tf1,
447 const fcl::Transform3f & tf2,
448 const fcl::DistanceRequest & request,
449 fcl::DistanceResult & result)
const
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);
457 bool operator==(
const ComputeDistance & other)
const
459 return Base::operator==(other) && go1_ptr == other.go1_ptr && go2_ptr == other.go2_ptr;
462 bool operator!=(
const ComputeDistance & other)
const
464 return !(*
this == other);
467 const GeometryObject & getGeometryObject1()
const
471 const GeometryObject & getGeometryObject2()
const
477 const GeometryObject * go1_ptr;
478 const GeometryObject * go2_ptr;
488 #include "pinocchio/multibody/geometry-object.hxx"
490 #endif // ifndef __pinocchio_multibody_geometry_object_hpp__
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.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ModelItem< GeometryObject > Base
bool overrideMaterial
Decide whether to override the Material.
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.
HPP_FCL_DLLAPI Halfspace transform(const Halfspace &a, const Transform3f &tf)
JointIndex parentJoint
Index of the parent joint.
Eigen::Vector3d meshScale
Scaling vector applied to the GeometryObject::geometry object.
SE3Tpl< Scalar, Options > SE3
GeometryPhongMaterial(const Eigen::Vector4d &meshEmissionColor, const Eigen::Vector4d &meshSpecularColor, double meshShininess)
Eigen::Vector4d meshSpecularColor
RGBA specular color value of the GeometryObject::geometry object.
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, bool compute_local_aabb=true)
bool operator==(const ConstraintDataBase< ConstraintDataDerived > &data1, const ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > &data2)
Eigen::Vector4d meshColor
RGBA color value of the GeometryObject::geometry object.
bool operator==(const GeometryNoMaterial &) const
bool compare_shared_ptr(const std::shared_ptr< T > &ptr1, const std::shared_ptr< T > &ptr2)
Compares two std::shared_ptr.
No material associated to a geometry.
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.
double meshShininess
Shininess associated to the specular lighting model.
SE3 placement
Position of kinematic element in parent joint frame.
hpp::fcl::Transform3f toFclTransform3f(const SE3Tpl< Scalar > &m)
bool operator==(const GeometryPhongMaterial &other) const
FrameIndex parentFrame
Index of the parent frame.
GeometryMaterial meshMaterial
Material associated to the mesh. This material should be used only if overrideMaterial is set to true...
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.
std::string meshPath
Absolute path to the mesh file (if the geometry pointee is also a Mesh)
boost::variant< GeometryNoMaterial, GeometryPhongMaterial > GeometryMaterial
GeometryPhongMaterial()=default
std::string meshTexturePath
Absolute path to the mesh texture file.
CollisionGeometryPtr geometry
The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
bool operator==(const GeometryObject &other) const
FakeCollisionGeometry CollisionGeometry
GeometryObject clone() const
Perform a deep copy of this. It will create a copy of the underlying FCL geometry.
traits< GeometryObject >::Scalar Scalar
bool operator!=(const JointDataBase< JointDataDerived > &joint_data, const JointDataTpl< Scalar, Options, JointCollectionTpl > &joint_data_generic)
bool disableCollision
If true, no collision or distance check will be done between the Geometry and any other geometry.
GeometryObject & operator=(const GeometryObject &other)=default
friend std::ostream & operator<<(std::ostream &os, const GeometryObject &geomObject)
Common traits structure to fully define base classes for CRTP.
std::shared_ptr< fcl::CollisionGeometry > CollisionGeometryPtr
SE3Tpl< context::Scalar, context::Options > SE3
bool operator!=(const GeometryObject &other) const
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
std::string name
Name of the kinematic element.
PINOCCHIO_SCALAR_TYPE Scalar
Eigen::Vector4d meshEmissionColor
RGBA emission (ambient) color value of the GeometryObject::geometry object.
Main pinocchio namespace.
bool operator==(const AABB &other) const
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:44