Struct GeometryObject
Defined in File geometry-object.hpp
Inheritance Relationships
Base Types
public pinocchio::ModelItem< GeometryObject >
(Template Struct ModelItem)public pinocchio::serialization::Serializable< GeometryObject >
(Template Struct Serializable)
Struct Documentation
-
struct GeometryObject : public pinocchio::ModelItem<GeometryObject>, public pinocchio::serialization::Serializable<GeometryObject>
Public Types
Values:
-
enumerator Options
-
enumerator Options
-
typedef traits<GeometryObject>::Scalar Scalar
-
typedef std::shared_ptr<fcl::CollisionGeometry> CollisionGeometryPtr
Public Functions
-
inline 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.
- Parameters:
name – [in] Name of the geometry object.
parent_joint – [in] Index of the parent joint (that supports the geometry).
parent_frame – [in] Index of the parent frame.
placement – [in] Placement of the geometry with respect to the joint frame.
collision_geometry – [in] The FCL collision geometry object.
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 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.
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).
placement – [in] Placement of the geometry with respect to the joint frame.
collision_geometry – [in] The FCL collision geometry object.
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_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.
- Deprecated:
This constructor is now deprecated, and its argument order has been changed.
- 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_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.
- Deprecated:
This constructor is now deprecated, and its argument order has been changed.
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].
-
GeometryObject(const GeometryObject &other) = default
-
GeometryObject &operator=(const GeometryObject &other) = default
-
inline GeometryObject clone() const
Perform a deep copy of this. It will create a copy of the underlying FCL geometry.
-
inline bool operator==(const GeometryObject &other) const
-
inline bool operator!=(const GeometryObject &other) const
Public Members
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ModelItem< GeometryObject > Base
-
CollisionGeometryPtr geometry
The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
-
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 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)