Template Class ForceBase
Defined in File force-base.hpp
Inheritance Relationships
Derived Types
public pinocchio::ForceDense< ForceRef< Vector6ArgType > >
(Template Class ForceDense)public pinocchio::ForceDense< ForceRef< const Vector6ArgType > >
(Template Class ForceDense)public pinocchio::ForceDense< ForceTpl< _Scalar, _Options > >
(Template Class ForceDense)public pinocchio::ForceDense< ForceTpl< Scalar, _Options > >
(Template Class ForceDense)public pinocchio::ForceDense< pinocchio::ForceTpl >
(Template Class ForceDense)public pinocchio::ForceDense< pinocchio::ForceRef >
(Template Class ForceDense)public pinocchio::ForceDense< Derived >
(Template Class ForceDense)
Class Documentation
-
template<class Derived>
class ForceBase 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 }
Subclassed by pinocchio::ForceDense< ForceRef< Vector6ArgType > >, pinocchio::ForceDense< ForceRef< const Vector6ArgType > >, pinocchio::ForceDense< ForceTpl< _Scalar, _Options > >, pinocchio::ForceDense< ForceTpl< Scalar, _Options > >, pinocchio::ForceDense< pinocchio::ForceTpl >, pinocchio::ForceDense< pinocchio::ForceRef >, pinocchio::ForceDense< Derived >
Public Functions
-
inline ConstAngularType angular() const
Return the angular part of the force vector.
- Returns:
The 3D vector associated to the angular part of the 6D force vector
-
inline ConstLinearType linear() const
Return the linear part of the force vector.
- Returns:
The 3D vector associated to the linear part of the 6D force vector
-
inline AngularType angular()
Return the angular part of the force vector.
- Returns:
The 3D vector associated to the angular part of the 6D force vector
-
inline LinearType linear()
Return the linear part of the force vector.
- Returns:
The 3D vector associated to the linear part of the 6D force vector
-
template<typename V3Like>
inline void angular(const Eigen::MatrixBase<V3Like> &n) Set the angular part of the force vector.
- Template Parameters:
V3Like – A vector 3 like type.
- Parameters:
n – [in]
-
template<typename V3Like>
inline void linear(const Eigen::MatrixBase<V3Like> &f) Set the linear part of the force vector.
- Template Parameters:
V3Like – A vector 3 like type.
- Parameters:
f – [in]
-
inline ToVectorConstReturnType toVector() const
Return the force as an Eigen vector.
- Returns:
The 6D vector \( \phi \) such that
\[\begin{split}\begin{equation*} {}^{A}\phi = \begin{bmatrix} {}^{A}f \\ {}^{A}\tau \end{bmatrix} \end{equation*}\end{split}\]
-
inline ToVectorReturnType toVector()
Return the force as an Eigen vector.
- Returns:
The 6D vector \( \phi \) such that
\[\begin{split}\begin{equation*} {}^{A}\phi = \begin{bmatrix} {}^{A}f \\ {}^{A}\tau \end{bmatrix} \end{equation*}\end{split}\]
-
inline operator Vector6() const
-
template<typename F2>
inline bool operator==(const ForceBase<F2> &other) const Warning
When using floating point scalar values you probably should rather use a fuzzy comparison such as isApprox()
- Returns:
true if each coefficients of
*this
and other are all exactly equal.
-
template<typename F2>
inline bool operator!=(const ForceBase<F2> &other) const - Returns:
true if at least one coefficient of
*this
and other does not match.
-
inline bool isApprox(const Derived &other, const Scalar &prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
- Returns:
true if *this is approximately equal to other, within the precision given by prec.
-
inline bool isZero(const Scalar &prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
- 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.
-
inline Derived &operator=(const ForceBase<Derived> &other)
Copies the Derived Force into *this.
- Returns:
a reference to *this
-
inline Derived &operator+=(const ForceBase<Derived> &phi)
Replaces *this by *this + other.
- Returns:
a reference to *this
-
inline Derived &operator-=(const ForceBase<Derived> &phi)
Replaces *this by *this - other.
- Returns:
a reference to *this
-
inline Derived operator+(const ForceBase<Derived> &phi) const
- Returns:
an expression of the sum of *this and other
-
template<typename OtherScalar>
inline ForcePlain operator*(const OtherScalar &alpha) const - Returns:
an expression of *this scaled by the factor alpha
-
template<typename OtherScalar>
inline ForcePlain operator/(const OtherScalar &alpha) const - Returns:
an expression of *this divided by the factor alpha
-
inline Derived operator-(const ForceBase<Derived> &phi) const
- Returns:
an expression of the difference of *this and phi
-
template<typename MotionDerived>
inline Scalar dot(const MotionDense<MotionDerived> &m) const - Returns:
the dot product of *this with m *
-
template<typename S2, int O2>
inline 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*}\]- Parameters:
m – [in] The 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
-
template<typename S2, int O2>
inline 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*}\]- Parameters:
m – [in] The 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
-
template<typename M1>
inline MotionAlgebraAction<Derived, M1>::ReturnType motionAction(const MotionDense<M1> &v) const
-
inline void disp(std::ostream &os) const