|
typedef boost::shared_ptr< fcl::CollisionGeometry > | CollisionGeometryPtr |
|
|
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 GeometryObject & | operator= (const GeometryObject &other) |
|
|
bool | disableCollision |
| If true, no collision or distance check will be done between the Geometry and any other geometry.
|
|
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.
|
|
|
std::ostream & | operator<< (std::ostream &os, const GeometryObject &geomObject) |
|
Definition at line 118 of file fcl.hpp.
◆ GeometryObject() [1/2]
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 = "" |
|
) |
| |
|
inline |
Full constructor.
- Parameters
-
[in] | name | Name of the geometry object. |
[in] | parent_frame | Index of the parent frame. |
[in] | parent_joint | Index of the parent joint (that supports the geometry). |
[in] | collision_geometry | The FCL collision geometry object. |
[in] | placement | Placement of the geometry with respect to the joint frame. |
[in] | meshPath | Path of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable]. |
[in] | meshScale | Scale of the mesh [if applicable]. |
[in] | overrideMaterial | If true, this option allows to overrite the material [if applicable]. |
[in] | meshColor | Color of the mesh [if applicable]. |
[in] | meshTexturePath | Path to the file containing the texture information [if applicable]. |
Definition at line 181 of file fcl.hpp.
◆ GeometryObject() [2/2]
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 = "" |
|
) |
| |
|
inline |
Reduced constructor.
- Parameters
-
[in] | name | Name of the geometry object. |
[in] | parent_joint | Index of the parent joint (that supports the geometry). |
[in] | collision_geometry | The FCL collision geometry object. |
[in] | placement | Placement of the geometry with respect to the joint frame. |
[in] | meshPath | Path of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable]. |
[in] | meshScale | Scale of the mesh [if applicable]. |
[in] | overrideMaterial | If true, this option allows to overrite the material [if applicable]. |
[in] | meshColor | Color of the mesh [if applicable]. |
[in] | meshTexturePath | Path to the file containing the texture information [if applicable]. |
Definition at line 222 of file fcl.hpp.
◆ fcl
PINOCCHIO_DEPRECATED CollisionGeometryPtr& fcl |
◆ 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.
The documentation for this struct was generated from the following file: