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

#include <casadi.hpp>

Public Types

typedef SE3Base< SE3Tpl< _Scalar, _Options > > Base
 
typedef traits< SE3Tpl >::Matrix3 Matrix3
 
typedef traits< SE3Tpl >::Matrix4 Matrix4
 
typedef traits< SE3Tpl >::Matrix6 Matrix6
 
typedef Eigen::Quaternion< Scalar, OptionsQuaternion
 
typedef traits< SE3Tpl >::Vector3 Vector3
 
typedef traits< SE3Tpl >::Vector4 Vector4
 

Public Member Functions

template<int O2>
SE3Tpl __mult__ (const SE3Tpl< Scalar, O2 > &m2) const
 
template<typename D >
SE3GroupAction< D >::ReturnType act_impl (const D &d) const
 — GROUP ACTIONS ON M6, F6 and I6 — More...
 
template<int O2>
SE3Tpl act_impl (const SE3Tpl< Scalar, O2 > &m2) const
 
Vector3 act_impl (const Vector3 &p) const
 
template<typename D >
SE3GroupAction< D >::ReturnType actInv_impl (const D &d) const
 by = aXb.actInv(ay) More...
 
template<int O2>
SE3Tpl actInv_impl (const SE3Tpl< Scalar, O2 > &m2) const
 
Vector3 actInv_impl (const Vector3 &p) const
 
template<typename MapDerived >
Vector3 actInvOnEigenObject (const Eigen::MapBase< MapDerived > &p) const
 
template<typename EigenDerived >
EigenDerived::PlainObject actInvOnEigenObject (const Eigen::MatrixBase< EigenDerived > &p) const
 
template<typename MapDerived >
Vector3 actOnEigenObject (const Eigen::MapBase< MapDerived > &p) const
 
template<typename EigenDerived >
EigenDerived::PlainObject actOnEigenObject (const Eigen::MatrixBase< EigenDerived > &p) const
 
template<typename NewScalar >
SE3Tpl< NewScalar, Optionscast () const
 
void disp_impl (std::ostream &os) const
 
template<typename OtherScalar >
SE3Tpl< Scalar, OptionsInterpolate (const SE3Tpl &A, const SE3Tpl &B, const OtherScalar &alpha)
 
SE3Tpl inverse () const
 aXb = bXa.inverse() More...
 
