Struct GeometryObject
Defined in File fcl.hpp
Struct Documentation
-
struct GeometryObject
Public Functions
- inline 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.
- Parameters:
name – [in] Name of the geometry object.
parent_frame – [in] Index of the parent frame.
parent_joint – [in] Index of the parent joint (that supports the geometry).
collision_geometry – [in] The FCL collision geometry object.
placement – [in] Placement of the geometry with respect to the joint frame.
meshPath – [in] Path of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable].
meshScale – [in] Scale of the mesh [if applicable].
overrideMaterial – [in] If true, this option allows to overrite the material [if applicable].
meshColor – [in] Color of the mesh [if applicable].
meshTexturePath – [in] Path to the file containing the texture information [if applicable].
meshMaterial – [in] Material of the mesh [if applicable].
- inline 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.
Remark
Compared to the other constructor, this one assumes that there is no parentFrame associated to the geometry.
- Parameters:
name – [in] Name of the geometry object.
parent_joint – [in] Index of the parent joint (that supports the geometry).
collision_geometry – [in] The FCL collision geometry object.
placement – [in] Placement of the geometry with respect to the joint frame.
meshPath – [in] Path of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable].
meshScale – [in] Scale of the mesh [if applicable].
overrideMaterial – [in] If true, this option allows to overrite the material [if applicable].
meshColor – [in] Color of the mesh [if applicable].
meshTexturePath – [in] Path to the file containing the texture information [if applicable].
meshMaterial – [in] Material of the mesh [if applicable].
- inline PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS GeometryObject (const GeometryObject &other)
- inline PINOCCHIO_COMPILER_DIAGNOSTIC_POP GeometryObject & operator= (const GeometryObject &other)
Public Members
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef shared_ptr< fcl::CollisionGeometry > CollisionGeometryPtr
-
std::string name
Name of the geometry object.
-
FrameIndex parentFrame
Index of the parent frame.
Parent frame may be unset (to the std::numeric_limits<FrameIndex>::max() value) as it is mostly used as a documentation of the tree, or in third-party libraries. The URDF parser of Pinocchio is setting it to the proper value according to the urdf link-joint tree. In particular, anchor joints of URDF would cause parent frame to be different to joint frame.
-
JointIndex parentJoint
Index of the parent joint.
-
CollisionGeometryPtr geometry
The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
- PINOCCHIO_DEPRECATED CollisionGeometryPtr & fcl
The former pointer to the FCL CollisionGeometry.
- Deprecated:
It is now deprecated and has been renamed GeometryObject::geometry
-
SE3 placement
Position of geometry object in parent joint frame.
-
std::string meshPath
Absolute path to the mesh file (if the geometry pointee is also a Mesh)
-
Eigen::Vector3d meshScale
Scaling vector applied to the GeometryObject::geometry object.
-
bool overrideMaterial
Decide whether to override the Material.
-
Eigen::Vector4d meshColor
RGBA diffuse color value of the GeometryObject::geometry object.
-
GeometryMaterial meshMaterial
Material associated to the mesh. This material should be used only if overrideMaterial is set to true. In other case, the mesh default material must be used.
-
std::string meshTexturePath
Absolute path to the mesh texture file.
-
bool disableCollision
If true, no collision or distance check will be done between the Geometry and any other geometry.
Friends
-
friend std::ostream &operator<<(std::ostream &os, const GeometryObject &geomObject)