[ros-users] IK with KDL

Ruben Smits ruben.smits at mech.kuleuven.be
Mon Nov 15 10:13:51 UTC 2010


On Thursday 11 November 2010 11:52:06 Jeroen Willems wrote:
> On 2010-11-09 09:27, Herman Bruyninckx wrote:
> > On Tue, 9 Nov 2010, Jeroen Willems wrote:
> > > I have a question regarding the inverse kinematics using KDL.
> > > 
> > > I would like to use carttojnt of the inverse kinematics solver.
> > > The problem is I have to use a destination frame as input.
> > > I'm using something similar to a elbow manipulator so you can imagine I
> > > only want a reference position. The arm only can have 2 poses to a
> > > reference position, to get the rotational part of the frame I actually
> > > have to get the joint positions to calculate it (correct me if I'm
> > > wrong).
> > > 
> > > So
> > > 1. Am I right?
> > > 2. Could I use KDL to compute the IK or should I use an analytic
> > > solution?
> > 
> > The major issue with your problem is that "IK" does not make too much
> > sense for a 2DOF system: when you don't take precautions the input frame
> > will never lie in the span of your 2DOF, so you will have make a
> > "projection" from the full 6D space onto your 2D subspace. KDL has
> > algorithms to do that, but they make choices about how to project that
> > might not correspond to your intuition. But that's inevitable.
> > 
> > So, please try to formulate exactly what kind of input you would like or
> > need to have.
> > 
> > Herman
> > _______________________________________________
> > ros-users mailing list
> > ros-users at code.ros.org<mailto:ros-users at code.ros.org>
> > https://code.ros.org/mailman/listinfo/ros-users
> 
> Thanks for the response.
> 
> Okay to be more precise to give a better idea of what I'm doing.
> I have an hexapod, so a torso with 6 legs consisting of 3 links (without
> torso) and 3 joints. I want to be the tip/foot on an specific point
> (x,y,z) in respect to the torso (thorax) so I have to know the three joint
> positions to get there.
> 
> So preferable without giving a rotation. So I'm really curious how to
> obtain this or how to use a "projection".

There is a inverse (CartToJnt) velocity solver in KDL that you can use to 
disable (or weigth)  some of the degrees of freedom in the cartesian space:

http://people.mech.kuleuven.be/~orocos/pub/devel/kdl/latest/api/html/classKDL_1_1ChainIkSolverVel__wdls.html

You can use the setWeightTS function for this. Setting a diagonal value of 
zero disables the joint, every other value neq 0 will be used as a weighting 
value.

So if you want to disable the rotations, just set the last three diagonal 
values to 0.

You can then use this solver in one of the inverse position solvers, but the 
problem is that we do not have a solver yet that can take these weights into 
account. But I do not think it should be to hard to figure that out yourself 
when starting from the code of the iterative solver for the inverse position 
kinematics:

http://people.mech.kuleuven.be/~orocos/pub/devel/kdl/latest/api/html/classKDL_1_1ChainIkSolverPos__NR.html


Ruben



More information about the ros-users mailing list