pinocchio  3.9.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
Loading...
Searching...
No Matches
GeometryObject Struct Reference
Inheritance diagram for GeometryObject:
Collaboration diagram for GeometryObject:

Public Types

enum  { Options = traits<GeometryObject>::Options }
typedef ModelItem< GeometryObjectBase
typedef std::shared_ptr< fcl::CollisionGeometry > CollisionGeometryPtr
typedef traits< GeometryObject >::Scalar Scalar
typedef SE3Tpl< Scalar, Options > SE3
Public Types inherited from ModelItem< GeometryObject >
enum  
typedef traits< GeometryObject >::Scalar Scalar
typedef SE3Tpl< Scalar, Options > SE3
Public Types inherited from NumericalBase< Derived >
typedef traits< Derived >::Scalar Scalar

Public Member Functions

 GeometryObject (const GeometryObject &other)=default
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.
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.
 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.
 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.
GeometryObject clone () const
 Perform a deep copy of this. It will create a copy of the underlying FCL geometry.
bool operator!= (const GeometryObject &other) const
GeometryObjectoperator= (const GeometryObject &other)=default
bool operator== (const GeometryObject &other) const
Public Member Functions inherited from ModelItem< GeometryObject >
 ModelItem ()
 Default constructor of ModelItem.
 ModelItem (const std::string &name, const JointIndex parent_joint, const FrameIndex parent_frame, const SE3 &frame_placement)
 Builds a kinematic element defined by its name, its joint parent id, its parent frame id and its placement.
bool operator== (const ModelItem &other) const
Public Member Functions inherited from Serializable< GeometryObject >
void loadFromBinary (const std::string &filename)
 Loads a Derived object from an binary file.
void loadFromString (const std::string &str)
 Loads a Derived object from a string.
void loadFromStringStream (std::istringstream &is)
 Loads a Derived object from a stream string.
void loadFromText (const std::string &filename)
 Loads a Derived object from a text file.
void loadFromXML (const std::string &filename, const std::string &tag_name)
 Loads a Derived object from an XML file.
void saveToBinary (const std::string &filename) const
 Saves a Derived object as an binary file.
std::string saveToString () const
 Saves a Derived object to a string.
void saveToStringStream (std::stringstream &ss) const
 Saves a Derived object to a string stream.
void saveToText (const std::string &filename) const
 Saves a Derived object as a text file.
void saveToXML (const std::string &filename, const std::string &tag_name) const
 Saves a Derived object as an XML file.

Public Attributes

bool disableCollision
 If true, no collision or distance check will be done between the Geometry and any other geometry.
CollisionGeometryPtr geometry
 The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
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 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.
std::string meshTexturePath
 Absolute path to the mesh texture file.
std::string name
 Name of the kinematic element.
bool overrideMaterial
 Decide whether to override the Material.
FrameIndex parentFrame
 Index of the parent frame.
JointIndex parentJoint
 Index of the parent joint.
SE3 placement
 Position of kinematic element in parent joint frame.
Public Attributes inherited from ModelItem< GeometryObject >
std::string name
 Name of the kinematic element.
FrameIndex parentFrame
 Index of the parent frame.
JointIndex parentJoint
 Index of the parent joint.
SE3 placement
 Position of kinematic element in parent joint frame.

Friends

std::ostream & operator<< (std::ostream &os, const GeometryObject &geomObject)

Detailed Description

Definition at line 87 of file geometry-object.hpp.

Member Typedef Documentation

◆ Base

Definition at line 93 of file geometry-object.hpp.

◆ CollisionGeometryPtr

typedef std::shared_ptr<fcl::CollisionGeometry> CollisionGeometryPtr

Definition at line 102 of file geometry-object.hpp.

◆ Scalar

typedef traits<GeometryObject>::Scalar Scalar

Definition at line 94 of file geometry-object.hpp.

◆ SE3

typedef SE3Tpl<Scalar, Options> SE3

