pinocchio  3.9.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
Loading...
Searching...
No Matches
Cheat sheet
Member LieGroupBase< Derived >::dDifference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianOut_t > &J) const
$ \frac{\partial\ominus}{\partial q_1} \frac{\partial\oplus}{\partial v} = I
$
Member LieGroupBase< Derived >::difference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< Tangent_t > &v) const
$ q_1 \ominus q_0 = - \left( q_0 \ominus q_1 \right) $
Member LieGroupBase< Derived >::isSameConfiguration (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
$ q_1 \equiv  q_0 \oplus \left( q_1 \ominus q_0 \right) $ ( $\equiv$ means equivalent, not equal).
Member pinocchio::Jlog6 (const SE3Tpl< Scalar, Options > &M, const Eigen::MatrixBase< Matrix6Like > &Jlog)

For $(A,B) \in SE(3)^2$, let $M_1(A, B) = A B$ and $m_1 = \log_6(M_1) $. Then, we have the following partial (right) Jacobians:

  • $ \frac{\partial m_1}{\partial A} = Jlog_6(M_1) Ad_B^{-1} $,
  • $ \frac{\partial m_1}{\partial B} = Jlog_6(M_1) $.

Let $A \in SE(3)$, $M_2(A) = A^{-1}$ and $m_2 =
\log_6(M_2)$. Then, we have the following partial (right) Jacobian:

  • $ \frac{\partial m_2}{\partial A} = - Jlog_6(M_2) Ad_A $.
Struct SE3Base< Derived >
$ {}^aM_c = {}^aM_b {}^bM_c $
Member SE3Base< Derived >::toActionMatrix () const
$ {}^a\nu_c = {}^aX_b {}^b\nu_c $
Member SpecialEuclideanOperationTpl< 3, _Scalar, _Options >::dDifference_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianOut_t > &J)
$ \frac{\partial\ominus}{\partial q_1} {}^1X_0 = -
\frac{\partial\ominus}{\partial q_0} $