This class encapsulates a serial kinematic interconnection structure. More...
#include <chain.hpp>
Public Member Functions | |
void | addChain (const Chain &chain) |
Adds a complete chain to the end of the chain The added chain is copied. | |
void | addSegment (const Segment &segment) |
Adds a new segment to the end of the chain. | |
Chain (const Chain &in) | |
Chain () | |
The constructor of a chain, a new chain is always empty. | |
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. | |
Chain & | operator= (const Chain &arg) |
virtual | ~Chain () |
Public Attributes | |
std::vector< Segment > | segments |
This class encapsulates a serial kinematic interconnection structure.
It is build out of segments.
Definition at line 35 of file chain.hpp.
KDL::Chain::Chain | ( | ) |
KDL::Chain::Chain | ( | const Chain & | in | ) |
Definition at line 34 of file chain.cpp.
References addSegment(), getNrOfSegments(), 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 60 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 52 of file chain.cpp.
References KDL::Segment::getJoint(), KDL::Joint::getType(), KDL::Joint::None, and segments.
Referenced by addChain(), Chain(), KDL::Tree::getChain(), operator=(), Robot::Robot6Axis::Restore(), Robot::Robot6Axis::setKinematic(), and Robot::RobotAlgos::Test().
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.
Definition at line 71 of file chain.hpp.
Referenced by KDL::ChainIkSolverVel_pinv_givens::CartToJnt(), KDL::ChainFkSolverVel_recursive::JntToCart(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), Robot::Robot6Axis::setTo(), and Robot::RobotAlgos::Test().
unsigned int KDL::Chain::getNrOfSegments | ( | ) | const [inline] |
Request the total number of segments in the chain.
Definition at line 76 of file chain.hpp.
Referenced by KDL::Tree::addChain(), addChain(), Chain(), KDL::ChainFkSolverVel_recursive::JntToCart(), KDL::ChainFkSolverPos_recursive::JntToCart(), and KDL::ChainJntToJacSolver::JntToJac().
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 |
Definition at line 66 of file chain.cpp.
References segments.
Referenced by KDL::Tree::addChain(), addChain(), KDL::ChainIdSolver_RNE::CartToJnt(), Chain(), KDL::ChainFkSolverVel_recursive::JntToCart(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), KDL::ChainDynParam::JntToMass(), operator=(), and Robot::Robot6Axis::Save().
Definition at line 41 of file chain.cpp.
References addSegment(), getSegment(), and segments.
std::vector<Segment> KDL::Chain::segments |
Definition at line 40 of file chain.hpp.
Referenced by addSegment(), getSegment(), and operator=().