Kinematic Trees

A KDL::Chain or KDL::Tree composes/consists of the concatenation of KDL::Segments. A KDL::Segment composes a KDL::Joint and KDL::RigidBodyInertia, and defines a reference and tip frame on the segment. The following figures show a KDL::Segment, KDL::Chain, and KDL::Tree, respectively. At the bottom of this page you'll find the links to a more detailed description.

KDL segmentKDL segment

  • Black: KDL::Segment:
    • reference frame {F_reference} (implicitly defined by the definition of the other frames wrt. this frame)
    • tip frame {F_tip}: frame from the end of the joint to the tip of the segment, default: Frame::Identity(). The transformation from the joint to the tip is denoted T_tip (in KDL directly represented by a KDL::Frame). In a kinematic chain or tree, a child segment is added to the parent segment's tip frame (tip frame of parent=reference frame of the child(ren)).
    • composes a KDL::Joint (red) and a KDL::RigidBodyInertia (green)
  • Red: KDL::Joint: single DOF joint around or along an axis of the joint frame {F_joint}. This joint frame has the same orientation as the the reference frame {F_reference} but can be offset wrt. this reference frame by the vector p_origin (default: no offset).
  • Green: KDL::RigidBodyInertia: Cartesian space inertia matrix, the arguments are the mass, the vector from the reference frame {F_reference} to cog (p_cog) and the rotational inertia in the cog frame {F_cog}.

KDL chainKDL chain KDL treeKDL tree

Select your revision: (1.0.x is the released version, 1.1.x is under discussion (see kinfam_refactored git branch))

Kinematic Trees - KDL 1.0.x

KDL::Joint

Link to API

A Joint allows translation or rotation in one degree of freedom between two Segments

Creating Joints

Joint rx = Joint(Joint::RotX);//Rotational Joint about X
Joint ry = Joint(Joint::RotY);//Rotational Joint about Y
Joint rz = Joint(Joint::RotZ);//Rotational Joint about Z
Joint tx = Joint(Joint::TransX);//Translational Joint along X
Joint ty = Joint(Joint::TransY);//Translational Joint along Y
Joint tz = Joint(Joint::TransZ);//Translational Joint along Z
Joint fixed = Joint(Joint::None);//Rigid Connection
Note: See the API document for a full list of construction possibilities

Pose and twist of a Joint

Joint rx = Joint(Joint::RotX);
double q = M_PI/4;//Joint position
Frame f = rx.pose(q);
double qdot = 0.1;//Joint velocity
Twist t = rx.twist(qdot);
f is the pose resulting from moving the joint from its zero position to a joint value q t is the twist expressed in the frame corresponding to the zero position of the joint, resulting from applying a joint speed qdot

KDL::Segment

Link to API

A Segment is an ideal rigid body to which one single Joint is connected and one single tip frame. It contains:

  • a Joint located at the root frame of the Segment.
  • a Frame describing the pose between the end of the Joint and the tip frame of the Segment.

Creating Segments

Segment s = Segment(Joint(Joint::RotX),
                Frame(Rotation::RPY(0.0,M_PI/4,0.0),
                          Vector(0.1,0.2,0.3) )
                    );
Note: The constructor takes copies of the arguments, you cannot change the frame or joint afterwards!!!

Pose and twist of a Segment

double q=M_PI/2;//joint position
Frame f = s.pose(q);//s constructed as in previous example
double qdot=0.1;//joint velocity
Twist t = s.twist(q,qdot);
fis the pose resulting from moving the joint from its zero position to a joint value q and expresses the new tip frame wrt the root frame of the Segment s. t is the twist of the tip frame expressed in the root frame of the Segment s, resulting from applying a joint speed qdot at the joint value q

KDL::Chain

Link to API

A KDL::Chain is

  • a kinematic description of a serial chain of bodies connected by joints.
  • built out of KDL::Segments.

A Chain has

  • a default constructor, creating an empty chain without any segments.
  • a copy-constructor, creating a copy of an existing chain.
  • a =-operator.

Chain chain1;
Chain chain2(chain3);
Chain chain4 = chain5;

Chains are constructed by adding segments or existing chains to the end of the chain. These functions add copies of the arguments, not the arguments themselves!

chain1.addSegment(segment1);
chain1.addChain(chain2);

You can get the number of joints and number of segments (this is not always the same since a segment can have a Joint::None, which is not included in the number of joints):

unsigned int nj = chain1.getNrOfJoints();
unsigned int js = chain1.getNrOfSegments();

You can iterate over the segments of a chain by getting a reference to each successive segment:

Segment& segment3 = chain1.getSegment(3);

KDL::Tree

Link to API

A KDL::Tree is

  • a kinematic description of a tree of bodies connected by joints.
  • built out of KDL::Segments.

A Tree has

  • a constructor that creates an empty tree without any segments and with the given name as its root name. The root name will be "root" if no name is given.
  • a copy-constructor, creating a copy of an existing tree.
  • a =-operator

Tree tree1;
Tree tree2("RootName");
Tree tree3(tree4);
Tree tree5 = tree6;

Trees are constructed by adding segments, existing chains or existing trees to a given hook name. The methods will return false if the given hook name is not in the tree. These functions add copies of the arguments, not the arguments themselves!

bool exit_value;
exit_value = tree1.addSegment(segment1,"root");
exit_value = tree1.addChain(chain1,"Segment 1");
exit_value = tree1.addTree(tree2,"root");

You can get the number of joints and number of segments (this is not always the same since a segment can have a fixed joint (Joint::None), which is not included in the number of joints):

unsigned int nj = tree1.getNrOfJoints();
unsigned int js = tree1.getNrOfSegments();

You can retrieve the root segment:

std::map<std::string,TreeElement>::const_iterator root = tree1.getRootSegment();

You can also retrieve a specific segment in a tree by its name:

std::map<std::string,TreeElement>::const_iterator segment3 = tree1.getSegment("Segment 3");

You can retrieve the segments in the tree:

std::map<std::string,TreeElement>& segments = tree1.getSegments();

It is possible to request the chain in a tree between a certain root and a tip:

bool exit_value;
Chain chain;
exit_value = tree1.getChain("Segment 1","Segment 3",chain);
//Segment 1 and segment 3 are included but segment 1 is renamed.
Chain chain2;
exit_value = tree1.getChain("Segment 3","Segment 1",chain2);
//Segment 1 and segment 3 are included but segment 3 is renamed.

Kinematic Trees - KDL 1.1.x

KDL::Joint

Link to API

A Joint allows translation or rotation in one degree of freedom between two Segments

Creating Joints

Joint rx = Joint(Joint::RotX);//Rotational Joint about X
Joint ry = Joint(Joint::RotY);//Rotational Joint about Y
Joint rz = Joint(Joint::RotZ);//Rotational Joint about Z
Joint tx = Joint(Joint::TransX);//Translational Joint along X
Joint ty = Joint(Joint::TransY);//Translational Joint along Y
Joint tz = Joint(Joint::TransZ);//Translational Joint along Z
Joint fixed = Joint(Joint::None);//Rigid Connection
Note: See the API document for a full list of construction possibilities

Pose and twist of a Joint

Joint rx = Joint(Joint::RotX);
double q = M_PI/4;//Joint position
Frame f = rx.pose(q);
double qdot = 0.1;//Joint velocity
Twist t = rx.twist(qdot);
f is the pose resulting from moving the joint from its zero position to a joint value q t is the twist expressed in the frame corresponding to the zero position of the joint, resulting from applying a joint speed qdot

KDL::Segment

Link to API

A Segment is an ideal rigid body to which one single Joint is connected and one single tip frame. It contains:

  • a Joint located at the root frame of the Segment.
  • a Frame describing the pose between the end of the Joint and the tip frame of the Segment.

Creating Segments

Segment s = Segment(Joint(Joint::RotX),
                Frame(Rotation::RPY(0.0,M_PI/4,0.0),
                          Vector(0.1,0.2,0.3) )
                    );
Note: The constructor takes copies of the arguments, you cannot change the frame or joint afterwards!!!

Pose and twist of a Segment

double q=M_PI/2;//joint position
Frame f = s.pose(q);//s constructed as in previous example
double qdot=0.1;//joint velocity
Twist t = s.twist(q,qdot);
fis the pose resulting from moving the joint from its zero position to a joint value q and expresses the new tip frame wrt the root frame of the Segment s. t is the twist of the tip frame expressed in the root frame of the Segment s, resulting from applying a joint speed qdot at the joint value q

KDL::Chain

Link to API

A KDL::Chain is

  • a kinematic description of a serial chain of bodies connected by joints.
  • built out of KDL::Segments.

A Chain has

  • a default constructor, creating an empty chain without any segments.
  • a copy-constructor, creating a copy of an existing chain.
  • a =-operator is supported too.

Chain chain1;
Chain chain2(chain3);
Chain chain4 = chain5;

Chains are constructed by adding segments or existing chains to the end of the chain. All segments must have a different name (or "NoName"), otherwise the methods will return false and the segments will not be added. The functions add copies of the arguments, not the arguments themselves!

