KDL algorithm details

All,

I'm new to Orocos and am considering use of KDL, however, I've worked
through much of the documentation and have been unable to determine the
algorithms used. For example, I'm trying to determine what inverse
kinematics algorithm is used. Somewhere in the docs I saw it described as
an "iterative" method. I'd like to know which one as they all have their
strengths and weaknesses. There doesn't appear to be any information on
this topic in the group's listserv archive as well.

Are there any resources available that can elaborate on the algorithms
implemented in KDL? A list of papers or books would be best so users can
clearly understand what the library is offering.

Thanks,

Joe

KDL algorithm details

On 10/25/2012 01:39 PM, Joe Hays wrote:
> All,
>
> I'm new to Orocos and am considering use of KDL, however, I've worked
> through much of the documentation and have been unable to determine the
> algorithms used. For example, I'm trying to determine what inverse
> kinematics algorithm is used.
To what type of inverse kinematics are you referring ?

Inverse velocity kinematics ?

For what purpose do you want to use the kinematics ?

Somewhere in the docs I saw it described
> as an "iterative" method. I'd like to know which one as they all have
> their strengths and weaknesses. There doesn't appear to be any
> information on this topic in the group's listserv archive as well.
>
> Are there any resources available that can elaborate on the algorithms
> implemented in KDL? A list of papers or books would be best so users can
> clearly understand what the library is offering.
>
> Thanks,
>
> Joe
>
>

KDL algorithm details

The question is general. As a perspective user, I'd like to be able to have
insight to the algorithms behind any library I am considering. Educate the
user and then let them decide if it fits for their application or not.
Today's needs may not be tomorrows needs. My $.02.

Having said that, my current needs are to see if KDL's inverse kinematics
can provide a redundant spacial serial manipulator's complete joint
trajectory (position, velocity and acceleration) when given a trajectory of
the end-effector in Cartesian space (6D in my case). Looking at the KDL API
it appears that only the positions are returned from the algorithm. Is this
because of an API definition? Or, because of the selected algorithm?

I'd like to see if KDL can generate the needed joint position, velocity,
and acceleration inputs for a computed torque controller. I can always
differentiate the positions twice but that isn't necessarily the wisest
approach when other algorithms can provide them for you.

Joe

On Thu, Oct 25, 2012 at 7:44 AM, Erwin Aertbelien <
Erwin [dot] Aertbelien [..] ...> wrote:

> On 10/25/2012 01:39 PM, Joe Hays wrote:
>
>> All,
>>
>> I'm new to Orocos and am considering use of KDL, however, I've worked
>> through much of the documentation and have been unable to determine the
>> algorithms used. For example, I'm trying to determine what inverse
>> kinematics algorithm is used.
>>
> To what type of inverse kinematics are you referring ?
>
> Inverse velocity kinematics ?
>
> For what purpose do you want to use the kinematics ?
>
>
>
> Somewhere in the docs I saw it described
>
>> as an "iterative" method. I'd like to know which one as they all have
>> their strengths and weaknesses. There doesn't appear to be any
>> information on this topic in the group's listserv archive as well.
>>
>> Are there any resources available that can elaborate on the algorithms
>> implemented in KDL? A list of papers or books would be best so users can
>> clearly understand what the library is offering.
>>
>> Thanks,
>>
>> Joe
>>
>>
>>
>

KDL algorithm details

On 10/25/2012 02:04 PM, Joe Hays wrote:
> The question is general. As a perspective user, I'd like to be able to
> have insight to the algorithms behind any library I am considering.
> Educate the user and then let them decide if it fits for their
> application or not. Today's needs may not be tomorrows needs. My $.02.

In theory, this sounds fine, in practice, it is good to know what we are
talking about.

>
> Having said that, my current needs are to see if KDL's inverse
> kinematics can provide a redundant spacial serial manipulator's complete
> joint trajectory (position, velocity and acceleration) when given a
> trajectory of the end-effector in Cartesian space (6D in my case).

This is a not completely determined problem, and in order to solve the
redundant kinematics, you have to implicitly or explicitly assume
other optimisation criteria to solve it.

As it is, KDL offers basic computational classes that can be used
to solve the kinematics in this case.
One way to solve this problem is to use one of the inverse velocity
kinematic solvers ( chainiksolvervel_xxxx ) and to integrate
the results to position.
(i.e. "resolved motion rate control")

