Class to calculate the jacobian of a general KDL::Chain, it is used by other solvers. It should not be used outside of KDL. More...
#include <chainjnttojacsolver.hpp>
Public Member Functions | |
ChainJntToJacSolver (const Chain &chain) | |
int | JntToJac (const JntArray &q_in, Jacobian &jac) |
int | setLockedJoints (const std::vector< bool > locked_joints) |
~ChainJntToJacSolver () | |
Private Attributes | |
const Chain | chain |
std::vector< bool > | locked_joints_ |
int | nr_of_unlocked_joints_ |
Twist | t_tmp |
Frame | T_tmp |
Class to calculate the jacobian of a general KDL::Chain, it is used by other solvers. It should not be used outside of KDL.
Definition at line 40 of file chainjnttojacsolver.hpp.
KDL::ChainJntToJacSolver::ChainJntToJacSolver | ( | const Chain & | chain | ) | [explicit] |
Definition at line 26 of file chainjnttojacsolver.cpp.
Definition at line 32 of file chainjnttojacsolver.cpp.
int KDL::ChainJntToJacSolver::JntToJac | ( | const JntArray & | q_in, |
Jacobian & | jac | ||
) |
Calculate the jacobian expressed in the base frame of the chain, with reference point at the end effector of the *chain. The alghoritm is similar to the one used in KDL::ChainFkSolverVel_recursive
q_in | input joint positions |
jac | output jacobian |
Definition at line 48 of file chainjnttojacsolver.cpp.
int KDL::ChainJntToJacSolver::setLockedJoints | ( | const std::vector< bool > | locked_joints | ) |
Definition at line 36 of file chainjnttojacsolver.cpp.
const Chain KDL::ChainJntToJacSolver::chain [private] |
Definition at line 60 of file chainjnttojacsolver.hpp.
std::vector<bool> KDL::ChainJntToJacSolver::locked_joints_ [private] |
Definition at line 63 of file chainjnttojacsolver.hpp.
int KDL::ChainJntToJacSolver::nr_of_unlocked_joints_ [private] |
Definition at line 64 of file chainjnttojacsolver.hpp.
Twist KDL::ChainJntToJacSolver::t_tmp [private] |
Definition at line 61 of file chainjnttojacsolver.hpp.
Frame KDL::ChainJntToJacSolver::T_tmp [private] |
Definition at line 62 of file chainjnttojacsolver.hpp.