KDL Joint offsets do not work

Hi,

I have the feeling that the offsets in the joints of KDL kinematic chains do
not work. If I modify the forward kinematic chain example from
http://www.orocos.org/kdl/examples to define the chain like this

    //Definition of a kinematic chain & add segments to the chain
    KDL::Chain chain;
    chain.addSegment(Segment(Joint(Joint::RotZ, 1.0,
1.0),Frame(Vector(0.0,0.0,1.020))));
    chain.addSegment(Segment(Joint(Joint::RotX, 1.0,
2.0),Frame(Vector(0.0,0.0,0.480))));
    chain.addSegment(Segment(Joint(Joint::RotX, 1.0,
3.0),Frame(Vector(0.0,0.0,0.645))));
    chain.addSegment(Segment(Joint(Joint::RotZ, 1.0, 4.0)));
    chain.addSegment(Segment(Joint(Joint::RotX, 1.0,
5.0),Frame(Vector(0.0,0.0,0.120))));
    chain.addSegment(Segment(Joint(Joint::RotZ, 1.0, 6.0)));

and if I then enter the same joint positions as before, the result is
exactly the same. Shouldn?t it be different? I expected it to be as if I had
added 1 to the first joint position, 2 to the second one and so on. Did I
miss anything?

Thank you for your help!

Benjamin

Ruben Smits's picture

KDL Joint offsets do not work

Hi Benjamin,

On Thu, Aug 2, 2012 at 9:25 AM, Benjamin Bihler
<benjamin [dot] bihler [..] ...> wrote:
>
> Hi,
>
> I have the feeling that the offsets in the joints of KDL kinematic chains
> do
> not work. If I modify the forward kinematic chain example from
> http://www.orocos.org/kdl/examples to define the chain like this
>
> //Definition of a kinematic chain & add segments to the chain
> KDL::Chain chain;
> chain.addSegment(Segment(Joint(Joint::RotZ, 1.0,
> 1.0),Frame(Vector(0.0,0.0,1.020))));
> chain.addSegment(Segment(Joint(Joint::RotX, 1.0,
> 2.0),Frame(Vector(0.0,0.0,0.480))));
> chain.addSegment(Segment(Joint(Joint::RotX, 1.0,
> 3.0),Frame(Vector(0.0,0.0,0.645))));
> chain.addSegment(Segment(Joint(Joint::RotZ, 1.0, 4.0)));
> chain.addSegment(Segment(Joint(Joint::RotX, 1.0,
> 5.0),Frame(Vector(0.0,0.0,0.120))));
> chain.addSegment(Segment(Joint(Joint::RotZ, 1.0, 6.0)));
>
> and if I then enter the same joint positions as before, the result is
> exactly the same. Shouldn’t it be different? I expected it to be as if I
> had
> added 1 to the first joint position, 2 to the second one and so on. Did I
> miss anything?

>From looking at the code I do not see how this can happen. Can you
provide us all the code including the creation of both solvers and the
calls to the forward kinematics.

Ruben

> Thank you for your help!
>
>
> Benjamin
>
> --
> Orocos-Users mailing list
> Orocos-Users [..] ...
> http://lists.mech.kuleuven.be/mailman/listinfo/orocos-users

--
Ruben Smits, Phd
Chief Technology Officer
Intermodalics BVBA
+32479511786
www.intermodalics.eu

KDL Joint offsets do not work

Hi Ruben,

> From looking at the code I do not see how this can happen. Can you provide
us all the code including the creation of both solvers and the calls to the
forward kinematics.

This is my main.cpp:

#include <chain.hp

#include <chainfksolver.hp

#include <chainfksolverpos_recursive.hp

#include <frames_io.hp

#include <stdio.h>
#include <iostream>

using namespace KDL;

void solve( KDL::Chain& chain )
{
// Create solver based on kinematic chain
ChainFkSolverPos_recursive fksolver = ChainFkSolverPos_recursive(chain);

// Create joint array
unsigned int nj = chain.getNrOfJoints();
KDL::JntArray jointpositions = JntArray(nj);

// Assign some values to the joint positions
for(unsigned int i=0;i<nj;i++){
jointpositions(i)=(double)i;
}

// Create the frame that will contain the results
KDL::Frame cartpos;

// Calculate forward position kinematics
bool kinematics_status;
kinematics_status = fksolver.JntToCart(jointpositions,cartpos);
if(kinematics_status>=0){
std::cout << cartpos <<std::endl;
printf("%s \n","Succes, thanks KDL!");
}else{
printf("%s \n","Error: could not calculate forward kinematics :(");
}
}

int main( int argc, char** argv )
{
//Definition of a kinematic chain & add segments to the chain
KDL::Chain chain;

chain.addSegment(Segment(Joint(Joint::RotZ),Frame(Vector(0.0,0.0,1.020))));

chain.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.480))));

chain.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.645))));
chain.addSegment(Segment(Joint(Joint::RotZ)));

chain.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.120))));
chain.addSegment(Segment(Joint(Joint::RotZ)));

std::cout << std::endl << "Chain without offsets:" << std::endl;
solve(chain);

//Definition of a kinematic chain & add segments to the chain
KDL::Chain chain2;
chain2.addSegment(Segment(Joint(Joint::RotZ, 1.0,
1.0),Frame(Vector(0.0,0.0,1.020))));
chain2.addSegment(Segment(Joint(Joint::RotX, 1.0,
2.0),Frame(Vector(0.0,0.0,0.480))));
chain2.addSegment(Segment(Joint(Joint::RotX, 1.0,
3.0),Frame(Vector(0.0,0.0,0.645))));
chain2.addSegment(Segment(Joint(Joint::RotZ, 1.0, 4.0)));
chain2.addSegment(Segment(Joint(Joint::RotX, 1.0,
5.0),Frame(Vector(0.0,0.0,0.120))));
chain2.addSegment(Segment(Joint(Joint::RotZ, 1.0, 6.0)));