template<int O2>
bool isApprox_impl (const SE3Tpl< Scalar, O2 > &m2, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
template<int O2>
bool isEqual (const SE3Tpl< Scalar, O2 > &m2) const
 
bool isIdentity (const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
bool isNormalized (const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
void normalize ()
 
PlainType normalized () const
 
SE3Tploperator= (const SE3Tpl &other)
 Copy assignment operator. More...
 
template<int O2>
SE3Tploperator= (const SE3Tpl< Scalar, O2 > &other)
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PINOCCHIO_SE3_TYPEDEF_TPL (SE3Tpl)
 
AngularRef rotation ()
 
ConstAngularRef rotation () const
 
void rotation (const AngularType &R)
 
AngularRef rotation_impl ()
 
ConstAngularRef rotation_impl () const
 
void rotation_impl (const AngularType &R)
 
 SE3Tpl ()
 
template<typename Matrix3Like , typename Vector3Like >
 SE3Tpl (const Eigen::MatrixBase< Matrix3Like > &R, const Eigen::MatrixBase< Vector3Like > &trans)
 
template<typename Matrix4Like >
 SE3Tpl (const Eigen::MatrixBase< Matrix4Like > &m)
 
template<typename QuaternionLike , typename Vector3Like >
 SE3Tpl (const Eigen::QuaternionBase< QuaternionLike > &quat, const Eigen::MatrixBase< Vector3Like > &trans)
 
 SE3Tpl (const SE3Tpl &other)
 
template<typename S2 , int O2>
 SE3Tpl (const SE3Tpl< S2, O2 > &other)
 
template<int O2>
 SE3Tpl (const SE3Tpl< Scalar, O2 > &clone)
 
 SE3Tpl (int)
 
SE3TplsetIdentity ()
 
SE3TplsetRandom ()
 
ActionMatrixType toActionMatrix_impl () const
 
template<typename Matrix6Like >
void toActionMatrix_impl (const Eigen::MatrixBase< Matrix6Like > &action_matrix) const
 Vb.toVector() = bXa.toMatrix() * Va.toVector() More...
 
ActionMatrixType toActionMatrixInverse_impl () const
 
template<typename Matrix6Like >
void toActionMatrixInverse_impl (const Eigen::MatrixBase< Matrix6Like > &action_matrix_inverse) const
 
ActionMatrixType toDualActionMatrix_impl () const
 
template<typename Matrix6Like >
void toDualActionMatrix_impl (const Eigen::MatrixBase< Matrix6Like > &dual_action_matrix) const
 
HomogeneousMatrixType toHomogeneousMatrix_impl () const
 
LinearRef translation ()
 
ConstLinearRef translation () const
 
void translation (const LinearType &t)
 
LinearRef translation_impl ()
 
ConstLinearRef translation_impl () const
 
void translation_impl (const LinearType &p)
 

Static Public Member Functions

static SE3Tpl Identity ()
 
template<typename OtherScalar >
static SE3Tpl Interpolate (const SE3Tpl &A, const SE3Tpl &B, const OtherScalar &alpha)
 Linear interpolation on the SE3 manifold. More...
 
static SE3Tpl Random ()
 

Protected Attributes

AngularType rot
 
LinearType trans
 

Detailed Description

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

Definition at line 29 of file context/casadi.hpp.

Member Typedef Documentation

◆ Base

template<typename _Scalar , int _Options>
typedef SE3Base<SE3Tpl<_Scalar, _Options> > pinocchio::SE3Tpl< _Scalar, _Options >::Base

Definition at line 53 of file spatial/se3-tpl.hpp.

◆ Matrix3

template<typename _Scalar , int _Options>
typedef traits<SE3Tpl>::Matrix3 pinocchio::SE3Tpl< _Scalar, _Options >::Matrix3

Definition at line 56 of file spatial/se3-tpl.hpp.

◆ Matrix4

template<typename _Scalar , int _Options>
typedef traits<SE3Tpl>::Matrix4 pinocchio::SE3Tpl< _Scalar, _Options >::Matrix4

Definition at line 57 of file spatial/se3-tpl.hpp.

◆ Matrix6

template<typename _Scalar , int _Options>
typedef traits<SE3Tpl>::Matrix6 pinocchio::SE3Tpl< _Scalar, _Options >::Matrix6

Definition at line 59 of file spatial/se3-tpl.hpp.

◆ Quaternion

template<typename _Scalar , int _Options>
typedef Eigen::Quaternion<Scalar, Options> pinocchio::SE3Tpl< _Scalar, _Options >::Quaternion

Definition at line 54 of file spatial/se3-tpl.hpp.

◆ Vector3

template<typename _Scalar , int _Options>
typedef traits<SE3Tpl>::Vector3 pinocchio::SE3Tpl< _Scalar, _Options >::Vector3

Definition at line 55 of file spatial/se3-tpl.hpp.

◆ Vector4

template<typename _Scalar , int _Options>
typedef traits<SE3Tpl>::Vector4 pinocchio::SE3Tpl< _Scalar, _Options >::Vector4

Definition at line 58 of file spatial/se3-tpl.hpp.

Constructor & Destructor Documentation

◆ SE3Tpl() [1/8]

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

Definition at line 64 of file spatial/se3-tpl.hpp.

◆ SE3Tpl() [2/8]

template<typename _Scalar , int _Options>
template<typename QuaternionLike , typename Vector3Like >
pinocchio::SE3Tpl< _Scalar, _Options >::SE3Tpl ( const Eigen::QuaternionBase< QuaternionLike > &  quat,
const Eigen::MatrixBase< Vector3Like > &  trans 
)
inline

Definition at line 69 of file spatial/se3-tpl.hpp.

◆ SE3Tpl() [3/8]

template<typename _Scalar , int _Options>
template<typename Matrix3Like , typename Vector3Like >
pinocchio::SE3Tpl< _Scalar, _Options >::SE3Tpl ( const Eigen::MatrixBase< Matrix3Like > &  R,
const Eigen::MatrixBase< Vector3Like > &  trans 
)
inline

Definition at line 79 of file spatial/se3-tpl.hpp.

◆ SE3Tpl() [4/8]

template<typename _Scalar , int _Options>
pinocchio::SE3Tpl< _Scalar, _Options >::SE3Tpl ( const SE3Tpl< _Scalar, _Options > &  other)
inline

Definition at line 84 of file spatial/se3-tpl.hpp.

◆ SE3Tpl() [5/8]

template<typename _Scalar , int _Options>
template<typename S2 , int O2>
pinocchio::SE3Tpl< _Scalar, _Options >::SE3Tpl ( const SE3Tpl< S2, O2 > &  other)
inlineexplicit

Definition at line 90 of file spatial/se3-tpl.hpp.

◆ SE3Tpl() [6/8]

template<typename _Scalar , int _Options>
template<typename Matrix4Like >
pinocchio::SE3Tpl< _Scalar, _Options >::SE3Tpl ( const Eigen::MatrixBase< Matrix4Like > &  m)
inlineexplicit

Definition at line 96 of file spatial/se3-tpl.hpp.

◆ SE3Tpl() [7/8]

template<typename _Scalar , int _Options>
pinocchio::SE3Tpl< _Scalar, _Options >::SE3Tpl ( int  )
inlineexplicit

Definition at line 103 of file spatial/se3-tpl.hpp.

◆ SE3Tpl() [8/8]

template<typename _Scalar , int _Options>
template<int O2>
pinocchio::SE3Tpl< _Scalar, _Options >::SE3Tpl ( const SE3Tpl< Scalar, O2 > &  clone)
inline

Definition at line 110 of file spatial/se3-tpl.hpp.

Member Function Documentation

◆ __mult__()

template<typename _Scalar , int _Options>
template<int O2>
SE3Tpl pinocchio::SE3Tpl< _Scalar, _Options >::__mult__ ( const SE3Tpl< Scalar, O2 > &  m2) const
inline

Definition at line 327 of file spatial/se3-tpl.hpp.

◆ act_impl() [1/3]

template<typename _Scalar , int _Options>
template<typename D >
SE3GroupAction<D>::ReturnType pinocchio::SE3Tpl< _Scalar, _Options >::act_impl ( const D d) const
inline

— GROUP ACTIONS ON M6, F6 and I6 —

ay = aXb.act(by)

Definition at line 265 of file spatial/se3-tpl.hpp.

◆ act_impl() [2/3]

template<typename _Scalar , int _Options>
template<int O2>
SE3Tpl pinocchio::SE3Tpl< _Scalar, _Options >::act_impl ( const SE3Tpl< Scalar, O2 > &  m2) const
inline

Definition at line 314 of file spatial/se3-tpl.hpp.

◆ act_impl() [3/3]

template<typename _Scalar , int _Options>
Vector3 pinocchio::SE3Tpl< _Scalar, _Options >::act_impl ( const Vector3 p) const
inline

Definition at line 303 of file spatial/se3-tpl.hpp.

◆ actInv_impl() [1/3]

template<typename _Scalar , int _Options>
template<typename D >
SE3GroupAction<D>::ReturnType pinocchio::SE3Tpl< _Scalar, _Options >::actInv_impl ( const D d) const
inline

by = aXb.actInv(ay)

Definition at line 272 of file spatial/se3-tpl.hpp.

◆ actInv_impl() [2/3]

template<typename _Scalar , int _Options>
template<int O2>
SE3Tpl pinocchio::SE3Tpl< _Scalar, _Options >::actInv_impl ( const SE3Tpl< Scalar, O2 > &  m2) const
inline

Definition at line 320 of file spatial/se3-tpl.hpp.

◆ actInv_impl() [3/3]

template<typename _Scalar , int _Options>
Vector3 pinocchio::SE3Tpl< _Scalar, _Options >::actInv_impl ( const Vector3 p) const
inline

Definition at line 308 of file spatial/se3-tpl.hpp.

◆ actInvOnEigenObject() [1/2]

template<typename _Scalar , int _Options>
template<typename MapDerived >
Vector3 pinocchio::SE3Tpl< _Scalar, _Options >::actInvOnEigenObject ( const Eigen::MapBase< MapDerived > &  p) const
inline

Definition at line 298 of file spatial/se3-tpl.hpp.

◆ actInvOnEigenObject() [2/2]

template<typename _Scalar , int _Options>
template<typename EigenDerived >
EigenDerived::PlainObject pinocchio::SE3Tpl< _Scalar, _Options >::actInvOnEigenObject ( const Eigen::MatrixBase< EigenDerived > &  p) const
inline

Definition at line 292 of file spatial/se3-tpl.hpp.

◆ actOnEigenObject() [1/2]

template<typename _Scalar , int _Options>
template<typename MapDerived >
Vector3 pinocchio::SE3Tpl< _Scalar, _Options >::actOnEigenObject ( const Eigen::MapBase< MapDerived > &  p) const
inline

Definition at line 285 of file spatial/se3-tpl.hpp.

◆ actOnEigenObject() [2/2]

template<typename _Scalar , int _Options>
template<typename EigenDerived >
EigenDerived::PlainObject pinocchio::SE3Tpl< _Scalar, _Options >::actOnEigenObject ( const Eigen::MatrixBase< EigenDerived > &  p) const
inline

Definition at line 279 of file spatial/se3-tpl.hpp.

◆ cast()

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

Definition at line 379 of file spatial/se3-tpl.hpp.

◆ disp_impl()

template<typename _Scalar , int _Options>
void pinocchio::SE3Tpl< _Scalar, _Options >::disp_impl ( std::ostream &  os) const
inline

Definition at line 256 of file spatial/se3-tpl.hpp.

◆ Identity()

template<typename _Scalar , int _Options>
static SE3Tpl pinocchio::SE3Tpl< _Scalar, _Options >::Identity ( )
inlinestatic

Definition at line 136 of file spatial/se3-tpl.hpp.

◆ Interpolate() [1/2]

template<typename _Scalar , int _Options>
template<typename OtherScalar >
static SE3Tpl pinocchio::SE3Tpl< _Scalar, _Options >::Interpolate ( const SE3Tpl< _Scalar, _Options > &  A,
const SE3Tpl< _Scalar, _Options > &  B,
const OtherScalar &  alpha 
)
static

Linear interpolation on the SE3 manifold.

Parameters
[in]AInitial transformation.
[in]BTarget transformation.
[in]alphaInterpolation factor in [0 ... 1].
Returns
An interpolated transformation between A and B.
Note
This is similar to the SLERP operation which acts initially for rotation but applied here to rigid transformation.

◆ Interpolate() [2/2]

template<typename _Scalar , int _Options>
template<typename OtherScalar >
SE3Tpl<Scalar, Options> pinocchio::SE3Tpl< _Scalar, _Options >::Interpolate ( const SE3Tpl< _Scalar, _Options > &  A,
const SE3Tpl< _Scalar, _Options > &  B,
const OtherScalar &  alpha 
)

Definition at line 690 of file spatial/explog.hpp.

◆ inverse()

template<typename _Scalar , int _Options>
SE3Tpl pinocchio::SE3Tpl< _Scalar, _Options >::inverse ( ) const
inline

aXb = bXa.inverse()

Definition at line 149 of file spatial/se3-tpl.hpp.

◆ isApprox_impl()

template<typename _Scalar , int _Options>
template<int O2>
bool pinocchio::SE3Tpl< _Scalar, _Options >::isApprox_impl ( const SE3Tpl< Scalar, O2 > &  m2,
const Scalar &  prec = Eigen::NumTraits<Scalar>::dummy_precision() 
) const
inline

Definition at line 339 of file spatial/se3-tpl.hpp.

◆ isEqual()

template<typename _Scalar , int _Options>
template<int O2>
bool pinocchio::SE3Tpl< _Scalar, _Options >::isEqual ( const SE3Tpl< Scalar, O2 > &  m2) const
inline

Definition at line 333 of file spatial/se3-tpl.hpp.

◆ isIdentity()

template<typename _Scalar , int _Options>
bool pinocchio::SE3Tpl< _Scalar, _Options >::isIdentity ( const Scalar &  prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
inline

Definition at line 347 of file spatial/se3-tpl.hpp.

◆ isNormalized()

template<typename _Scalar , int _Options>
bool pinocchio::SE3Tpl< _Scalar, _Options >::isNormalized ( const Scalar &  prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
inline

Definition at line 390 of file spatial/se3-tpl.hpp.

◆ normalize()

template<typename _Scalar , int _Options>
void pinocchio::SE3Tpl< _Scalar, _Options >::normalize ( )
inline

Definition at line 395 of file spatial/se3-tpl.hpp.

◆ normalized()

template<typename _Scalar , int _Options>
PlainType pinocchio::SE3Tpl< _Scalar, _Options >::normalized ( ) const
inline

Definition at line 400 of file spatial/se3-tpl.hpp.

◆ operator=() [1/2]

template<typename _Scalar , int _Options>
SE3Tpl& pinocchio::SE3Tpl< _Scalar, _Options >::operator= ( const SE3Tpl< _Scalar, _Options > &  other)
inline

Copy assignment operator.

Parameters
[in]otherSE3 to copy

Definition at line 129 of file spatial/se3-tpl.hpp.

◆ operator=() [2/2]

template<typename _Scalar , int _Options>
template<int O2>
SE3Tpl& pinocchio::SE3Tpl< _Scalar, _Options >::operator= ( const SE3Tpl< Scalar, O2 > &  other)
inline

Definition at line 117 of file spatial/se3-tpl.hpp.

◆ PINOCCHIO_SE3_TYPEDEF_TPL()

template<typename _Scalar , int _Options>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW pinocchio::SE3Tpl< _Scalar, _Options >::PINOCCHIO_SE3_TYPEDEF_TPL ( SE3Tpl< _Scalar, _Options >  )

◆ Random()

template<typename _Scalar , int _Options>
static SE3Tpl pinocchio::SE3Tpl< _Scalar, _Options >::Random ( )
inlinestatic

Definition at line 154 of file spatial/se3-tpl.hpp.

◆ rotation() [1/3]

template<typename _Scalar , int _Options>
AngularRef pinocchio::SE3Base< Derived >::rotation
inline

Definition at line 56 of file se3-base.hpp.

◆ rotation() [2/3]

template<typename _Scalar , int _Options>
ConstAngularRef pinocchio::SE3Base< Derived >::rotation
inline

Definition at line 48 of file se3-base.hpp.

◆ rotation() [3/3]

template<typename _Scalar , int _Options>
void pinocchio::SE3Base< Derived >::rotation
inline

Definition at line 64 of file se3-base.hpp.

◆ rotation_impl() [1/3]

template<typename _Scalar , int _Options>
AngularRef pinocchio::SE3Tpl< _Scalar, _Options >::rotation_impl ( )
inline

Definition at line 356 of file spatial/se3-tpl.hpp.

◆ rotation_impl() [2/3]

template<typename _Scalar , int _Options>
ConstAngularRef pinocchio::SE3Tpl< _Scalar, _Options >::rotation_impl ( ) const
inline

Definition at line 352 of file spatial/se3-tpl.hpp.

◆ rotation_impl() [3/3]

template<typename _Scalar , int _Options>
void pinocchio::SE3Tpl< _Scalar, _Options >::rotation_impl ( const AngularType &  R)
inline

Definition at line 360 of file spatial/se3-tpl.hpp.

◆ setIdentity()

template<typename _Scalar , int _Options>
SE3Tpl& pinocchio::SE3Tpl< _Scalar, _Options >::setIdentity ( )
inline

Definition at line 141 of file spatial/se3-tpl.hpp.

◆ setRandom()

template<typename _Scalar , int _Options>
SE3Tpl& pinocchio::SE3Tpl< _Scalar, _Options >::setRandom ( )
inline

Definition at line 159 of file spatial/se3-tpl.hpp.

◆ toActionMatrix_impl() [1/2]

template<typename _Scalar , int _Options>
ActionMatrixType pinocchio::SE3Tpl< _Scalar, _Options >::toActionMatrix_impl ( ) const
inline

Definition at line 195 of file spatial/se3-tpl.hpp.

◆ toActionMatrix_impl() [2/2]

template<typename _Scalar , int _Options>
template<typename Matrix6Like >
void pinocchio::SE3Tpl< _Scalar, _Options >::toActionMatrix_impl ( const Eigen::MatrixBase< Matrix6Like > &  action_matrix) const
inline

Vb.toVector() = bXa.toMatrix() * Va.toVector()

Definition at line 181 of file spatial/se3-tpl.hpp.

◆ toActionMatrixInverse_impl() [1/2]

template<typename _Scalar , int _Options>
ActionMatrixType pinocchio::SE3Tpl< _Scalar, _Options >::toActionMatrixInverse_impl ( ) const
inline

Definition at line 227 of file spatial/se3-tpl.hpp.

◆ toActionMatrixInverse_impl() [2/2]

template<typename _Scalar , int _Options>
template<typename Matrix6Like >
void pinocchio::SE3Tpl< _Scalar, _Options >::toActionMatrixInverse_impl ( const Eigen::MatrixBase< Matrix6Like > &  action_matrix_inverse) const
inline

Definition at line 204 of file spatial/se3-tpl.hpp.

◆ toDualActionMatrix_impl() [1/2]

template<typename _Scalar , int _Options>
ActionMatrixType pinocchio::SE3Tpl< _Scalar, _Options >::toDualActionMatrix_impl ( ) const
inline

Definition at line 249 of file spatial/se3-tpl.hpp.

◆ toDualActionMatrix_impl() [2/2]

template<typename _Scalar , int _Options>
template<typename Matrix6Like >
void pinocchio::SE3Tpl< _Scalar, _Options >::toDualActionMatrix_impl ( const Eigen::MatrixBase< Matrix6Like > &  dual_action_matrix) const
inline

Definition at line 235 of file spatial/se3-tpl.hpp.

◆ toHomogeneousMatrix_impl()

template<typename _Scalar , int _Options>
HomogeneousMatrixType pinocchio::SE3Tpl< _Scalar, _Options >::toHomogeneousMatrix_impl ( ) const
inline

Definition at line 169 of file spatial/se3-tpl.hpp.

◆ translation() [1/3]

template<typename _Scalar , int _Options>
LinearRef pinocchio::SE3Base< Derived >::translation
inline

Definition at line 60 of file se3-base.hpp.

◆ translation() [2/3]

template<typename _Scalar , int _Options>
ConstLinearRef pinocchio::SE3Base< Derived >::translation
inline

Definition at line 52 of file se3-base.hpp.

◆ translation() [3/3]

template<typename _Scalar , int _Options>
void pinocchio::SE3Base< Derived >::translation
inline

Definition at line 68 of file se3-base.hpp.

◆ translation_impl() [1/3]

template<typename _Scalar , int _Options>
LinearRef pinocchio::SE3Tpl< _Scalar, _Options >::translation_impl ( )
inline

Definition at line 368 of file spatial/se3-tpl.hpp.

◆ translation_impl() [2/3]

template<typename _Scalar , int _Options>
ConstLinearRef pinocchio::SE3Tpl< _Scalar, _Options >::translation_impl ( ) const
inline

Definition at line 364 of file spatial/se3-tpl.hpp.

◆ translation_impl() [3/3]

template<typename _Scalar , int _Options>
void pinocchio::SE3Tpl< _Scalar, _Options >::translation_impl ( const LinearType &  p)
inline

Definition at line 372 of file spatial/se3-tpl.hpp.

Member Data Documentation

◆ rot

template<typename _Scalar , int _Options>
AngularType pinocchio::SE3Tpl< _Scalar, _Options >::rot
protected

Definition at line 423 of file spatial/se3-tpl.hpp.

◆ trans

template<typename _Scalar , int _Options>
LinearType pinocchio::SE3Tpl< _Scalar, _Options >::trans
protected

Definition at line 424 of file spatial/se3-tpl.hpp.


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


pinocchio
Author(s):
autogenerated on Sat Jun 1 2024 02:40:41