Template Struct FrameTpl

Inheritance Relationships

Base Type

Struct Documentation

template<typename _Scalar, int _Options>
struct FrameTpl : public pinocchio::ModelItem<FrameTpl<_Scalar, _Options>>

A Plucker coordinate frame attached to a parent joint inside a kinematic tree.

Public Types

Values:

enumerator Options
typedef traits<ModelItemDerived>::Scalar Scalar
typedef ModelItem<ModelItemDerived> Base
typedef SE3Tpl<Scalar, Options> SE3
typedef InertiaTpl<Scalar, Options> Inertia
typedef pinocchio::JointIndex JointIndex

Public Functions

inline PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS FrameTpl ()

Default constructor of a frame.

inline PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS FrameTpl (const std::string &name, const JointIndex parentJoint, const SE3 &frame_placement, const FrameType type, const Inertia &inertia=Inertia::Zero())

Builds a frame defined by its name, its joint parent id, its placement and its type.

Parameters:
  • name[in] Name of the frame.

  • parent[in] Index of the parent joint in the kinematic tree.

  • frame_placement[in] Placement of the frame wrt the parent joint frame.

  • type[in] The type of the frame, see the enum FrameType.

  • inertia[in] Inertia info attached to the frame.

inline PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS FrameTpl (const std::string &name, const JointIndex parent_joint, const FrameIndex parent_frame, const SE3 &frame_placement, const FrameType type, const Inertia &inertia=Inertia::Zero())

Builds a frame defined by its name, its joint parent id, its placement and its type.

Parameters:
  • name[in] Name of the frame.

  • parent[in] Index of the parent joint in the kinematic tree.

  • parentFrame[in] Index of the parent frame in the kinematic tree.

  • frame_placement[in] Placement of the frame wrt the parent joint frame.

  • type[in] The type of the frame, see the enum FrameType.

  • inertia[in] Inertia info attached to the frame.

inline PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS FrameTpl (const FrameTpl &other)

Copy constructor.

Parameters:

other[in] Frame to copy

template<typename S2, int O2> inline explicit PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS FrameTpl (const FrameTpl< S2, O2 > &other)

Copy constructor by casting.

Parameters:

other[in] Frame to copy

inline PINOCCHIO_COMPILER_DIAGNOSTIC_POP FrameTpl< Scalar, Options > & operator= (const FrameTpl< Scalar, Options > &other)

Copy assignment operator. It needs to be user-define because references cannot be re-assigned during copy.

Parameters:

other[in] Frame to copy

template<typename S2, int O2>
inline bool operator==(const FrameTpl<S2, O2> &other) const

Equality comparison operator.

Parameters:

other[in] The frame to which the current frame is compared.

Returns:

true if *this is equal to other.

template<typename S2, int O2>
inline bool operator!=(const FrameTpl<S2, O2> &other) const
Returns:

true if *this is NOT equal to other.

template<typename NewScalar>
inline FrameTpl<NewScalar, Options> cast() const
Returns:

An expression of *this with the Scalar type casted to NewScalar.

Public Members

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef FrameTpl< _Scalar, _Options > ModelItemDerived
PINOCCHIO_DEPRECATED JointIndex & parent

Index of the parent joint.

Deprecated:

use parentJoint instead

PINOCCHIO_DEPRECATED FrameIndex & previousFrame

Index of the previous frame.

Deprecated:

use parentFrame instead

FrameType type

Type of the frame.

Inertia inertia

Inertia information attached to the frame. This inertia will be appended to the inertia supported by the parent joint when calling ModelTpl::addFrame. It won’t be processed otherwise by the algorithms.

std::string name

Name of the kinematic element.

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.

JointIndex parentJoint

Index of the parent joint.

SE3 placement

Position of kinematic element in parent joint frame.