#include "pinocchio/fwd.hpp"
#include "pinocchio/utils/static-if.hpp"
#include "pinocchio/math/fwd.hpp"
#include "pinocchio/math/sincos.hpp"
#include "pinocchio/math/taylor-expansion.hpp"
#include "pinocchio/spatial/motion.hpp"
#include "pinocchio/spatial/skew.hpp"
#include "pinocchio/spatial/se3.hpp"
#include <Eigen/Geometry>
#include "pinocchio/spatial/log.hpp"
#include "pinocchio/spatial/explog-quaternion.hpp"
#include "pinocchio/spatial/log.hxx"
Go to the source code of this file.
Namespaces | |
pinocchio | |
Main pinocchio namespace. | |
Functions | |
template<typename Vector3Like > | |
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > | pinocchio::exp3 (const Eigen::MatrixBase< Vector3Like > &v) |
Exp: so3 -> SO3. More... | |
template<typename MotionDerived > | |
SE3Tpl< typename MotionDerived::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(typename MotionDerived::Vector3)::Options > | pinocchio::exp6 (const MotionDense< MotionDerived > &nu) |
Exp: se3 -> SE3. More... | |
template<typename Vector6Like > | |
SE3Tpl< typename Vector6Like::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector6Like)::Options > | pinocchio::exp6 (const Eigen::MatrixBase< Vector6Like > &v) |
Exp: se3 -> SE3. More... | |
template<typename Scalar , typename Vector3Like1 , typename Vector3Like2 , typename Matrix3Like > | |
void | pinocchio::Hlog3 (const Scalar &theta, const Eigen::MatrixBase< Vector3Like1 > &log, const Eigen::MatrixBase< Vector3Like2 > &v, const Eigen::MatrixBase< Matrix3Like > &vt_Hlog) |
template<typename Matrix3Like1 , typename Vector3Like , typename Matrix3Like2 > | |
void | pinocchio::Hlog3 (const Eigen::MatrixBase< Matrix3Like1 > &R, const Eigen::MatrixBase< Vector3Like > &v, const Eigen::MatrixBase< Matrix3Like2 > &vt_Hlog) |
Second order derivative of log3. More... | |
template<AssignmentOperatorType op, typename Vector3Like , typename Matrix3Like > | |
void | pinocchio::Jexp3 (const Eigen::MatrixBase< Vector3Like > &r, const Eigen::MatrixBase< Matrix3Like > &Jexp) |
Derivative of
. More... | |
template<typename Vector3Like , typename Matrix3Like > | |
void | pinocchio::Jexp3 (const Eigen::MatrixBase< Vector3Like > &r, const Eigen::MatrixBase< Matrix3Like > &Jexp) |
Derivative of
. More... | |
template<AssignmentOperatorType op, typename MotionDerived , typename Matrix6Like > | |
void | pinocchio::Jexp6 (const MotionDense< MotionDerived > &nu, const Eigen::MatrixBase< Matrix6Like > &Jexp) |
Derivative of exp6 Computed as the inverse of Jlog6. More... | |
template<typename MotionDerived , typename Matrix6Like > | |
void | pinocchio::Jexp6 (const MotionDense< MotionDerived > &nu, const Eigen::MatrixBase< Matrix6Like > &Jexp) |
Derivative of exp6 Computed as the inverse of Jlog6. More... | |
template<typename Scalar , typename Vector3Like , typename Matrix3Like > | |
void | pinocchio::Jlog3 (const Scalar &theta, const Eigen::MatrixBase< Vector3Like > &log, const Eigen::MatrixBase< Matrix3Like > &Jlog) |
Derivative of log3. More... | |
template<typename Matrix3Like1 , typename Matrix3Like2 > | |
void | pinocchio::Jlog3 (const Eigen::MatrixBase< Matrix3Like1 > &R, const Eigen::MatrixBase< Matrix3Like2 > &Jlog) |
Derivative of log3. More... | |
template<typename Scalar , int Options, typename Matrix6Like > | |
void | pinocchio::Jlog6 (const SE3Tpl< Scalar, Options > &M, const Eigen::MatrixBase< Matrix6Like > &Jlog) |
Derivative of log6
where
and
. More... | |
template<typename Matrix3Like > | |
Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > | pinocchio::log3 (const Eigen::MatrixBase< Matrix3Like > &R, typename Matrix3Like::Scalar &theta) |
Same as log3. More... | |
template<typename Matrix3Like > | |
Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > | pinocchio::log3 (const Eigen::MatrixBase< Matrix3Like > &R) |
Log: SO(3)-> so(3). More... | |
template<typename Scalar , int Options> | |
MotionTpl< Scalar, Options > | pinocchio::log6 (const SE3Tpl< Scalar, Options > &M) |
Log: SE3 -> se3. More... | |
template<typename Matrix4Like > | |
MotionTpl< typename Matrix4Like::Scalar, Eigen::internal::traits< Matrix4Like >::Options > | pinocchio::log6 (const Eigen::MatrixBase< Matrix4Like > &M) |
Log: SE3 -> se3. More... | |