std::cout << std::endl << "Chain with offsets:" << std::endl;
solve(chain2);
}

The output is

Chain without offsets:
[[ -0.369277, -0.923162, -0.1068;
0.472269, -0.285396, 0.833973;
-0.800373, 0.257528, 0.541371]
[ -0.012816, -0.394852, 0.705764]]
Succes, thanks KDL!

Chain with offsets:
[[ -0.369277, -0.923162, -0.1068;
0.472269, -0.285396, 0.833973;
-0.800373, 0.257528, 0.541371]
[ -0.012816, -0.394852, 0.705764]]
Succes, thanks KDL!

I am using Orocos KDL revision 3d6b7c225cb7 from the repository (created by
you with the comment "cmake: make sure PyKDL gets intalled in the right
directory, not super robust though") and g++ 4.6.2 with MinGW, but the
effect was the same when I tried VC 2008 Express.

Thank you for your answer!

Bye,
Benjamin

>

KDL Joint offsets do not work

Hello,

may I ask again: does anyone use the KDL joint offsets (i.e. define offsets
different from zero) in combination with forward/inverse kinematics solvers?
As far as I understand their definition, the results should change if I set
offsets during the definition of the kinematic chain. But this is not the
case here.

I have debugged into the KDL::Joint::pose method and the offsets there are
definitely different from zero. Therefore why do I get exactly the same
results as if the offsets were zero?

Thank you very much for any help,

Benjamin Bihler

Ruben Smits's picture

KDL Joint offsets do not work

Hi Benjamin,

On Fri, Aug 17, 2012 at 7:00 AM, Benjamin Bihler
<benjamin [dot] bihler [..] ...> wrote:
> Hi Ruben,
>
> did you find time to look at my example. Does it show the same behavior on
> your system? Thanks!

I have found some time to look at it, and I can confirm that this is a
bug. I think I have an idea where it comes from (segment.cpp,
calculation of f_tip at construction time) But I have not found a
solution for it yet.

> Bye,
> Benjamin

Ruben

>
> -----Ursprüngliche Nachricht-----
> Von: ruben [dot] smits [..] ... [mailto:ruben [dot] smits [..] ...]
> Im Auftrag von Ruben Smits
> Gesendet: Dienstag, 14. August 2012 11:45
> An: Benjamin Bihler
> Cc: orocos-users [..] ...
> Betreff: Re: [Orocos-users] KDL Joint offsets do not work
>
> Hi Benjamin,
>
> On Thu, Aug 2, 2012 at 9:25 AM, Benjamin Bihler
> <benjamin [dot] bihler [..] ...> wrote:
>>
>> Hi,
>>
>> I have the feeling that the offsets in the joints of KDL kinematic
>> chains do not work. If I modify the forward kinematic chain example
>> from http://www.orocos.org/kdl/examples to define the chain like this
>>
>> //Definition of a kinematic chain & add segments to the chain
>> KDL::Chain chain;
>> chain.addSegment(Segment(Joint(Joint::RotZ, 1.0,
>> 1.0),Frame(Vector(0.0,0.0,1.020))));
>> chain.addSegment(Segment(Joint(Joint::RotX, 1.0,
>> 2.0),Frame(Vector(0.0,0.0,0.480))));
>> chain.addSegment(Segment(Joint(Joint::RotX, 1.0,
>> 3.0),Frame(Vector(0.0,0.0,0.645))));
>> chain.addSegment(Segment(Joint(Joint::RotZ, 1.0, 4.0)));
>> chain.addSegment(Segment(Joint(Joint::RotX, 1.0,
>> 5.0),Frame(Vector(0.0,0.0,0.120))));
>> chain.addSegment(Segment(Joint(Joint::RotZ, 1.0, 6.0)));
>>
>> and if I then enter the same joint positions as before, the result is
>> exactly the same. Shouldn’t it be different? I expected it to be as if
>> I had added 1 to the first joint position, 2 to the second one and so
>> on. Did I miss anything?
>
> From looking at the code I do not see how this can happen. Can you provide
> us all the code including the creation of both solvers and the calls to the
> forward kinematics.
>
>
> Ruben
>
>> Thank you for your help!
>>
>>
>> Benjamin
>>
>> --
>> Orocos-Users mailing list
>> Orocos-Users [..] ...
>> http://lists.mech.kuleuven.be/mailman/listinfo/orocos-users
>
>
>
>
> --
> Ruben Smits, Phd
> Chief Technology Officer
> Intermodalics BVBA
> +32479511786
> www.intermodalics.eu
>

KDL Joint offsets do not work

On Aug 14, 2012, at 03:23 , Benjamin Bihler wrote:

> Hello,
>
> may I ask again: does anyone use the KDL joint offsets (i.e. define offsets different from zero) in combination with forward/inverse kinematics solvers? As far as I understand their definition, the results should change if I set offsets during the definition of the kinematic chain. But this is not the case here.
>
> I have debugged into the KDL::Joint::pose method and the offsets there are definitely different from zero. Therefore why do I get exactly the same results as if the offsets were zero?

Do you have a test case you can provide us, that demonstrates this?
S

KDL Joint offsets do not work

On Aug 14, 2012, at 12:40, S Roderick <kiwi [dot] net [..] ...> wrote:

>Do you have a test case you can provide us, that demonstrates this?

Please see my reply to Ruben Smits in the other thread (sorry for asking the
question in two threads).

Benjamin