/// 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.
FrameIndexparentFrame;
/// \brief Index of the parent joint
JointIndexparentJoint;
usingBase::name;
usingBase::parentFrame;
usingBase::parentJoint;
usingBase::placement;
/// \brief The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
CollisionGeometryPtrgeometry;
...
...
@@ -141,9 +148,6 @@ struct GeometryObject
/// \deprecated It is now deprecated and has been renamed GeometryObject::geometry
PINOCCHIO_DEPRECATEDCollisionGeometryPtr&fcl;
/// \brief Position of geometry object in parent joint frame
SE3placement;
/// \brief Absolute path to the mesh file (if the fcl pointee is also a Mesh)