Definition at line 100 of file geometry-object.hpp.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum

Definition at line 95 of file geometry-object.hpp.

Constructor & Destructor Documentation

◆ GeometryObject() [1/4]

GeometryObject(const std::string &name,
const JointIndexparent_joint,
const FrameIndexparent_frame,
const SE3 &placement,
const CollisionGeometryPtr &collision_geometry,
const std::string &meshPath = "",
const Eigen::Vector3d &meshScale = Eigen::Vector3d::Ones(),
const booloverrideMaterial = false,
const Eigen::Vector4d &meshColor = Eigen::Vector4d(0, 0, 0, 1),
const std::string &meshTexturePath = "",
const GeometryMaterial &meshMaterial = GeometryNoMaterial() )
inline

Full constructor.

Parameters
[in]nameName of the geometry object.
[in]parent_jointIndex of the parent joint (that supports the geometry).
[in]parent_frameIndex of the parent frame.
[in]placementPlacement of the geometry with respect to the joint frame.
[in]collision_geometryThe FCL collision geometry object.
[in]meshPathPath of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable].
[in]meshScaleScale of the mesh [if applicable].
[in]overrideMaterialIf true, this option allows to overrite the material [if applicable].
[in]meshColorColor of the mesh [if applicable].
[in]meshTexturePathPath to the file containing the texture information [if applicable].
[in]meshMaterialMaterial of the mesh [if applicable].

Definition at line 151 of file geometry-object.hpp.

◆ GeometryObject() [2/4]

GeometryObject(const std::string &name,
const JointIndexparent_joint,
const SE3 &placement,
const CollisionGeometryPtr &collision_geometry,
const std::string &meshPath = "",
const Eigen::Vector3d &meshScale = Eigen::Vector3d::Ones(),
const booloverrideMaterial = false,
const Eigen::Vector4d &meshColor = Eigen::Vector4d(0, 0, 0, 1),
const std::string &meshTexturePath = "",
const GeometryMaterial &meshMaterial = GeometryNoMaterial() )
inline

Reduced constructor.

Remarks
Compared to the other constructor, this one assumes that there is no parentFrame associated to the geometry.
Parameters
[in]nameName of the geometry object.
[in]parent_jointIndex of the parent joint (that supports the geometry).
[in]placementPlacement of the geometry with respect to the joint frame.
[in]collision_geometryThe FCL collision geometry object.
[in]meshPathPath of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable].
[in]meshScaleScale of the mesh [if applicable].
[in]overrideMaterialIf true, this option allows to overrite the material [if applicable].
[in]meshColorColor of the mesh [if applicable].
[in]meshTexturePathPath to the file containing the texture information [if applicable].
[in]meshMaterialMaterial of the mesh [if applicable].

Definition at line 191 of file geometry-object.hpp.

◆ GeometryObject() [3/4]

PINOCCHIO_DEPRECATED GeometryObject(const std::string &name,
const FrameIndexparent_frame,
const JointIndexparent_joint,
const CollisionGeometryPtr &collision_geometry,
const SE3 &placement,
const std::string &meshPath = "",
const Eigen::Vector3d &meshScale = Eigen::Vector3d::Ones(),
const booloverrideMaterial = false,
const Eigen::Vector4d &meshColor = Eigen::Vector4d(0, 0, 0, 1),
const std::string &meshTexturePath = "",
const GeometryMaterial &meshMaterial = GeometryNoMaterial() )
inline

Full constructor.

Parameters
[in]nameName of the geometry object.
[in]parent_frameIndex of the parent frame.
[in]parent_jointIndex of the parent joint (that supports the geometry).
[in]collision_geometryThe FCL collision geometry object.
[in]placementPlacement of the geometry with respect to the joint frame.
[in]meshPathPath of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable].
[in]meshScaleScale of the mesh [if applicable].
[in]overrideMaterialIf true, this option allows to overrite the material [if applicable].
[in]meshColorColor of the mesh [if applicable].
[in]meshTexturePathPath to the file containing the texture information [if applicable].
[in]meshMaterialMaterial of the mesh [if applicable].
Deprecated
This constructor is now deprecated, and its argument order has been changed.

