Kinematic chains

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.
  • build out of KDL::Segments.

A Chain has a default constructor, creating an empty chain without any segments and a copy-constructor, creating a copy of an existing chain:

Chain chain1();
Chain chain2(chain3);

Chain are constructed by adding Segments or adding 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);