Public Types | Public Member Functions | Public Attributes | List of all members
pinocchio::FrameTpl< _Scalar, _Options > Struct Template Reference

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

#include <frame.hpp>

Public Types

enum  { Options = _Options }
 
typedef InertiaTpl< Scalar, OptionsInertia
 
typedef _Scalar Scalar
 
typedef SE3Tpl< Scalar, OptionsSE3
 

Public Member Functions

template<typename NewScalar >
FrameTpl< NewScalar, Optionscast () const
 
 FrameTpl ()
 Default constructor of a frame. More...
 
 FrameTpl (const std::string &name, const JointIndex parent, const FrameIndex previousFrame, 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
 
template<typename S2 , int O2>
bool operator== (const FrameTpl< S2, O2 > &other) const
 Equality comparison operator. More...
 

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 pinocchio::JointIndex JointIndex
 
std::string name
 Name of the frame. More...
 
JointIndex parent
 Index of the parent joint. More...
 
SE3 placement
 Placement of the frame wrt the parent joint. More...
 
FrameIndex previousFrame
 Index of the previous frame. More...
 
FrameType type
 Type of the frame. More...
 

Detailed Description

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

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

Definition at line 32 of file src/multibody/frame.hpp.

Member Typedef Documentation

template<typename _Scalar, int _Options>
typedef InertiaTpl<Scalar,Options> pinocchio::FrameTpl< _Scalar, _Options >::Inertia

Definition at line 39 of file src/multibody/frame.hpp.

template<typename _Scalar, int _Options>
typedef _Scalar pinocchio::FrameTpl< _Scalar, _Options >::Scalar

Definition at line 37 of file src/multibody/frame.hpp.

template<typename _Scalar, int _Options>
typedef SE3Tpl<Scalar,Options> pinocchio::FrameTpl< _Scalar, _Options >::SE3

Definition at line 38 of file src/multibody/frame.hpp.

Member Enumeration Documentation

template<typename _Scalar, int _Options>
anonymous enum
Enumerator
Options 

Definition at line 36 of file src/multibody/frame.hpp.

Constructor & Destructor Documentation

template<typename _Scalar, int _Options>
pinocchio::FrameTpl< _Scalar, _Options >::FrameTpl ( )
inline

Default constructor of a frame.

Definition at line 44 of file src/multibody/frame.hpp.

template<typename _Scalar, int _Options>
pinocchio::FrameTpl< _Scalar, _Options >::FrameTpl ( const std::string &  name,
const JointIndex  parent,
const FrameIndex  previousFrame,
const SE3 frame_placement,
const FrameType  type,
const Inertia inertia = Inertia::Zero() 
)
inline

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

Parameters
[in]nameName of the frame.
[in]parentIndex of the parent joint in the kinematic tree.
[in]previousFrameIndex of the parent frame in the kinematic tree.
[in]frame_placementPlacement of the frame wrt the parent joint frame.
[in]typeThe type of the frame, see the enum FrameType.
[in]inertiaInertia info attached to the frame.

Definition at line 62 of file src/multibody/frame.hpp.

Member Function Documentation

template<typename _Scalar, int _Options>
template<typename NewScalar >
FrameTpl<NewScalar,Options> pinocchio::FrameTpl< _Scalar, _Options >::cast ( ) const
inline
Returns
An expression of *this with the Scalar type casted to NewScalar.

Definition at line 105 of file src/multibody/frame.hpp.

template<typename _Scalar, int _Options>
template<typename S2 , int O2>
bool pinocchio::FrameTpl< _Scalar, _Options >::operator!= ( const FrameTpl< S2, O2 > &  other) const
inline
Returns
true if *this is NOT equal to other.

Definition at line 98 of file src/multibody/frame.hpp.

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

Equality comparison operator.

Returns
true if *this is equal to other.
Parameters
[in]otherThe frame to which the current frame is compared.

Definition at line 84 of file src/multibody/frame.hpp.

Member Data Documentation

template<typename _Scalar, int _Options>
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 137 of file src/multibody/frame.hpp.

template<typename _Scalar, int _Options>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef pinocchio::JointIndex pinocchio::FrameTpl< _Scalar, _Options >::JointIndex

Definition at line 35 of file src/multibody/frame.hpp.

template<typename _Scalar, int _Options>
std::string pinocchio::FrameTpl< _Scalar, _Options >::name

Name of the frame.

Definition at line 120 of file src/multibody/frame.hpp.

template<typename _Scalar, int _Options>
JointIndex pinocchio::FrameTpl< _Scalar, _Options >::parent

Index of the parent joint.

Definition at line 123 of file src/multibody/frame.hpp.

template<typename _Scalar, int _Options>
SE3 pinocchio::FrameTpl< _Scalar, _Options >::placement

Placement of the frame wrt the parent joint.

Definition at line 129 of file src/multibody/frame.hpp.

template<typename _Scalar, int _Options>
FrameIndex pinocchio::FrameTpl< _Scalar, _Options >::previousFrame

Index of the previous frame.

Definition at line 126 of file src/multibody/frame.hpp.

template<typename _Scalar, int _Options>
FrameType pinocchio::FrameTpl< _Scalar, _Options >::type

Type of the frame.

Definition at line 132 of file src/multibody/frame.hpp.


The documentation for this struct was generated from the following file:


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:05