pinocchio  2.4.4
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
GeometryObject Struct Reference
Collaboration diagram for GeometryObject:

Public Types

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

Public Member Functions

 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::Zero(), const std::string &meshTexturePath="")
 Full constructor. More...
 
 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::Zero(), const std::string &meshTexturePath="")
 Reduced constructor. More...
 
 GeometryObject (const GeometryObject &other)
 
GeometryObjectoperator= (const GeometryObject &other)
 

Public Attributes

PINOCCHIO_DEPRECATED CollisionGeometryPtr & fcl
 The former pointer to the FCL CollisionGeometry. More...
 
CollisionGeometryPtr geometry
 The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
 
Eigen::Vector4d meshColor
 RGBA color value of the GeometryObject::fcl object.
 
std::string meshPath
 Absolute path to the mesh file (if the fcl pointee is also a Mesh)
 
Eigen::Vector3d meshScale
 Scaling vector applied to the GeometryObject::fcl object.
 
std::string meshTexturePath
 Absolute path to the mesh texture file.
 
std::string name
 Name of the geometry object.
 
bool overrideMaterial
 Decide whether to override the Material.
 
FrameIndex parentFrame
 Index of the parent frame. More...
 
JointIndex parentJoint
 Index of the parent joint.
 
SE3 placement
 Position of geometry object in parent joint frame.
 

Friends

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

Detailed Description

Definition at line 83 of file fcl.hpp.

Constructor & Destructor Documentation

◆ GeometryObject() [1/2]

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::Zero(),
const std::string &  meshTexturePath = "" 
)
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].

Definition at line 143 of file fcl.hpp.

◆ GeometryObject() [2/2]

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::Zero(),
const std::string &  meshTexturePath = "" 
)
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].

Definition at line 183 of file fcl.hpp.

Member Data Documentation

◆ fcl

PINOCCHIO_DEPRECATED CollisionGeometryPtr& fcl

The former pointer to the FCL CollisionGeometry.

Deprecated:
It is now deprecated and has been renamed GeometryObject::geometry

Definition at line 107 of file fcl.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 97 of file fcl.hpp.


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