Definition at line 231 of file geometry-object.hpp.

◆ GeometryObject() [4/4]

PINOCCHIO_DEPRECATED GeometryObject(const std::string &name,
const JointIndexparent_joint,
const CollisionGeometryPtr &collision_geometry,
const SE3 &placement,
const std::string &meshPath = "",
const Eigen::Vector3d &meshScale = Eigen::Vector3d::Ones(),
const booloverrideMaterial = false,
const Eigen::Vector4d &meshColor = Eigen::Vector4d(0, 0, 0, 1),
const std::string &meshTexturePath = "",
const GeometryMaterial &meshMaterial = GeometryNoMaterial() )
inline

Reduced constructor.

Remarks
Compared to the other constructor, this one assumes that there is no parentFrame associated to the geometry.
Parameters
[in]nameName of the geometry object.
[in]parent_jointIndex of the parent joint (that supports the geometry).
[in]collision_geometryThe FCL collision geometry object.
[in]placementPlacement of the geometry with respect to the joint frame.
[in]meshPathPath of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable].
[in]meshScaleScale of the mesh [if applicable].
[in]overrideMaterialIf true, this option allows to overrite the material [if applicable].
[in]meshColorColor of the mesh [if applicable].
[in]meshTexturePathPath to the file containing the texture information [if applicable].
[in]meshMaterialMaterial of the mesh [if applicable].
Deprecated
This constructor is now deprecated, and its argument order has been changed.

Definition at line 273 of file geometry-object.hpp.

Member Function Documentation

◆ clone()

GeometryObject clone()const
inline

Perform a deep copy of this. It will create a copy of the underlying FCL geometry.

Definition at line 302 of file geometry-object.hpp.

◆ operator!=()

bool operator!=(const GeometryObject &other)const
inline

Definition at line 327 of file geometry-object.hpp.

◆ operator==()

bool operator==(const GeometryObject &other)const
inline

Definition at line 314 of file geometry-object.hpp.

Member Data Documentation

◆ disableCollision

bool disableCollision

If true, no collision or distance check will be done between the Geometry and any other geometry.

Definition at line 134 of file geometry-object.hpp.

◆ geometry

CollisionGeometryPtr geometry

The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)

Definition at line 110 of file geometry-object.hpp.

◆ meshColor

Eigen::Vector4d meshColor

RGBA color value of the GeometryObject::geometry object.

Definition at line 122 of file geometry-object.hpp.

◆ meshMaterial

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.

Definition at line 127 of file geometry-object.hpp.

◆ meshPath

std::string meshPath

Absolute path to the mesh file (if the geometry pointee is also a Mesh)

Definition at line 113 of file geometry-object.hpp.

◆ meshScale

Eigen::Vector3d meshScale

Scaling vector applied to the GeometryObject::geometry object.

Definition at line 116 of file geometry-object.hpp.

◆ meshTexturePath

std::string meshTexturePath

Absolute path to the mesh texture file.

Definition at line 130 of file geometry-object.hpp.

◆ name

std::string name

Name of the kinematic element.

Definition at line 25 of file model-item.hpp.

◆ overrideMaterial

bool overrideMaterial

Decide whether to override the Material.

Definition at line 119 of file geometry-object.hpp.

◆ parentFrame

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.

Definition at line 36 of file model-item.hpp.

◆ parentJoint

JointIndex parentJoint

Index of the parent joint.

Definition at line 28 of file model-item.hpp.

◆ placement

SE3 placement

Position of kinematic element in parent joint frame.

Definition at line 39 of file model-item.hpp.


The documentation for this struct was generated from the following file: