#include <kinematics.hpp>
|
template<class MatT > |
static Eigen::Matrix< typename MatT::Scalar, MatT::ColsAtCompileTime, MatT::RowsAtCompileTime > | pseudoinverse (const MatT &mat, typename MatT::Scalar tolerance=typename MatT::Scalar{1e-4}) |
|
static std::array< double, 16 > | forward (const Eigen::Matrix< double, 7, 1 > &q) |
|
static std::array< double, 16 > | forwardElbow (const Eigen::Matrix< double, 7, 1 > &q) |
|
static Eigen::Matrix< double, 6, 1 > | forwardEuler (const Eigen::Matrix< double, 7, 1 > &q) |
|
static Eigen::Matrix< double, 6, 7 > | jacobian (const Eigen::Matrix< double, 7, 1 > &q) |
|
static Eigen::Matrix< double, 7, 1 > | inverse (const Eigen::Matrix< double, 6, 1 > &x_target, const Eigen::Matrix< double, 7, 1 > &q0, std::optional< NullSpaceHandling > null_space=std::nullopt) |
|
◆ forward()
std::array< double, 16 > frankx::Kinematics::forward |
( |
const Eigen::Matrix< double, 7, 1 > & |
q | ) |
|
|
static |
◆ forwardElbow()
std::array< double, 16 > frankx::Kinematics::forwardElbow |
( |
const Eigen::Matrix< double, 7, 1 > & |
q | ) |
|
|
static |
◆ forwardEuler()
Eigen::Matrix< double, 6, 1 > frankx::Kinematics::forwardEuler |
( |
const Eigen::Matrix< double, 7, 1 > & |
q | ) |
|
|
static |
◆ inverse()
Eigen::Matrix< double, 7, 1 > frankx::Kinematics::inverse |
( |
const Eigen::Matrix< double, 6, 1 > & |
x_target, |
|
|
const Eigen::Matrix< double, 7, 1 > & |
q0, |
|
|
std::optional< NullSpaceHandling > |
null_space = std::nullopt |
|
) |
| |
|
static |
◆ jacobian()
Eigen::Matrix< double, 6, 7 > frankx::Kinematics::jacobian |
( |
const Eigen::Matrix< double, 7, 1 > & |
q | ) |
|
|
static |
◆ pseudoinverse()
template<class MatT >
static Eigen::Matrix<typename MatT::Scalar, MatT::ColsAtCompileTime, MatT::RowsAtCompileTime> frankx::Kinematics::pseudoinverse |
( |
const MatT & |
mat, |
|
|
typename MatT::Scalar |
tolerance = typename MatT::Scalar{1e-4} |
|
) |
| |
|
inlinestatic |
The documentation for this struct was generated from the following files: