Template Struct SE3Base
- Defined in File se3-base.hpp 
Inheritance Relationships
Base Type
- public pinocchio::NumericalBase< Derived >(Template Struct NumericalBase)
Derived Types
- public pinocchio::SE3Tpl< Scalar, Options >(Template Struct SE3Tpl)
- public pinocchio::SE3Tpl< context::Scalar, context::Options >(Template Struct SE3Tpl)
Struct Documentation
- 
template<class Derived>
 struct SE3Base : public pinocchio::NumericalBase<Derived>
- Base class for rigid transformation. - The rigid transform aMb can be seen in two ways: - given a point p expressed in frame B by its coordinate vector \( ^bp \), \( ^aM_b \) computes its coordinates in frame A by \( ^ap = {}^aM_b {}^bp \). 
- \( ^aM_b \) displaces a solid S centered at frame A into the solid centered in B. In particular, the origin of A is displaced at the origin of B: \(^aM_b {}^aA = {}^aB \). 
 - The rigid displacement is stored as a rotation matrix and translation vector by: \( ^aM_b x = {}^aR_b x + {}^aAB \) where \(^aAB\) is the vector from origin A to origin B expressed in coordinates A. - \cheatsheet \( {}^aM_c = {}^aM_b {}^bM_c \) - Subclassed by pinocchio::SE3Tpl< Scalar, Options >, pinocchio::SE3Tpl< context::Scalar, context::Options > - Public Functions - 
inline ConstAngularRef rotation() const
 - 
inline ConstLinearRef translation() const
 - 
inline AngularRef rotation()
 - 
inline LinearRef translation()
 - 
inline void rotation(const AngularType &R)
 - 
inline void translation(const LinearType &t)
 - 
inline HomogeneousMatrixType toHomogeneousMatrix() const
 - 
inline operator HomogeneousMatrixType() const
 - 
inline ActionMatrixType toActionMatrix() const
- The action matrix \( {}^aX_b \) of \( {}^aM_b \). - With \( {}^aM_b = \left( \begin{array}{cc} R & t \\ 0 & 1 \\ \end{array} \right) \), \[\begin{split} {}^aX_b = \left( \begin{array}{cc} R & \hat{t} R \\ 0 & R \\ \end{array} \right) \end{split}\]- \cheatsheet \( {}^a\nu_c = {}^aX_b {}^b\nu_c \) 
 - 
inline operator ActionMatrixType() const
 - 
template<typename Matrix6Like>
 inline void toActionMatrix(const Eigen::MatrixBase<Matrix6Like> &action_matrix) const
 - 
inline ActionMatrixType toActionMatrixInverse() const
- The action matrix \( {}^bX_a \) of \( {}^aM_b \). - See also 
 - 
template<typename Matrix6Like>
 inline void toActionMatrixInverse(const Eigen::MatrixBase<Matrix6Like> &action_matrix_inverse) const
 - 
inline ActionMatrixType toDualActionMatrix() const
 - 
inline void disp(std::ostream &os) const
 - 
template<typename Matrix6Like>
 inline void toDualActionMatrix(const Eigen::MatrixBase<Matrix6Like> &dual_action_matrix) const
 - 
inline SE3GroupAction<Derived>::ReturnType operator*(const Derived &m2) const
 - 
template<typename D>
 inline SE3GroupAction<D>::ReturnType act(const D &d) const
- ay = aXb.act(by) 
 - 
template<typename D>
 inline SE3GroupAction<D>::ReturnType actInv(const D &d) const
- by = aXb.actInv(ay) 
 - 
inline bool isApprox(const Derived &other, const Scalar &prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
 - 
inline bool isIdentity(const typename traits<Derived>::Scalar &prec = Eigen::NumTraits<typename traits<Derived>::Scalar>::dummy_precision()) const
- Returns:
- true if *this is approximately equal to the identity placement, within the precision given by prec. 
 
 - 
inline bool isNormalized(const Scalar &prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
- Returns:
- true if the rotational part of *this is a rotation matrix (normalized columns), within the precision given by prec. 
 
 - 
inline void normalize()
- Normalize *this in such a way the rotation part of *this lies on SO(3). 
 - 
inline PlainType normalized() const
- Returns:
- a Normalized version of *this, in such a way the rotation part of the returned transformation lies on SO(3).