|
KDL 1.5.1
|
#include <src/chain.hpp>

Public Member Functions | |
| Chain () | |
| The constructor of a chain, a new chain is always empty. | |
| Chain (const Chain &in) | |
| Chain & | operator= (const Chain &arg) |
| void | addSegment (const Segment &segment) |
| Adds a new segment to the end of the chain. | |
| void | addChain (const Chain &chain) |
| Adds a complete chain to the end of the chain The added chain is copied. | |
| unsigned int | getNrOfJoints () const |
| Request the total number of joints in the chain. | |
| unsigned int | getNrOfSegments () const |
| Request the total number of segments in the chain. | |
| const Segment & | getSegment (unsigned int nr) const |
| Request the nr'd segment of the chain. | |
| Segment & | getSegment (unsigned int nr) |
| Request the nr'd segment of the chain. | |
| virtual | ~Chain () |
Public Attributes | |
| std::vector< Segment > | segments |
Private Attributes | |
| unsigned int | nrOfJoints |
| unsigned int | nrOfSegments |
\brief This class encapsulates a <strong>serial</strong> kinematic interconnection structure. It is built out of segments.
| KDL::Chain::Chain | ( | ) |
The constructor of a chain, a new chain is always empty.
References nrOfJoints, nrOfSegments, and segments.
Referenced by addChain(), Chain(), and operator=().
| KDL::Chain::Chain | ( | const Chain & | in | ) |
References addSegment(), Chain(), getNrOfSegments(), getSegment(), nrOfJoints, nrOfSegments, and segments.
|
virtual |
| 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 |
References addSegment(), Chain(), 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 |
References KDL::Joint::Fixed, KDL::Segment::getJoint(), KDL::Joint::getType(), nrOfJoints, nrOfSegments, and segments.
Referenced by addChain(), Chain(), KDL::Tree::getChain(), 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.
References nrOfJoints.
|
inline |
Request the total number of segments in the chain.
References nrOfSegments.
Referenced by addChain(), KDL::Tree::addChain(), Chain(), and KDL::operator<<().
| Segment & KDL::Chain::getSegment | ( | unsigned int | nr | ) |
Request the nr'd segment of the chain.
There is no boundary checking.
| nr | the nr of the segment starting from 0 |
References segments.
| const Segment & KDL::Chain::getSegment | ( | unsigned int | nr | ) | const |
Request the nr'd segment of the chain.
There is no boundary checking.
| nr | the nr of the segment starting from 0 |
References segments.
Referenced by addChain(), KDL::Tree::addChain(), Chain(), KDL::operator<<(), and operator=().
References addSegment(), Chain(), getSegment(), nrOfJoints, nrOfSegments, and segments.
|
private |
Referenced by addSegment(), Chain(), Chain(), getNrOfJoints(), and operator=().
|
private |
Referenced by addSegment(), Chain(), Chain(), getNrOfSegments(), and operator=().
| std::vector<Segment> KDL::Chain::segments |
Referenced by addSegment(), Chain(), Chain(), getSegment(), getSegment(), and operator=().