Public Member Functions | Public Attributes | Friends | List of all members
pinocchio::GeometryObject Struct Reference

#include <fcl.hpp>

Public Member Functions

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

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr< fcl::CollisionGeometryCollisionGeometryPtr
 
bool disableCollision
 If true, no collision or distance check will be done between the Geometry and any other geometry. More...
 
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.) More...
 
Eigen::Vector4d meshColor
 RGBA color value of the GeometryObject::fcl object. More...
 
std::string meshPath
 Absolute path to the mesh file (if the fcl pointee is also a Mesh) More...
 
Eigen::Vector3d meshScale
 Scaling vector applied to the GeometryObject::fcl object. More...
 
std::string meshTexturePath
 Absolute path to the mesh texture file. More...
 
std::string name
 Name of the geometry object. More...
 
bool overrideMaterial
 Decide whether to override the Material. More...
 
FrameIndex parentFrame
 Index of the parent frame. More...
 
JointIndex parentJoint
 Index of the parent joint. More...
 
SE3 placement
 Position of geometry object in parent joint frame. More...
 

Friends

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

Detailed Description

Definition at line 118 of file fcl.hpp.

Constructor & Destructor Documentation

PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS pinocchio::GeometryObject::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 181 of file fcl.hpp.

PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS pinocchio::GeometryObject::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 222 of file fcl.hpp.

Definition at line 248 of file fcl.hpp.

Member Function Documentation

PINOCCHIO_COMPILER_DIAGNOSTIC_POP GeometryObject& pinocchio::GeometryObject::operator= ( const GeometryObject other)
inline

Definition at line 256 of file fcl.hpp.

Friends And Related Function Documentation

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

Member Data Documentation

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr<fcl::CollisionGeometry> pinocchio::GeometryObject::CollisionGeometryPtr

Definition at line 122 of file fcl.hpp.

bool pinocchio::GeometryObject::disableCollision

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

Definition at line 163 of file fcl.hpp.

PINOCCHIO_DEPRECATED CollisionGeometryPtr& pinocchio::GeometryObject::fcl

The former pointer to the FCL CollisionGeometry.

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

Definition at line 142 of file fcl.hpp.

CollisionGeometryPtr pinocchio::GeometryObject::geometry

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

Definition at line 138 of file fcl.hpp.

Eigen::Vector4d pinocchio::GeometryObject::meshColor

RGBA color value of the GeometryObject::fcl object.

Definition at line 157 of file fcl.hpp.

std::string pinocchio::GeometryObject::meshPath

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

Definition at line 148 of file fcl.hpp.

Eigen::Vector3d pinocchio::GeometryObject::meshScale

Scaling vector applied to the GeometryObject::fcl object.

Definition at line 151 of file fcl.hpp.

std::string pinocchio::GeometryObject::meshTexturePath

Absolute path to the mesh texture file.

Definition at line 160 of file fcl.hpp.

std::string pinocchio::GeometryObject::name

Name of the geometry object.

Definition at line 125 of file fcl.hpp.

bool pinocchio::GeometryObject::overrideMaterial

Decide whether to override the Material.

Definition at line 154 of file fcl.hpp.

FrameIndex pinocchio::GeometryObject::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 132 of file fcl.hpp.

JointIndex pinocchio::GeometryObject::parentJoint

Index of the parent joint.

Definition at line 135 of file fcl.hpp.

SE3 pinocchio::GeometryObject::placement

Position of geometry object in parent joint frame.

Definition at line 145 of file fcl.hpp.


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


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:05