bool exit_value;
bool exit_value = chain1.addSegment(segment1);
exit_value = chain1.addChain(chain2);

You can get the number of joints and number of segments (this is not always the same since a segment can have a Joint::None, which is not included in the number of joints):

unsigned int nj = chain1.getNrOfJoints();
unsigned int js = chain1.getNrOfSegments();

You can iterate over the segments of a chain by getting a reference to each successive segment. The method will return false if the index is out of bounds.

Segment segment3;
bool exit_value = chain1.getSegment(3, segment3);

You can also request a segment by name:

Segment segment3;
bool exit_value = chain1.getSegment("Segment 3", segment3);

The root and leaf segment can be requested, as well as all segments in the chain.

bool exit_value;
Segment root_segment;
Segment leaf_segment;
std::vector<Segment> segments;
exit_value = chain1.getRootSegment(root_segment);
exit_value = chain1.getLeafSegment(leaf_segment);
exit_value = chain1.getSegments(segments);

You can request a part of the chain between a certain root and a tip:

bool exit_value;
Chain part_chain;
 
exit_value = chain1.getChain_Including(1,3, part_chain);
exit_value = chain1.getChain_Including("Segment 1","Segment 3", part_chain);
//Segment 1 and Segment 3 are included in the new chain!
 
exit_value = chain1.getChain_Excluding(1,3, part_chain);
exit_value = chain1.getChain_Excluding("Segment 1","Segment 3", part_chain);
//Segment 1 is not included in the chain. Segment 3 is included in the chain.

There is a function to copy the chain up to a given segment number or segment name:

bool exit_value;
Chain chain_copy;
exit_value = chain1.copy(3, chain_copy);
exit_value = chain1.copy("Segment 3", chain_copy);
//Segment 3, 4,... are not included in the copy!

KDL::Tree

Link to API

A KDL::Tree is

  • a kinematic description of a tree of bodies connected by joints.
  • built out of KDL::Segments.

A Tree has

  • a constructor that creates an empty tree without any segments and with the given name as its root name. The root name will be "root" if no name is given.
  • a copy-constructor, creating a copy of an existing tree.
  • a =-operator.

Tree tree1;
Tree tree2("RootName");
Tree tree3(tree4);
Tree tree5 = tree6;

Trees are constructed by adding segments, existing chains or existing trees to a given hook name. The methods will return false if the given hook name is not in the tree. These functions add copies of the arguments, not the arguments themselves!

bool exit_value;
exit_value = tree1.addSegment(segment1,"root");
exit_value = tree1.addChain(chain1,"Segment 1");
exit_value = tree1.addTree(tree2,"root");

You can get the number of joints and number of segments (this is not always the same since a segment can have a Joint::None, which is not included in the number of joints):

unsigned int nj = tree1.getNrOfJoints();
unsigned int js = tree1.getNrOfSegments();

You can retrieve the root segment and the leaf segments:

bool exit_value;
std::map<std::string,TreeElement>::const_iterator root;
std::map<std::string,TreeElement> leafs;
exit_value = tree1.getRootSegment(root);
exit_value = tree1.getLeafSegments(leafs);

You can also retrieve a specific segment in a tree by its name:

std::map<std::string,TreeElement>::const_iterator segment3;
bool exit_value = tree1.getSegment("Segment 3",segment3);

You can retrieve the segments in the tree:

std::map<std::string,TreeElement> segments;
bool exit_value = tree1.getSegments(segments);

It is possible to request the chain in a tree between a certain root and a tip:

bool exit_value;
Chain chain;
exit_value = tree1.getChain("Segment 1","Segment 3",chain);
//Segment 1 and segment 3 are included but segment 1 is renamed.
Chain chain2;
exit_value = tree1.getChain("Segment 3","Segment 1",chain2);
//Segment 1 and segment 3 are included but segment 3 is renamed.

This chain can also be requested in a tree structure with the given root name ("root" if no name is given).

bool exit_value;
Tree tree;
exit_value = tree1.getChain("Segment 1","Segment 3",tree,"RootName");
Tree tree2;
exit_value = tree1.getChain("Segment 3","Segment 1",tree2,"RootName");

There is a function to copy a tree excluding some segments and all their decendants.

bool exit_value;
Tree tree_copy;
exit_value = tree1.copy("Segment 3", tree_copy);
//tree1 is copied up to segment 3 (excluding segment 3).
std::vector<std::string> vect;
vect.push_back("Segment 1");
vect.push_back("Segment 7");
exit_value = tree1.copy(vect,tree_copy);