Blender  V3.3
Public Member Functions | List of all members
KDL::Chain Class Reference

This class encapsulates a serial kinematic interconnection structure. It is build out of segments. More...

#include <chain.hpp>

Public Member Functions

 Chain ()
 
 Chain (const Chain &in)
 
Chainoperator= (const Chain &arg)
 
void addSegment (const Segment &segment)
 
void addChain (const Chain &chain)
 
unsigned int getNrOfJoints () const
 
unsigned int getNrOfSegments () const
 
const SegmentgetSegment (unsigned int nr) const
 
virtual ~Chain ()
 

Detailed Description

This class encapsulates a serial kinematic interconnection structure. It is build out of segments.

Definition at line 36 of file chain.hpp.

Constructor & Destructor Documentation

◆ Chain() [1/2]

KDL::Chain::Chain ( )

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

Definition at line 30 of file chain.cpp.

◆ Chain() [2/2]

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

Definition at line 37 of file chain.cpp.

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

◆ ~Chain()

KDL::Chain::~Chain ( )
virtual

Definition at line 73 of file chain.cpp.

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

Definition at line 62 of file chain.cpp.

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

Definition at line 55 of file chain.cpp.

Referenced by addChain(), Chain(), iTaSC::Distance::Distance(), 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

Definition at line 73 of file chain.hpp.

Referenced by KDL::ChainFkSolverPos_recursive::JntToCart(), and KDL::ChainJntToJacSolver::JntToJac().

◆ getNrOfSegments()

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

Request the total number of segments in the chain.

Returns
total number of segments

Definition at line 78 of file chain.hpp.

Referenced by addChain(), KDL::Tree::addChain(), Chain(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), and KDL::operator<<().

◆ getSegment()

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

Request the nr'd segment of the chain. There is no boundary checking.

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

Definition at line 68 of file chain.cpp.

Referenced by addChain(), KDL::Tree::addChain(), Chain(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), KDL::operator<<(), and operator=().

◆ operator=()

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

Definition at line 44 of file chain.cpp.

References addSegment(), and getSegment().


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