Blender V2.61 - r43446
|
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) | |
~ChainJntToJacSolver () | |
int | JntToJac (const JntArray &q_in, Jacobian &jac) |
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 | ) |
Definition at line 29 of file chainjnttojacsolver.cpp.
KDL::ChainJntToJacSolver::~ChainJntToJacSolver | ( | ) |
Definition at line 34 of file chainjnttojacsolver.cpp.
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 38 of file chainjnttojacsolver.cpp.
References assert, KDL::changeBase(), KDL::Jacobian::columns(), KDL::Segment::getFrameToTip(), KDL::Segment::getJoint(), KDL::Joint::getNDof(), KDL::Chain::getNrOfJoints(), KDL::Chain::getNrOfSegments(), KDL::Chain::getSegment(), i, KDL::Frame::Identity(), KDL::Frame::M, KDL::Frame::p, KDL::Joint::pose(), KDL::Twist::RefPoint(), KDL::JntArray::rows(), KDL::SetToZero(), KDL::Segment::twist(), and KDL::Jacobian::twists.
Referenced by iTaSC::Distance::updateJacobian().