KDL::ChainJntToJacSolver Class Reference

Class to calculate the jacobian of a general KDL::Chain, it is used by other solvers. More...

#include <chainjnttojacsolver.hpp>

List of all members.

Public Member Functions

 ChainJntToJacSolver (const Chain &chain)
int 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.
int setLockedJoints (const std::vector< bool > locked_joints)
 ~ChainJntToJacSolver ()

Detailed Description

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.


Constructor & Destructor Documentation

KDL::ChainJntToJacSolver::ChainJntToJacSolver ( const Chain chain  ) 

Definition at line 26 of file chainjnttojacsolver.cpp.

KDL::ChainJntToJacSolver::~ChainJntToJacSolver (  ) 

Definition at line 32 of file chainjnttojacsolver.cpp.


Member Function Documentation

int KDL::ChainJntToJacSolver::JntToJac ( const JntArray q_in,
Jacobian jac 
)
int KDL::ChainJntToJacSolver::setLockedJoints ( const std::vector< bool >  locked_joints  ) 

Definition at line 36 of file chainjnttojacsolver.cpp.


The documentation for this class was generated from the following files:

Generated on Wed Nov 23 19:02:16 2011 for FreeCAD by  doxygen 1.6.1