> Looking at the KDL API it appears that only the positions are returned
> from the algorithm. Is this because of an API definition? Or, because of
> the selected algorithm?
>
> I'd like to see if KDL can generate the needed joint position, velocity,
> and acceleration inputs for a computed torque controller. I can always
> differentiate the positions twice but that isn't necessarily the wisest
> approach when other algorithms can provide them for you.
Oh... This makes the answer above only partially relevant.
( you see: it really depends on the use case...)

For the moment, we do not have inverse acceleration kinematics in KDL,
which is what you would do in these instances.

There are inverse dynamics algorithm in KDL ( on of them implemented by
Azamat, included in CC). But what you'll need, it probably depends on
the exact computed torque control scheme that you choose.

Note that starting from a fully specified Cartesian path is not always
recommended. Often, to perform a robot task, only some contraints
need to be specified, and not the whole Cartesian path of the end
effector. Also, people want to have more control over how to optimize
the redundant degrees of freedom.
The iTasc framework ( http://www.orocos.org/wiki/orocos/itasc-wiki ) can
solve for such specifications. (built on top of other parts of Orocos,
such as RTT, KDL). Please note that this is tightly integrated
with Orocos-RTT ( and rFSM, ...)

>
> Joe
>
> On Thu, Oct 25, 2012 at 7:44 AM, Erwin Aertbelien
> <Erwin [dot] Aertbelien [..] ...
> <mailto:Erwin [dot] Aertbelien [..] ...>> wrote:
>
> On 10/25/2012 01:39 PM, Joe Hays wrote:
>
> All,
>
> I'm new to Orocos and am considering use of KDL, however, I've
> worked
> through much of the documentation and have been unable to
> determine the
> algorithms used. For example, I'm trying to determine what inverse
> kinematics algorithm is used.
>
> To what type of inverse kinematics are you referring ?
>
> Inverse velocity kinematics ?
>
> For what purpose do you want to use the kinematics ?
>
>
>
> Somewhere in the docs I saw it described
>
> as an "iterative" method. I'd like to know which one as they all
> have
> their strengths and weaknesses. There doesn't appear to be any
> information on this topic in the group's listserv archive as well.
>
> Are there any resources available that can elaborate on the
> algorithms
> implemented in KDL? A list of papers or books would be best so
> users can
> clearly understand what the library is offering.
>
> Thanks,
>
> Joe
>
>
>
>

KDL algorithm details

Erwin,

Thanks for this information and I'll take a look at iTasc.

Joe

On Thu, Oct 25, 2012 at 8:55 AM, Erwin Aertbelien <
Erwin [dot] Aertbelien [..] ...> wrote:

> On 10/25/2012 02:04 PM, Joe Hays wrote:
>
>> The question is general. As a perspective user, I'd like to be able to
>> have insight to the algorithms behind any library I am considering.
>> Educate the user and then let them decide if it fits for their
>> application or not. Today's needs may not be tomorrows needs. My $.02.
>>
>
> In theory, this sounds fine, in practice, it is good to know what we are
> talking about.
>
>
>
>> Having said that, my current needs are to see if KDL's inverse
>> kinematics can provide a redundant spacial serial manipulator's complete
>> joint trajectory (position, velocity and acceleration) when given a
>> trajectory of the end-effector in Cartesian space (6D in my case).
>>
>
> This is a not completely determined problem, and in order to solve the
> redundant kinematics, you have to implicitly or explicitly assume
> other optimisation criteria to solve it.
>
> As it is, KDL offers basic computational classes that can be used
> to solve the kinematics in this case.
> One way to solve this problem is to use one of the inverse velocity
> kinematic solvers ( chainiksolvervel_xxxx ) and to integrate
> the results to position.
> (i.e. "resolved motion rate control")
>
>
> Looking at the KDL API it appears that only the positions are returned
>> from the algorithm. Is this because of an API definition? Or, because of
>> the selected algorithm?
>>
>> I'd like to see if KDL can generate the needed joint position, velocity,
>> and acceleration inputs for a computed torque controller. I can always
>> differentiate the positions twice but that isn't necessarily the wisest
>> approach when other algorithms can provide them for you.
>>
> Oh... This makes the answer above only partially relevant.
> ( you see: it really depends on the use case...)
>
> For the moment, we do not have inverse acceleration kinematics in KDL,
> which is what you would do in these instances.
>
> There are inverse dynamics algorithm in KDL ( on of them implemented by
> Azamat, included in CC). But what you'll need, it probably depends on the
> exact computed torque control scheme that you choose.
>
> Note that starting from a fully specified Cartesian path is not always
> recommended. Often, to perform a robot task, only some contraints
> need to be specified, and not the whole Cartesian path of the end
> effector. Also, people want to have more control over how to optimize
> the redundant degrees of freedom.
> The iTasc framework ( http://www.orocos.org/wiki/**orocos/itasc-wiki<http://www.orocos.org/wik...) can solve for such specifications. (built on top of other parts of
> Orocos, such as RTT, KDL). Please note that this is tightly integrated
> with Orocos-RTT ( and rFSM, ...)
>
>
>
>> Joe
>>
>> On Thu, Oct 25, 2012 at 7:44 AM, Erwin Aertbelien
>> <Erwin.Aertbelien@mech.**kuleuven.be <Erwin [dot] Aertbelien [..] ...>
>> <mailto:Erwin.Aertbelien@mech.**kuleuven.be<Erwin [dot] Aertbelien [..] ...>>>
>> wrote:
>>
>> On 10/25/2012 01:39 PM, Joe Hays wrote:
>>
>> All,
>>
>> I'm new to Orocos and am considering use of KDL, however, I've
>> worked
>> through much of the documentation and have been unable to
>> determine the
>> algorithms used. For example, I'm trying to determine what inverse
>> kinematics algorithm is used.
>>
>> To what type of inverse kinematics are you referring ?
>>
>> Inverse velocity kinematics ?
>>
>> For what purpose do you want to use the kinematics ?
>>
>>
>>
>> Somewhere in the docs I saw it described
>>
>> as an "iterative" method. I'd like to know which one as they all
>> have
>> their strengths and weaknesses. There doesn't appear to be any
>> information on this topic in the group's listserv archive as well.
>>
>> Are there any resources available that can elaborate on the
>> algorithms
>> implemented in KDL? A list of papers or books would be best so
>> users can
>> clearly understand what the library is offering.
>>
>> Thanks,
>>
>> Joe
>>
>>
>>
>>
>>
>

KDL algorithm details

On Thu, 25 Oct 2012, Erwin Aertbelien wrote:

[...]
>> I'd like to see if KDL can generate the needed joint position, velocity,
>> and acceleration inputs for a computed torque controller. I can always
>> differentiate the positions twice but that isn't necessarily the wisest
>> approach when other algorithms can provide them for you.
> Oh... This makes the answer above only partially relevant.
> ( you see: it really depends on the use case...)
>
> For the moment, we do not have inverse acceleration kinematics in KDL,
> which is what you would do in these instances.
>
> There are inverse dynamics algorithm in KDL ( on of them implemented by
> Azamat, included in CC).

And that one computes joint accelerations (as a byproduct).

Herman

> But what you'll need, it probably depends on
> the exact computed torque control scheme that you choose.
>
> Note that starting from a fully specified Cartesian path is not always
> recommended. Often, to perform a robot task, only some contraints
> need to be specified, and not the whole Cartesian path of the end
> effector. Also, people want to have more control over how to optimize
> the redundant degrees of freedom.
> The iTasc framework ( http://www.orocos.org/wiki/orocos/itasc-wiki ) can
> solve for such specifications. (built on top of other parts of Orocos,
> such as RTT, KDL). Please note that this is tightly integrated
> with Orocos-RTT ( and rFSM, ...)
>
>
>>
>> Joe
>>
>> On Thu, Oct 25, 2012 at 7:44 AM, Erwin Aertbelien
>> <Erwin [dot] Aertbelien [..] ...
>> <mailto:Erwin [dot] Aertbelien [..] ...>> wrote:
>>
>> On 10/25/2012 01:39 PM, Joe Hays wrote:
>>
>> All,
>>
>> I'm new to Orocos and am considering use of KDL, however, I've
>> worked
>> through much of the documentation and have been unable to
>> determine the
>> algorithms used. For example, I'm trying to determine what inverse
>> kinematics algorithm is used.
>>
>> To what type of inverse kinematics are you referring ?
>>
>> Inverse velocity kinematics ?
>>
>> For what purpose do you want to use the kinematics ?
>>
>>
>>
>> Somewhere in the docs I saw it described
>>
>> as an "iterative" method. I'd like to know which one as they all
>> have
>> their strengths and weaknesses. There doesn't appear to be any
>> information on this topic in the group's listserv archive as well.
>>
>> Are there any resources available that can elaborate on the
>> algorithms
>> implemented in KDL? A list of papers or books would be best so
>> users can
>> clearly understand what the library is offering.
>>
>> Thanks,
>>
>> Joe
>>
>>
>>
>>
>