Public Member Functions | Private Attributes | List of all members
KDL::ChainJntToJacSolver Class Reference

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

#include <chainjnttojacsolver.hpp>

Inheritance diagram for KDL::ChainJntToJacSolver:
Inheritance graph
[legend]

Public Member Functions

 ChainJntToJacSolver (const Chain &chain)
 
virtual int JntToJac (const JntArray &q_in, Jacobian &jac, int seg_nr=-1)
 
int setLockedJoints (const std::vector< bool > locked_joints)
 
virtual void updateInternalDataStructures ()
 
virtual ~ChainJntToJacSolver ()
 
- Public Member Functions inherited from KDL::SolverI
virtual int getError () const
 Return the latest error. More...
 
 SolverI ()
 Initialize latest error to E_NOERROR. More...
 
virtual const char * strError (const int error) const
 
virtual ~SolverI ()
 

Private Attributes

const Chainchain
 
std::vector< bool > locked_joints_
 
Twist t_tmp
 
Frame T_tmp
 

Additional Inherited Members

- Public Types inherited from KDL::SolverI
enum  {
  E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2,
  E_NOT_UP_TO_DATE = -3, E_SIZE_MISMATCH = -4, E_MAX_ITERATIONS_EXCEEDED = -5, E_OUT_OF_RANGE = -6,
  E_NOT_IMPLEMENTED = -7, E_SVD_FAILED = -8
}
 
- Protected Attributes inherited from KDL::SolverI
int error
 Latest error, initialized to E_NOERROR in constructor. More...
 

Detailed Description

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

Definition at line 38 of file chainjnttojacsolver.hpp.

Constructor & Destructor Documentation

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

Definition at line 26 of file chainjnttojacsolver.cpp.

KDL::ChainJntToJacSolver::~ChainJntToJacSolver ( )
virtual

Definition at line 34 of file chainjnttojacsolver.cpp.

Member Function Documentation

int KDL::ChainJntToJacSolver::JntToJac ( const JntArray q_in,
Jacobian jac,
int  seg_nr = -1 
)
virtual

Calculate the jacobian expressed in the base frame of the chain, with reference point at the end effector of the *chain. The algorithm is similar to the one used in KDL::ChainFkSolverVel_recursive

Parameters
q_ininput joint positions
jacoutput jacobian
seg_nrThe final segment to compute
Returns
success/error code

Definition at line 48 of file chainjnttojacsolver.cpp.

int KDL::ChainJntToJacSolver::setLockedJoints ( const std::vector< bool >  locked_joints)
Parameters
locked_jointsnew values for locked joints
Returns
success/error code

Definition at line 38 of file chainjnttojacsolver.cpp.

void KDL::ChainJntToJacSolver::updateInternalDataStructures ( )
virtual

Update the internal data structures. This is required if the number of segments or number of joints of a chain/tree have changed. This provides a single point of contact for solver memory allocations.

Implements KDL::SolverI.

Definition at line 31 of file chainjnttojacsolver.cpp.

Member Data Documentation

const Chain& KDL::ChainJntToJacSolver::chain
private

Definition at line 68 of file chainjnttojacsolver.hpp.

std::vector<bool> KDL::ChainJntToJacSolver::locked_joints_
private

Definition at line 71 of file chainjnttojacsolver.hpp.

Twist KDL::ChainJntToJacSolver::t_tmp
private

Definition at line 69 of file chainjnttojacsolver.hpp.

Frame KDL::ChainJntToJacSolver::T_tmp
private

Definition at line 70 of file chainjnttojacsolver.hpp.


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


orocos_kdl
Author(s):
autogenerated on Fri Mar 12 2021 03:05:44