#include <fcl.hpp>
|
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(0, 0, 0, 1), 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::Ones(), 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) |
|
Definition at line 137 of file fcl.hpp.
◆ GeometryObject() [1/3]
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(0,0,0,1) , |
|
|
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 200 of file fcl.hpp.
◆ GeometryObject() [2/3]
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 241 of file fcl.hpp.
◆ GeometryObject() [3/3]
◆ operator=()
◆ operator<<
std::ostream& operator<< |
( |
std::ostream & |
os, |
|
|
const GeometryObject & |
geomObject |
|
) |
| |
|
friend |
◆ CollisionGeometryPtr
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef shared_ptr<fcl::CollisionGeometry> pinocchio::GeometryObject::CollisionGeometryPtr |
◆ disableCollision
bool pinocchio::GeometryObject::disableCollision |
If true, no collision or distance check will be done between the Geometry and any other geometry.
Definition at line 182 of file fcl.hpp.
◆ fcl
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 161 of file fcl.hpp.
◆ geometry
CollisionGeometryPtr pinocchio::GeometryObject::geometry |
The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
Definition at line 157 of file fcl.hpp.
◆ meshColor
Eigen::Vector4d pinocchio::GeometryObject::meshColor |
◆ meshPath
std::string pinocchio::GeometryObject::meshPath |
Absolute path to the mesh file (if the fcl pointee is also a Mesh)
Definition at line 167 of file fcl.hpp.
◆ meshScale
Eigen::Vector3d pinocchio::GeometryObject::meshScale |
◆ meshTexturePath
std::string pinocchio::GeometryObject::meshTexturePath |
Absolute path to the mesh texture file.
Definition at line 179 of file fcl.hpp.
◆ name
std::string pinocchio::GeometryObject::name |
Name of the geometry object.
Definition at line 144 of file fcl.hpp.
◆ overrideMaterial
bool pinocchio::GeometryObject::overrideMaterial |
Decide whether to override the Material.
Definition at line 173 of file fcl.hpp.
◆ 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 151 of file fcl.hpp.
◆ parentJoint
Index of the parent joint.
Definition at line 154 of file fcl.hpp.
◆ placement
SE3 pinocchio::GeometryObject::placement |
Position of geometry object in parent joint frame.
Definition at line 164 of file fcl.hpp.
The documentation for this struct was generated from the following file: