This class encapsulates a serial kinematic interconnection structure. It is built out of segments.
More...
#include <chain.hpp>
This class encapsulates a serial kinematic interconnection structure. It is built out of segments.
Definition at line 35 of file chain.hpp.
The constructor of a chain, a new chain is always empty.
Definition at line 27 of file chain.cpp.
| KDL::Chain::Chain |
( |
const Chain & |
in | ) |
|
| void KDL::Chain::addChain |
( |
const Chain & |
chain | ) |
|
Adds a complete chain to the end of the chain The added chain is copied.
- Parameters
-
Definition at line 62 of file chain.cpp.
| void KDL::Chain::addSegment |
( |
const Segment & |
segment | ) |
|
Adds a new segment to the end of the chain.
- Parameters
-
| segment | The segment to add |
Definition at line 54 of file chain.cpp.
| 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 71 of file chain.hpp.
| unsigned int KDL::Chain::getNrOfSegments |
( |
| ) |
const |
|
inline |
Request the total number of segments in the chain.
- Returns
- total number of segments
Definition at line 76 of file chain.hpp.
| const Segment & KDL::Chain::getSegment |
( |
unsigned int |
nr | ) |
const |
Request the nr'd segment of the chain. There is no boundary checking.
- Parameters
-
| nr | the nr of the segment starting from 0 |
- Returns
- a constant reference to the nr'd segment
Definition at line 68 of file chain.cpp.
| Segment & KDL::Chain::getSegment |
( |
unsigned int |
nr | ) |
|
Request the nr'd segment of the chain. There is no boundary checking.
- Parameters
-
| nr | the nr of the segment starting from 0 |
- Returns
- a reference to the nr'd segment
Definition at line 73 of file chain.cpp.
| Chain & KDL::Chain::operator= |
( |
const Chain & |
arg | ) |
|
| unsigned int KDL::Chain::nrOfJoints |
|
private |
| unsigned int KDL::Chain::nrOfSegments |
|
private |
| std::vector<Segment> KDL::Chain::segments |
The documentation for this class was generated from the following files: