A Plucker coordinate frame attached to a parent joint inside a kinematic tree. More...
#include <frame.hpp>
Public Types | |
enum | { Options = traits<ModelItemDerived>::Options } |
typedef ModelItem< ModelItemDerived > | Base |
typedef InertiaTpl< Scalar, Options > | Inertia |
typedef pinocchio::JointIndex | JointIndex |
typedef traits< ModelItemDerived >::Scalar | Scalar |
typedef SE3Tpl< Scalar, Options > | SE3 |
Public Types inherited from pinocchio::ModelItem< FrameTpl< _Scalar, _Options > > | |
enum | |
typedef SE3Tpl< Scalar, Options > | SE3 |
Public Types inherited from pinocchio::NumericalBase< FrameTpl< _Scalar, _Options > > | |
typedef traits< FrameTpl< _Scalar, _Options > >::Scalar | Scalar |
Public Member Functions | |
template<typename NewScalar > | |
FrameTpl< NewScalar, Options > | cast () const |
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS | FrameTpl () |
Default constructor of a frame. More... | |
PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS | FrameTpl (const FrameTpl &other) |
Copy constructor. More... | |
template<typename S2 , int O2> | |
PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS | FrameTpl (const FrameTpl< S2, O2 > &other) |
Copy constructor by casting. More... | |
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. More... | |
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. More... | |
template<typename S2 , int O2> | |
bool | operator!= (const FrameTpl< S2, O2 > &other) const |
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. More... | |
template<typename S2 , int O2> | |
bool | operator== (const FrameTpl< S2, O2 > &other) const |
Equality comparison operator. More... | |
Public Member Functions inherited from pinocchio::ModelItem< FrameTpl< _Scalar, _Options > > | |
ModelItem () | |
Default constructor of ModelItem. More... | |
ModelItem (const std::string &name, const JointIndex parent_joint, const FrameIndex parent_frame, const SE3 &frame_placement) | |
Builds a kinematic element defined by its name, its joint parent id, its parent frame id and its placement. More... | |
bool | operator== (const ModelItem &other) const |
Public Attributes | |
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. More... | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef FrameTpl< _Scalar, _Options > | ModelItemDerived |
std::string | name |
Name of the kinematic element. More... | |
PINOCCHIO_DEPRECATED JointIndex & | parent |
Index of the parent joint. More... | |
FrameIndex | parentFrame |
Index of the parent frame. More... | |
JointIndex | parentJoint |
Index of the parent joint. More... | |
SE3 | placement |
Position of kinematic element in parent joint frame. More... | |
PINOCCHIO_DEPRECATED FrameIndex & | previousFrame |
Index of the previous frame. More... | |
FrameType | type |
Type of the frame. More... | |
Public Attributes inherited from pinocchio::ModelItem< FrameTpl< _Scalar, _Options > > | |
std::string | name |
Name of the kinematic element. More... | |
FrameIndex | parentFrame |
Index of the parent frame. More... | |
JointIndex | parentJoint |
Index of the parent joint. More... | |
SE3 | placement |
Position of kinematic element in parent joint frame. More... | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef traits< FrameTpl< _Scalar, _Options > >::Scalar | Scalar |
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Definition at line 55 of file multibody/frame.hpp.
typedef ModelItem<ModelItemDerived> pinocchio::FrameTpl< _Scalar, _Options >::Base |
Definition at line 64 of file multibody/frame.hpp.
typedef InertiaTpl<Scalar, Options> pinocchio::FrameTpl< _Scalar, _Options >::Inertia |
Definition at line 67 of file multibody/frame.hpp.
typedef pinocchio::JointIndex pinocchio::FrameTpl< _Scalar, _Options >::JointIndex |
Definition at line 68 of file multibody/frame.hpp.
typedef traits<ModelItemDerived>::Scalar pinocchio::FrameTpl< _Scalar, _Options >::Scalar |
Definition at line 59 of file multibody/frame.hpp.
typedef SE3Tpl<Scalar, Options> pinocchio::FrameTpl< _Scalar, _Options >::SE3 |
Definition at line 66 of file multibody/frame.hpp.
anonymous enum |
Enumerator | |
---|---|
Options |
Definition at line 60 of file multibody/frame.hpp.
|
inline |
Default constructor of a frame.
Definition at line 75 of file multibody/frame.hpp.
|
inline |
Builds a frame defined by its name, its joint parent id, its placement and its type.
[in] | name | Name of the frame. |
[in] | parent | Index of the parent joint in the kinematic tree. |
[in] | frame_placement | Placement of the frame wrt the parent joint frame. |
[in] | type | The type of the frame, see the enum FrameType. |
[in] | inertia | Inertia info attached to the frame. |
Definition at line 96 of file multibody/frame.hpp.
|
inline |
Builds a frame defined by its name, its joint parent id, its placement and its type.
[in] | name | Name of the frame. |
[in] | parent | Index of the parent joint in the kinematic tree. |
[in] | parentFrame | Index of the parent frame in the kinematic tree. |
[in] | frame_placement | Placement of the frame wrt the parent joint frame. |
[in] | type | The type of the frame, see the enum FrameType. |
[in] | inertia | Inertia info attached to the frame. |
Definition at line 123 of file multibody/frame.hpp.
|
inline |
Copy constructor.
[in] | other | Frame to copy |
Definition at line 146 of file multibody/frame.hpp.
|
inlineexplicit |
Copy constructor by casting.
[in] | other | Frame to copy |
Definition at line 164 of file multibody/frame.hpp.
|
inline |
Definition at line 219 of file multibody/frame.hpp.
|
inline |
Definition at line 212 of file multibody/frame.hpp.
|
inline |
Copy assignment operator. It needs to be user-define because references cannot be re-assigned during copy.
[in] | other | Frame to copy |
Definition at line 182 of file multibody/frame.hpp.
|
inline |
Equality comparison operator.
[in] | other | The frame to which the current frame is compared. |
Definition at line 201 of file multibody/frame.hpp.
Inertia pinocchio::FrameTpl< _Scalar, _Options >::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.
Definition at line 248 of file multibody/frame.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef FrameTpl<_Scalar, _Options> pinocchio::FrameTpl< _Scalar, _Options >::ModelItemDerived |
Definition at line 58 of file multibody/frame.hpp.
std::string pinocchio::ModelItem< Derived >::name |
Name of the kinematic element.
Definition at line 25 of file model-item.hpp.
PINOCCHIO_DEPRECATED JointIndex& pinocchio::FrameTpl< _Scalar, _Options >::parent |
Index of the parent joint.
Definition at line 231 of file multibody/frame.hpp.
FrameIndex pinocchio::ModelItem< Derived >::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 36 of file model-item.hpp.
JointIndex pinocchio::ModelItem< Derived >::parentJoint |
Index of the parent joint.
Definition at line 28 of file model-item.hpp.
SE3 pinocchio::ModelItem< Derived >::placement |
Position of kinematic element in parent joint frame.
Definition at line 39 of file model-item.hpp.
PINOCCHIO_DEPRECATED FrameIndex& pinocchio::FrameTpl< _Scalar, _Options >::previousFrame |
Index of the previous frame.
Definition at line 235 of file multibody/frame.hpp.
FrameType pinocchio::FrameTpl< _Scalar, _Options >::type |
Type of the frame.
Definition at line 243 of file multibody/frame.hpp.