Public Member Functions | Friends | List of all members
pinocchio::ForceBase< Derived > Class Template Reference

Base interface for forces representation. More...

#include <force-base.hpp>

Inheritance diagram for pinocchio::ForceBase< Derived >:
Inheritance graph
[legend]

Public Member Functions

ConstAngularType angular () const
 Return the angular part of the force vector. More...
 
AngularType angular ()
 Return the angular part of the force vector. More...
 
template<typename V3Like >
void angular (const Eigen::MatrixBase< V3Like > &n)
 Set the angular part of the force vector. More...
 
Derived & derived ()
 
const Derived & derived () const
 
void disp (std::ostream &os) const
 
template<typename MotionDerived >
Scalar dot (const MotionDense< MotionDerived > &m) const
 
 FORCE_TYPEDEF_TPL (Derived)
 
bool isApprox (const Derived &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
bool isZero (const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
ConstLinearType linear () const
 Return the linear part of the force vector. More...
 
LinearType linear ()
 Return the linear part of the force vector. More...
 
template<typename V3Like >
void linear (const Eigen::MatrixBase< V3Like > &f)
 Set the linear part of the force vector. More...
 
template<typename M1 >
MotionAlgebraAction< Derived, M1 >::ReturnType motionAction (const MotionDense< M1 > &v) const
 
 operator Vector6 () const
 
template<typename F2 >
bool operator!= (const ForceBase< F2 > &other) const
 
template<typename OtherScalar >
ForcePlain operator* (const OtherScalar &alpha) const
 
Derived operator+ (const ForceBase< Derived > &phi) const
 
Derived & operator+= (const ForceBase< Derived > &phi)
 Replaces *this by *this + other. More...
 
Derived operator- () const
 
Derived operator- (const ForceBase< Derived > &phi) const
 
Derived & operator-= (const ForceBase< Derived > &phi)
 Replaces *this by *this - other. More...
 
template<typename OtherScalar >
ForcePlain operator/ (const OtherScalar &alpha) const
 
Derived & operator= (const ForceBase< Derived > &other)
 Copies the Derived Force into *this. More...
 
template<typename F2 >
bool operator== (const ForceBase< F2 > &other) const
 
template<typename S2 , int O2>
SE3GroupAction< Derived >::ReturnType se3Action (const SE3Tpl< S2, O2 > &m) const
 Transform from A to B coordinates the Force represented by *this such that

\begin{equation*} {}^{B}f = {}^{B}X_A^* * {}^{A}f \end{equation*}

. More...

 
template<typename S2 , int O2>
SE3GroupAction< Derived >::ReturnType se3ActionInverse (const SE3Tpl< S2, O2 > &m) const
 Transform from B to A coordinates the Force represented by *this such that

\begin{equation*} {}^{A}f = {}^{A}X_B^* * {}^{A}f \end{equation*}

. More...

 
ToVectorConstReturnType toVector () const
 Return the force as an Eigen vector. More...
 
ToVectorReturnType toVector ()
 Return the force as an Eigen vector. More...
 

Friends

std::ostream & operator<< (std::ostream &os, const ForceBase< Derived > &X)
 

Detailed Description

template<class Derived>
class pinocchio::ForceBase< Derived >

Base interface for forces representation.

The Class implements all

This class hierarchy represents a spatial force, e.g. a spatial impulse or force associated to a body. The spatial force is the mathematical representation of $ se^{*}(3) $, the dual of $ se(3) $.

Template Parameters
Derived{ description }

Definition at line 22 of file force-base.hpp.

Member Function Documentation

template<class Derived>
ConstAngularType pinocchio::ForceBase< Derived >::angular ( ) const
inline

Return the angular part of the force vector.

Returns
The 3D vector associated to the angular part of the 6D force vector

Definition at line 35 of file force-base.hpp.

template<class Derived>
AngularType pinocchio::ForceBase< Derived >::angular ( )
inline

Return the angular part of the force vector.

Returns
The 3D vector associated to the angular part of the 6D force vector

Definition at line 45 of file force-base.hpp.

template<class Derived>
template<typename V3Like >
void pinocchio::ForceBase< Derived >::angular ( const Eigen::MatrixBase< V3Like > &  n)
inline

Set the angular part of the force vector.

Template Parameters
V3LikeA vector 3 like type.
Parameters
[in]n

Definition at line 59 of file force-base.hpp.

template<class Derived>
Derived& pinocchio::ForceBase< Derived >::derived ( )
inline

Definition at line 27 of file force-base.hpp.

template<class Derived>
const Derived& pinocchio::ForceBase< Derived >::derived ( ) const
inline

Definition at line 28 of file force-base.hpp.

template<class Derived>
void pinocchio::ForceBase< Derived >::disp ( std::ostream &  os) const
inline

Definition at line 199 of file force-base.hpp.

template<class Derived>
template<typename MotionDerived >
Scalar pinocchio::ForceBase< Derived >::dot ( const MotionDense< MotionDerived > &  m) const
inline
Returns
the dot product of *this with m *

Definition at line 157 of file force-base.hpp.

template<class Derived>
pinocchio::ForceBase< Derived >::FORCE_TYPEDEF_TPL ( Derived  )
template<class Derived>
bool pinocchio::ForceBase< Derived >::isApprox ( const Derived &  other,
const Scalar &  prec = Eigen::NumTraits<Scalar>::dummy_precision() 
) const
inline
Returns
true if *this is approximately equal to other, within the precision given by prec.

Definition at line 106 of file force-base.hpp.

template<class Derived>
bool pinocchio::ForceBase< Derived >::isZero ( const Scalar &  prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
inline
Returns
true if the component of the linear and angular part of the Spatial Force are approximately equal to zero, within the precision given by prec.

Definition at line 111 of file force-base.hpp.

template<class Derived>
ConstLinearType pinocchio::ForceBase< Derived >::linear ( ) const
inline

Return the linear part of the force vector.

Returns
The 3D vector associated to the linear part of the 6D force vector

Definition at line 42 of file force-base.hpp.

template<class Derived>
LinearType pinocchio::ForceBase< Derived >::linear ( )
inline

Return the linear part of the force vector.

Returns
The 3D vector associated to the linear part of the 6D force vector

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

template<class Derived>
template<typename V3Like >
void pinocchio::ForceBase< Derived >::linear ( const Eigen::MatrixBase< V3Like > &  f)
inline

Set the linear part of the force vector.

Template Parameters
V3LikeA vector 3 like type.
Parameters
[in]f

Definition at line 70 of file force-base.hpp.

template<class Derived>
template<typename M1 >
MotionAlgebraAction<Derived,M1>::ReturnType pinocchio::ForceBase< Derived >::motionAction ( const MotionDense< M1 > &  v) const
inline

Definition at line 194 of file force-base.hpp.

template<class Derived>
pinocchio::ForceBase< Derived >::operator Vector6 ( ) const
inline

Definition at line 90 of file force-base.hpp.

template<class Derived>
template<typename F2 >
bool pinocchio::ForceBase< Derived >::operator!= ( const ForceBase< F2 > &  other) const
inline
Returns
true if at least one coefficient of *this and other does not match.

Definition at line 102 of file force-base.hpp.

template<class Derived>
template<typename OtherScalar >
ForcePlain pinocchio::ForceBase< Derived >::operator* ( const OtherScalar &  alpha) const
inline
Returns
an expression of *this scaled by the factor alpha

Definition at line 139 of file force-base.hpp.

template<class Derived>
Derived pinocchio::ForceBase< Derived >::operator+ ( const ForceBase< Derived > &  phi) const
inline
Returns
an expression of the sum of *this and other

Definition at line 134 of file force-base.hpp.

template<class Derived>
Derived& pinocchio::ForceBase< Derived >::operator+= ( const ForceBase< Derived > &  phi)
inline

Replaces *this by *this + other.

Returns
a reference to *this

Definition at line 124 of file force-base.hpp.

template<class Derived>
Derived pinocchio::ForceBase< Derived >::operator- ( ) const
inline
Returns
an expression of the opposite of *this

Definition at line 148 of file force-base.hpp.

template<class Derived>
Derived pinocchio::ForceBase< Derived >::operator- ( const ForceBase< Derived > &  phi) const
inline
Returns
an expression of the difference of *this and phi

Definition at line 152 of file force-base.hpp.

template<class Derived>
Derived& pinocchio::ForceBase< Derived >::operator-= ( const ForceBase< Derived > &  phi)
inline

Replaces *this by *this - other.

Returns
a reference to *this

Definition at line 130 of file force-base.hpp.

template<class Derived>
template<typename OtherScalar >
ForcePlain pinocchio::ForceBase< Derived >::operator/ ( const OtherScalar &  alpha) const
inline
Returns
an expression of *this divided by the factor alpha

Definition at line 144 of file force-base.hpp.

template<class Derived>
Derived& pinocchio::ForceBase< Derived >::operator= ( const ForceBase< Derived > &  other)
inline

Copies the Derived Force into *this.

Returns
a reference to *this

Definition at line 117 of file force-base.hpp.

template<class Derived>
template<typename F2 >
bool pinocchio::ForceBase< Derived >::operator== ( const ForceBase< F2 > &  other) const
inline
Returns
true if each coefficients of *this and other are all exactly equal.
Warning
When using floating point scalar values you probably should rather use a fuzzy comparison such as isApprox()

Definition at line 97 of file force-base.hpp.

template<class Derived>
template<typename S2 , int O2>
SE3GroupAction<Derived>::ReturnType pinocchio::ForceBase< Derived >::se3Action ( const SE3Tpl< S2, O2 > &  m) const
inline

Transform from A to B coordinates the Force represented by *this such that

\begin{equation*} {}^{B}f = {}^{B}X_A^* * {}^{A}f \end{equation*}

.

Parameters
[in]mThe rigid transformation $ {}^{B}m_A $ whose coordinates transform for forces is {}^{B}X_A^*
Returns
an expression of the force expressed in the new coordinates

Definition at line 173 of file force-base.hpp.

template<class Derived>
template<typename S2 , int O2>
SE3GroupAction<Derived>::ReturnType pinocchio::ForceBase< Derived >::se3ActionInverse ( const SE3Tpl< S2, O2 > &  m) const
inline

Transform from B to A coordinates the Force represented by *this such that

\begin{equation*} {}^{A}f = {}^{A}X_B^* * {}^{A}f \end{equation*}

.

Parameters
[in]mThe rigid transformation $ {}^{B}m_A $ whose coordinates transform for forces is {}^{B}X_A^*
Returns
an expression of the force expressed in the new coordinates

Definition at line 189 of file force-base.hpp.

template<class Derived>
ToVectorConstReturnType pinocchio::ForceBase< Derived >::toVector ( ) const
inline

Return the force as an Eigen vector.

Returns
The 6D vector $ \phi $ such that

\begin{equation*} {}^{A}\phi = \begin{bmatrix} {}^{A}f \\ {}^{A}\tau \end{bmatrix} \end{equation*}

Definition at line 81 of file force-base.hpp.

template<class Derived>
ToVectorReturnType pinocchio::ForceBase< Derived >::toVector ( )
inline

Return the force as an Eigen vector.

Returns
The 6D vector $ \phi $ such that

\begin{equation*} {}^{A}\phi = \begin{bmatrix} {}^{A}f \\ {}^{A}\tau \end{bmatrix} \end{equation*}

Definition at line 84 of file force-base.hpp.

Friends And Related Function Documentation

template<class Derived>
std::ostream& operator<< ( std::ostream &  os,
const ForceBase< Derived > &  X 
)
friend

Definition at line 200 of file force-base.hpp.


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


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