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

This class encapsulates a serial kinematic interconnection structure. More...

#include <src/chain.hpp>

Collaboration diagram for KDL::Chain:
Collaboration graph
[legend]

Public Member Functions

 Chain ()
 The constructor of a chain, a new chain is always empty. More...
 
 Chain (const Chain &in)
 
Chainoperator= (const Chain &arg)
 
void addSegment (const Segment &segment)
 Adds a new segment to the end of the chain. More...
 
void addChain (const Chain &chain)
 Adds a complete chain to the end of the chain The added chain is copied. More...
 
unsigned int getNrOfJoints () const
 Request the total number of joints in the chain. More...
 
unsigned int getNrOfSegments () const
 Request the total number of segments in the chain. More...
 
const SegmentgetSegment (unsigned int nr) const
 Request the nr'd segment of the chain. More...
 
SegmentgetSegment (unsigned int nr)
 Request the nr'd segment of the chain. More...
 
virtual ~Chain ()
 

Public Attributes

std::vector< Segmentsegments
 

Private Attributes

unsigned int nrOfJoints
 
unsigned int nrOfSegments
 

Detailed Description

This class encapsulates a serial kinematic interconnection structure.

It is built out of segments.

Constructor & Destructor Documentation

§ Chain() [1/2]

KDL::Chain::Chain ( )

The constructor of a chain, a new chain is always empty.

§ Chain() [2/2]

KDL::Chain::Chain ( const Chain in)

§ ~Chain()

KDL::Chain::~Chain ( )
virtual

Referenced by getNrOfSegments().

Member Function Documentation

§ addChain()

void KDL::Chain::addChain ( const Chain chain)

Adds a complete chain to the end of the chain The added chain is copied.

Parameters
chainThe chain to add

References addSegment(), getNrOfSegments(), and getSegment().

§ addSegment()

void KDL::Chain::addSegment ( const Segment segment)

Adds a new segment to the end of the chain.

Parameters
segmentThe segment to add

References KDL::Segment::getJoint(), KDL::Joint::getType(), KDL::Joint::None, nrOfJoints, nrOfSegments, and segments.

Referenced by addChain(), Chain(), KDL::Tree::getChain(), and operator=().

§ getNrOfJoints()

unsigned int KDL::Chain::getNrOfJoints ( ) const
inline

Request the total number of joints in the chain.


Important: It is not the same as the total number of segments since a segment does not need to have a joint. This function is important when creating a KDL::JntArray to use with this chain.

Returns
total nr of joints

References nrOfJoints.

Referenced by KDL::ChainIkSolverVel_pinv_givens::CartToJnt(), KDL::ChainIdSolver_RNE::CartToJnt(), KDL::ChainIkSolverVel_pinv_nso::CartToJnt(), KDL::ChainIkSolverPos_NR::CartToJnt(), KDL::ChainIdSolver_Vereshchagin::CartToJnt(), KDL::ChainIkSolverVel_pinv::CartToJnt(), KDL::ChainIkSolverPos_NR_JL::CartToJnt(), KDL::ChainIkSolverVel_wdls::CartToJnt(), KDL::ChainIkSolverPos_LMA::CartToJnt(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainFkSolverVel_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), KDL::ChainJntToJacDotSolver::JntToJacDot(), KDL::ChainDynParam::JntToMass(), KDL::ChainJntToJacSolver::setLockedJoints(), KDL::ChainIkSolverVel_wdls::setWeightJS(), KDL::ChainIkSolverVel_pinv_givens::updateInternalDataStructures(), KDL::ChainDynParam::updateInternalDataStructures(), KDL::ChainIdSolver_RNE::updateInternalDataStructures(), KDL::ChainJntToJacSolver::updateInternalDataStructures(), KDL::ChainIkSolverPos_NR::updateInternalDataStructures(), KDL::ChainIkSolverVel_pinv::updateInternalDataStructures(), KDL::ChainIkSolverPos_NR_JL::updateInternalDataStructures(), KDL::ChainJntToJacDotSolver::updateInternalDataStructures(), KDL::ChainIkSolverVel_pinv_nso::updateInternalDataStructures(), KDL::ChainIkSolverPos_LMA::updateInternalDataStructures(), and KDL::ChainIkSolverVel_wdls::updateInternalDataStructures().

§ getNrOfSegments()

unsigned int KDL::Chain::getNrOfSegments ( ) const
inline

§ getSegment() [1/2]

const Segment & KDL::Chain::getSegment ( unsigned int  nr) const

§ getSegment() [2/2]

Segment & KDL::Chain::getSegment ( unsigned int  nr)

Request the nr'd segment of the chain.

There is no boundary checking.

Parameters
nrthe nr of the segment starting from 0
Returns
a reference to the nr'd segment

References segments.

§ operator=()

Chain & KDL::Chain::operator= ( const Chain arg)

Member Data Documentation

§ nrOfJoints

unsigned int KDL::Chain::nrOfJoints
private

§ nrOfSegments

unsigned int KDL::Chain::nrOfSegments
private

§ segments

std::vector<Segment> KDL::Chain::segments

Referenced by addSegment(), getSegment(), and operator=().


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