|
Blender V4.3
|
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) | |
| Chain & | operator= (const Chain &arg) |
| void | addSegment (const Segment &segment) |
| void | addChain (const Chain &chain) |
| unsigned int | getNrOfJoints () const |
| unsigned int | getNrOfSegments () const |
| const Segment & | getSegment (unsigned int nr) const |
| virtual | ~Chain () |
This class encapsulates a serial kinematic interconnection structure. It is build out of segments.
| KDL::Chain::Chain | ( | ) |
| KDL::Chain::Chain | ( | const Chain & | in | ) |
Definition at line 37 of file chain.cpp.
References addSegment(), and getSegment().
| void KDL::Chain::addChain | ( | const Chain & | chain | ) |
Adds a complete chain to the end of the chain The added chain is copied.
| chain | The chain to add |
Definition at line 62 of file chain.cpp.
References addSegment(), getNrOfSegments(), and getSegment().
| void KDL::Chain::addSegment | ( | const Segment & | segment | ) |
Adds a new segment to the end of the chain.
| segment | The segment to add |
Definition at line 55 of file chain.cpp.
Referenced by addChain(), Chain(), iTaSC::Distance::Distance(), and operator=().
|
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.
Definition at line 73 of file chain.hpp.
Referenced by KDL::ChainFkSolverPos_recursive::JntToCart(), and KDL::ChainJntToJacSolver::JntToJac().
|
inline |
Request the total number of segments in the chain.
Definition at line 78 of file chain.hpp.
Referenced by addChain(), KDL::Tree::addChain(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), and KDL::operator<<().
Request the nr'd segment of the chain. There is no boundary checking.
| nr | the nr of the segment starting from 0 |
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=().
Definition at line 44 of file chain.cpp.
References addSegment(), and getSegment().