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

#include <joint-prismatic-unaligned.hpp>

Inheritance diagram for pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >:
Inheritance graph
[legend]

Public Member Functions

template<typename OtherScalar >
MotionPrismaticUnalignedTpl __mult__ (const OtherScalar &alpha) const
 
template<typename Derived >
void addTo (MotionDense< Derived > &other) const
 
const Vector3 & axis () const
 
Vector3 & axis ()
 
bool isEqual_impl (const MotionPrismaticUnalignedTpl &other) const
 
const Scalar & linearRate () const
 
Scalar & linearRate ()
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MOTION_TYPEDEF_TPL (MotionPrismaticUnalignedTpl)
 
template<typename M1 , typename M2 >
void motionAction (const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
 
template<typename M1 >
MotionPlain motionAction (const MotionDense< M1 > &v) const
 
 MotionPrismaticUnalignedTpl ()
 
template<typename Vector3Like , typename S2 >
 MotionPrismaticUnalignedTpl (const Eigen::MatrixBase< Vector3Like > &axis, const S2 &v)
 
PlainReturnType plain () const
 
template<typename S2 , int O2, typename D2 >
void se3Action_impl (const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
 
template<typename S2 , int O2>
MotionPlain se3Action_impl (const SE3Tpl< S2, O2 > &m) const
 
template<typename S2 , int O2, typename D2 >
void se3ActionInverse_impl (const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
 
template<typename S2 , int O2>
MotionPlain se3ActionInverse_impl (const SE3Tpl< S2, O2 > &m) const
 
template<typename Derived >
void setTo (MotionDense< Derived > &other) const
 
- Public Member Functions inherited from pinocchio::MotionBase< MotionPrismaticUnalignedTpl< _Scalar, _Options > >
ConstAngularType angular () const
 
AngularType angular ()
 
void angular (const Eigen::MatrixBase< V3Like > &w)
 
MotionAlgebraAction< OtherSpatialType, MotionPrismaticUnalignedTpl< _Scalar, _Options > >::ReturnType cross (const OtherSpatialType &d) const
 
MotionPrismaticUnalignedTpl< _Scalar, _Options > & derived ()
 
const MotionPrismaticUnalignedTpl< _Scalar, _Options > & derived () const
 
void disp (std::ostream &os) const
 
Scalar dot (const ForceDense< ForceDerived > &f) const
 
bool isApprox (const MotionPrismaticUnalignedTpl< _Scalar, _Options > &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
bool isZero (const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
ConstLinearType linear () const
 
LinearType linear ()
 
void linear (const Eigen::MatrixBase< V3Like > &v)
 
 MOTION_TYPEDEF_TPL (MotionPrismaticUnalignedTpl< _Scalar, _Options >)
 
 operator Matrix6 () const
 
 operator PlainReturnType () const
 
 operator Vector6 () const
 
bool operator!= (const MotionBase< M2 > &other) const
 
internal::RHSScalarMultiplication< MotionPrismaticUnalignedTpl< _Scalar, _Options >, OtherScalar >::ReturnType operator* (const OtherScalar &alpha) const
 
MotionPrismaticUnalignedTpl< _Scalar, _Options > operator+ (const MotionBase< MotionPrismaticUnalignedTpl< _Scalar, _Options > > &v) const
 
MotionPrismaticUnalignedTpl< _Scalar, _Options > & operator+= (const MotionBase< MotionPrismaticUnalignedTpl< _Scalar, _Options > > &v)
 
MotionPrismaticUnalignedTpl< _Scalar, _Options > operator- () const
 
MotionPrismaticUnalignedTpl< _Scalar, _Options > operator- (const MotionBase< MotionPrismaticUnalignedTpl< _Scalar, _Options > > &v) const
 
MotionPrismaticUnalignedTpl< _Scalar, _Options > & operator-= (const MotionBase< MotionPrismaticUnalignedTpl< _Scalar, _Options > > &v)
 
MotionPrismaticUnalignedTpl< _Scalar, _Options > operator/ (const OtherScalar &alpha) const
 
bool operator== (const MotionBase< M2 > &other) const
 
PlainReturnType plain () const
 
SE3GroupAction< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::ReturnType se3Action (const SE3Tpl< S2, O2 > &m) const
 
SE3GroupAction< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::ReturnType se3ActionInverse (const SE3Tpl< S2, O2 > &m) const
 
void setZero ()
 
ActionMatrixType toActionMatrix () const
 
ActionMatrixType toDualActionMatrix () const
 
ToVectorConstReturnType toVector () const
 
ToVectorReturnType toVector ()
 

Protected Attributes

Vector3 m_axis
 
Scalar m_v
 

Detailed Description

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

Definition at line 19 of file joint-prismatic-unaligned.hpp.

Constructor & Destructor Documentation

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

Definition at line 64 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
template<typename Vector3Like , typename S2 >
pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::MotionPrismaticUnalignedTpl ( const Eigen::MatrixBase< Vector3Like > &  axis,
const S2 &  v 
)
inline

Definition at line 67 of file joint-prismatic-unaligned.hpp.

Member Function Documentation

template<typename _Scalar, int _Options>
template<typename OtherScalar >
MotionPrismaticUnalignedTpl pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::__mult__ ( const OtherScalar &  alpha) const
inline

Definition at line 79 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
template<typename Derived >
void pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::addTo ( MotionDense< Derived > &  other) const
inline

Definition at line 85 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
const Vector3& pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::axis ( ) const
inline

Definition at line 157 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
Vector3& pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::axis ( )
inline

Definition at line 158 of file joint-prismatic-unaligned.hpp.

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

Definition at line 149 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
const Scalar& pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::linearRate ( ) const
inline

Definition at line 154 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
Scalar& pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::linearRate ( )
inline

Definition at line 155 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::MOTION_TYPEDEF_TPL ( MotionPrismaticUnalignedTpl< _Scalar, _Options >  )
template<typename _Scalar, int _Options>
template<typename M1 , typename M2 >
void pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::motionAction ( const MotionDense< M1 > &  v,
MotionDense< M2 > &  mout 
) const
inline

Definition at line 131 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
template<typename M1 >
MotionPlain pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::motionAction ( const MotionDense< M1 > &  v) const
inline

Definition at line 142 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
PlainReturnType pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::plain ( ) const
inline

Definition at line 72 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
template<typename S2 , int O2, typename D2 >
void pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::se3Action_impl ( const SE3Tpl< S2, O2 > &  m,
MotionDense< D2 > &  v 
) const
inline

Definition at line 98 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
template<typename S2 , int O2>
MotionPlain pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::se3Action_impl ( const SE3Tpl< S2, O2 > &  m) const
inline

Definition at line 105 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
template<typename S2 , int O2, typename D2 >
void pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::se3ActionInverse_impl ( const SE3Tpl< S2, O2 > &  m,
MotionDense< D2 > &  v 
) const
inline

Definition at line 113 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
template<typename S2 , int O2>
MotionPlain pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::se3ActionInverse_impl ( const SE3Tpl< S2, O2 > &  m) const
inline

Definition at line 123 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
template<typename Derived >
void pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::setTo ( MotionDense< Derived > &  other) const
inline

Definition at line 91 of file joint-prismatic-unaligned.hpp.

Member Data Documentation

template<typename _Scalar, int _Options>
Vector3 pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::m_axis
protected

Definition at line 162 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
Scalar pinocchio::MotionPrismaticUnalignedTpl< _Scalar, _Options >::m_v
protected

Definition at line 163 of file joint-prismatic-unaligned.hpp.


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


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