Skeleton of a serial robot arm with six revolute joints. This is one example of a kinematic structure, reducing the motion modelling and specification to a geometric problem of relative motion of reference frames. The Kinematics and Dynamics Library (KDL) develops an application independent framework for modelling and computation of kinematic chains, such as robots, biomechanical human models, computer-animated figures, machine tools, etc. It provides class libraries for geometrical objects (point, frame, line,... ), kinematic chains of various families (serial, humanoid, parallel, mobile,... ), and their motion specification and interpolation.
This document is not ready yet, but it's a wiki page so feel free to contribute
There are different ways for getting the software.
Orocos KDL is part of the geometry stack in the ROS distributions pre-Electric.
Since ROS Electric it is available stand-alone as the orocos-kinematics-dynamics stack.
git clone https://github.com/orocos/orocos_kinematics_dynamics.git
mkdir <kdl-dir>/build ; cd <kdl-dir>/build
ccmake ..
make;make check;make install
http://github.com/orocos-toolchain/rtt_geometryand build&install it using the provided Makefile (uses defaults) or CMakeLists.txt (if you want to modify paths).
Import the kdl_typekit in Orocos by using the 'import' Deployment command in the TaskBrowser or the 'Import' Deployment property in your deployment xml file:
import("kdl_typekit")
.types
var KDL.Frame z
z.p.X=1
or z.M.X_x=2
z.p = KDL.Vector(1,2,3)
z.M=KDL.Rotation(0,1.57,0)
(roll, pitch, yaw angles???)z
A Vector is a 3x1 matrix containing X-Y-Z coordinate values. It is used for representing: 3D position of a point wrt a reference frame, rotational and translational part of a 6D motion or force entity : <equation id="vector">$\textrm{KDL::Vector} = \left[ \begin{array}{ccc} x \\ y \\ z \end{array}\right]$<equation>
Vector v1; //The default constructor, X-Y-Z are initialized to zero Vector v2(x,y,z); //X-Y-Z are initialized with the given values Vector v3(v2); //The copy constructor Vector v4 = Vector::Zero(); //All values are set to zero
The operators [ ] and ( ) use indices from 0..2, index checking is enabled/disabled by the DEBUG/NDEBUG definitions:
v1[0]=v2[1];//copy y value of v2 to x value of v1 v2(1)=v3(3);//copy z value of v3 to y value of v2 v3.x( v4.y() );//copy y value of v4 to x value of v3
You can multiply or divide a Vector with a double using the operator * and /:
v2=2*v1; v3=v1/2;
v2+=v1; v3-=v1; v4=v1+v2; v5=v2-v3;
v3=v1*v2; //Cross product double a=dot(v1,v2)//Scalar product
You can reset the values of a vector to zero:
SetToZero(v1);
v1==v2; v2!=v3; Equal(v3,v4,eps);//with accuracy eps
A Rotation is the 3x3 matrix that represents the 3D rotation of an object wrt the reference frame.
<equation id="rotation">$ \textrm{KDL::Rotation} = \left[\begin{array}{ccc}Xx&Yx&Zx\\Xy&Yy&Zy\\Xz&Yz&Zz\end{array}\right] $<equation>
The following result always in consistent Rotations. This means the rows/columns are always normalized and orthogonal:
Rotation r1; //The default constructor, initializes to an 3x3 identity matrix Rotation r1 = Rotation::Identity();//Identity Rotation = zero rotation Rotation r2 = Rotation::RPY(roll,pitch,yaw); //Rotation built from Roll-Pitch-Yaw angles Rotation r3 = Rotation::EulerZYZ(alpha,beta,gamma); //Rotation built from Euler Z-Y-Z angles Rotation r4 = Rotation::EulerZYX(alpha,beta,gamma); //Rotation built from Euler Z-Y-X angles Rotation r5 = Rotation::Rot(vector,angle); //Rotation built from an equivalent axis(vector) and an angle.
The following should be used with care, they can result in inconsistent rotation matrices, since there is no checking if columns/rows are normalized or orthogonal
Rotation r6( Xx,Yx,Zx,Xy,Yy,Zy,Xz,Yz,Zz);//Give each individual element (Column-Major) Rotation r7(vectorX,vectorY,vectorZ);//Give each individual column
Individual values, the indices go from 0..2:
double Zx = r1(0,2);
r1.GetEulerZYZ(alpha,beta,gamma); r1.GetEulerZYX(alpha,beta,gamma); r1.GetRPY(roll,pitch,yaw); axis = r1.GetRot();//gives only rotation axis angle = r1.GetRotAngle(axis);//gives both angle and rotation axis
vecX=r1.UnitX();//or r1.UnitX(vecX); vecY=r1.UnitY();//or r1.UnitY(vecY); vecZ=r1.UnitZ();//or r1.UnitZ(vecZ);
Replacing a rotation by its inverse:
r1.SetInverse();//r1 is inverted and overwritten
r2=r1.Inverse();//r2 is the inverse rotation of r1
Compose two rotations to a new rotation, the order of the rotations is important:
r3=r1*r2;
r1.DoRotX(angle); r2.DoRotY(angle); r3.DoRotZ(angle);
r1 = r1*Rotation::RotX(angle)
v2=r1*v1;
r1==r2; r1!=r2; Equal(r1,r2,eps);
A Frame is the 4x4 matrix that represents the pose of an object/frame wrt a reference frame. It contains:
<equation id="frame">$ \textrm{KDL::Frame} = \left[\begin{array}{cc}\mathbf{M}(3 \times 3) &p(3 \times 1)\\ 0(1 \times 3)&1 \end{array}\right] $<equation>
Frame f1;//Creates Identity frame Frame f1=Frame::Identity();//Creates an identity frame: Rotation::Identity() and Vector::Zero() Frame f2(your_rotation);//Create a frame with your_rotation and a zero vector Frame f3(your_vector);//Create a frame with your_vector and a identity rotation Frame f4(your_rotation,your_vector);//Create a frame with your_rotation Frame f5(your_vector,your_rotation);//and your_vector Frame f5(f6);//the copy constructor
double x = f1(0,3); double Yy = f1(1,1);
Vector p = f1.p; Rotation M = f1.M;
Frame F_A_C = F_A_B * F_B_C;
Replacing a frame by its inverse:
//not yet implemented
f2=f1.Inverse();//f2 is the inverse of f1
f1==f2; f1!=f2; Equal(f1,f2,eps);
A Twist is the 6x1 matrix that represents the velocity of a Frame using a 3D translational velocity Vector vel and a 3D angular velocity Vector rot:
<equation id="twist">$\textrm{KDL::Twist} = \left[\begin{array}{c} v_x\\v_y\\v_z\\ \hline \omega_x \\ \omega_y \\ \omega_z \end{array} \right] = \left[\begin{array}{c} \textrm{vel} \\ \hline \textrm{rot}\end{array} \right] $<equation>
Twist t1; //Default constructor, initializes both vel and rot to Zero Twist t2(vel,rot);//Vector vel, and Vector rot Twist t3 = Twist::Zero();//Zero twist
Using the operators [ ] and ( ), the indices from 0..2 return the elements of vel, the indices from 3..5 return the elements of rot:
double vx = t1(0); double omega_y = t1[4]; t1(1) = vy; t1[5] = omega_z;
double vx = t1.vel.x();//or vx = t1.vel(0); double omega_y = t1.rot.y();//or omega_y = t1.rot(1); t1.vel.y(v_y);//or t1.vel(1)=v_y; //etc
t2=2*t1; t2=t1*2; t2=t1/2;
t1+=t2; t1-=t2; t3=t1+t2; t3=t1-t2;
t1==t2; t1!=t2; Equal(t1,t2,eps);
A Wrench is the 6x1 matrix that represents a force on a Frame using a 3D translational force Vector force and a 3D moment Vector torque:
<equation id="wrench">$\textrm{KDL::Wrench} = \left[\begin{array}{c} f_x\\f_y\\f_z\\ \hline t_x \\ t_y \\ t_z \end{array} \right] = \left[\begin{array}{c} \textrm{force} \\ \hline \textrm{torque}\end{array} \right] $<equation>
Wrench w1; //Default constructor, initializes force and torque to Zero Wrench w2(force,torque);//Vector force, and Vector torque Wrench w3 = Wrench::Zero();//Zero wrench
Using the operators [ ] and ( ), the indices from 0..2 return the elements of force, the indices from 3..5 return the elements of torque:
double fx = w1(0); double ty = w1[4]; w1(1) = fy; w1[5] = tz;
double fx = w1.force.x();//or fx = w1.force(0); double ty = w1.torque.y();//or ty = w1.torque(1); w1.force.y(fy);//or w1.force(1)=fy;//etc
w2=2*w1; w2=w1*2; w2=w1/2;
w1+=w2; w1-=w2; w3=w1+w2; w3=w1-w2;
w1==w2; w1!=w2; Equal(w1,w2,eps);
The values of a Wrench or Twist change if the reference frame or reference point is changed.
t2 = t1.RefPoint(v_old_new); w2 = w1.RefPoint(v_old_new);
ta = R_AB*tb; wa = R_AB*wb;
Note: This operation seems to multiply a 3x3 matrix R_AB with 6x1 matrices tb or wb, while in reality it uses the 6x6 Screw transformation matrix derived from R_AB.
ta = F_AB*tb; wa = F_AB*wb;
Note: This operation seems to multiply a 4x4 matrix F_AB with 6x1 matrices tb or wb, while in reality it uses the 6x6 Screw transformation matrix derived from F_AB.
t = diff(F_w_A,F_w_B,timestep)//differentiation F_w_B = F_w_A.addDelta(t,timestep)//integration
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.
Select your revision: (1.0.x is the released version, 1.1.x is under discussion (see kinfam_refactored git branch))
A Joint allows translation or rotation in one degree of freedom between two Segments
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
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);
A Segment is an ideal rigid body to which one single Joint is connected and one single tip frame. It contains:
Segment s = Segment(Joint(Joint::RotX), Frame(Rotation::RPY(0.0,M_PI/4,0.0), Vector(0.1,0.2,0.3) ) );
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);
A KDL::Chain is
A Chain has
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);
A KDL::Tree is
A Tree has
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.
A Joint allows translation or rotation in one degree of freedom between two Segments
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
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);
A Segment is an ideal rigid body to which one single Joint is connected and one single tip frame. It contains:
Segment s = Segment(Joint(Joint::RotX), Frame(Rotation::RPY(0.0,M_PI/4,0.0), Vector(0.1,0.2,0.3) ) );
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);
A KDL::Chain is
A Chain has
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!
A KDL::Tree is
A Tree has
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);
KDL contains for the moment only generic solvers for kinematic chains. They can be used (with care) for every KDL::Chain.
The idea behind the generic solvers is to have a uniform API. We do this by inheriting from the abstract classes for each type of solver:
A seperate solver has to be created for each chain. At construction time, it will allocate all necessary resources.
A specific type of solver can add some solver-specific functions/parameters to the interface, but still has to use the generic interface for it's main solving purpose.
The forward kinematics use the function JntToCart(...) to calculate the Cartesian space values from the Joint space values. The inverse kinematics use the function CartToJnt(...) to calculate the Joint space values from the Cartesian space values.
It recursively adds the poses/velocity of the successive segments, going from the first to the last segment, you can also get intermediate results by giving a Segment number:
ChainFkSolverPos_recursive fksolver(chain1); JntArray q(chain1.getNrOfJoints); q=... Frame F_result; fksolver.JntToCart(q,F_result,segment_nr);