manipulator dynamics

Hi,

I am a new user to KDL. We are investigating the use of KDL for a personal robotics program being developed at the company I work for. I have some specific questions about some of the features in KDL that I was hoping some of the developers could answer.

(1) Can we do manipulator dynamics in KDL? I have poked around a little in the documentation but can't seem to find examples for this.

(2) How can we contribute code back? Can we submit patches that will be integrated into the code base?

(3) We were looking at computing the forward kinematics for intermediate link frames in addition to doing it for the end-effector so we can use this for collision checking. How can I access the intermediate frame poses?

Thank you,

Regards,
Sachin Chitta

Willow Garage Inc.
(http://www.willowgarage.com)

manipulator dynamics

> Ok, the api should not be reason to reject the patch. And it was not _my_
> main reason to reject it.
> The fact that it is doing dynamic memory allocation every calculation and
> the api uses a Vector* for the output torques where i would expect an array
> of joint torques (since they are 1D) .

ok, we already had a version without dynamic memory allocation, and
I'll change the output format. I also noticed that the code does not
take segments without a joint into account, so I'll update this as
well. I'll post the new patch!

Wim

ps. Is there an update on our previous discussion about Segments and
their reference frame?

manipulator dynamics

On Thu, 22 Jan 2009, Wim Meeussen wrote:

>> Ok, the api should not be reason to reject the patch. And it was not _my_
>> main reason to reject it.
>> The fact that it is doing dynamic memory allocation every calculation and
>> the api uses a Vector* for the output torques where i would expect an array
>> of joint torques (since they are 1D) .
>
> ok, we already had a version without dynamic memory allocation, and
> I'll change the output format. I also noticed that the code does not
> take segments without a joint into account, so I'll update this as
> well. I'll post the new patch!

Thanks!

>
> Wim
>
> ps. Is there an update on our previous discussion about Segments and
> their reference frame?
>
No, not that I can remember. I think the discussion stopped after we seemed
not to understand each other completely about what the real problem is...

Herman

manipulator dynamics

>> ps. Is there an update on our previous discussion about Segments and
>> their reference frame?

> No, not that I can remember. I think the discussion stopped after we seemed
> not to understand each other completely about what the real problem is...

I'm working on an additional joint class that should allow us to put
the segment reference frame at any place on a segment, without a
performance penalty. If everything works out, it should even work with
the existing solvers, and be able to co-exist with the existing joint
implementation.

Wim

manipulator dynamics

On Thu, 22 Jan 2009, Wim Meeussen wrote:

>>> ps. Is there an update on our previous discussion about Segments and
>>> their reference frame?
>
>> No, not that I can remember. I think the discussion stopped after we seemed
>> not to understand each other completely about what the real problem is...
>
> I'm working on an additional joint class that should allow us to put
> the segment reference frame at any place on a segment, without a
> performance penalty. If everything works out, it should even work with
> the existing solvers, and be able to co-exist with the existing joint
> implementation.
>
Amazing! The whole grale of robotics! :-)

Herman

manipulator dynamics

>> I'm working on an additional joint class that should allow us to put
>> the segment reference frame at any place on a segment, without a
>> performance penalty. If everything works out, it should even work with
>> the existing solvers, and be able to co-exist with the existing joint
>> implementation.

Here is the patch for the joints, plus a patch for the unit tests. It
seems to work for me, but could definitely use more thorough testing.

* it allows to choose a joint along an arbitrary axes, at an arbitrary origin,
* it allows to freely choose the reference frame of the segment
* it works with the current solvers
* it even runs a little faster than the current kdl implementation
* it just _adds_ a joint type, so the current joints can still be used.

Wim

Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

Ruben Smits's picture

manipulator dynamics

On Friday 23 January 2009 03:44:00 Wim Meeussen wrote:
> >> I'm working on an additional joint class that should allow us to put
> >> the segment reference frame at any place on a segment, without a
> >> performance penalty. If everything works out, it should even work with
> >> the existing solvers, and be able to co-exist with the existing joint
> >> implementation.
>
> Here is the patch for the joints, plus a patch for the unit tests. It
> seems to work for me, but could definitely use more thorough testing.
>
> * it allows to choose a joint along an arbitrary axes, at an arbitrary
> origin, * it allows to freely choose the reference frame of the segment
> * it works with the current solvers
> * it even runs a little faster than the current kdl implementation
> * it just _adds_ a joint type, so the current joints can still be used.
>

I don't really like the solution, also the meaning of certain functions are
not clear to me anymore.

Some of my problems/thoughts

I think the location of the joint does not belong to the joint.

What is the meaning of the pose and twist functions of the Joint and Segment.

In the case of a segment with a reference frame that can be at any place, the
meaning of the pose function is not very clear to me.

What is the actual meaning of a segment, and should it actually contain a
joint?

Maybe the joint is not a member of segment, maybe it should be a member of the
chain class?

Maybe we need to rethink the complete design of the kinematic family?

A joint is just a joint, it holds only information about the type (and
dynamical parameters).
A segment is like a rigid body, maybe we should rename it to body or so, it
only holds the information of the Intertia, cog and a frame we are interested
in (f_tip now).

A chain is the interconnection of segments and joints.

If a joint is added to a chain, we should say to which body(segment) is is
connected and where the position of the joint connection point is in the
reference frame of the body.

If a body/segment is added to chain, we should say to which joint it is
attached, and where the joint is located in it's reference frame.

The forward position kinematics of a chain would calculate the pose between
the root/base of the chain and the interested frame (f_tip) of one of the
segments/bodies.

The forward velocity kinematics of a chain would calculate the twist of the
interested frame (f_tip) of one of the segments/bodies.

The jacobian calculation will express the relation between the joint velocity
values and the velocity of the interested frame of one of the segments/bodies.

Any comments?

Ruben

Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

manipulator dynamics

> Some of my problems/thoughts
>
> I think the location of the joint does not belong to the joint.
>
> What is the meaning of the pose and twist functions of the Joint and Segment.
>
> In the case of a segment with a reference frame that can be at any place, the
> meaning of the pose function is not very clear to me.
>
> What is the actual meaning of a segment, and should it actually contain a
> joint?
>
> Maybe the joint is not a member of segment, maybe it should be a member of the
> chain class?
>
> Maybe we need to rethink the complete design of the kinematic family?
>
> A joint is just a joint, it holds only information about the type (and
> dynamical parameters).
> A segment is like a rigid body, maybe we should rename it to body or so, it
> only holds the information of the Intertia, cog and a frame we are interested
> in (f_tip now).
>
> A chain is the interconnection of segments and joints.
>
> If a joint is added to a chain, we should say to which body(segment) is is
> connected and where the position of the joint connection point is in the
> reference frame of the body.
>
> If a body/segment is added to chain, we should say to which joint it is
> attached, and where the joint is located in it's reference frame.
>
> The forward position kinematics of a chain would calculate the pose between
> the root/base of the chain and the interested frame (f_tip) of one of the
> segments/bodies.
>
> The forward velocity kinematics of a chain would calculate the twist of the
> interested frame (f_tip) of one of the segments/bodies.
>
> The jacobian calculation will express the relation between the joint velocity
> values and the velocity of the interested frame of one of the segments/bodies.
>
> Any comments?

That's a lot of questions at once ;-)

We already have a separate class for a joint (Joint) and a body
(Inertia). Those two are combined in a Segment, which has exactly 1
joint and 1 body. The segment is a container class that specifies the
reference frame with respect to the reference frame of the previous
segment. The joint and the body are defined with respect to the
reference frame of the segment that contains them.

This is very close to the implementation we already have, with these changes:
* The Joint is defined with respect to the reference frame of the
segment that contains it, not with respect to the reference frame of
the previous segment. So the joint specifies its position and
orientation with respect to the reference frame.
* The Body (should we use this name instead of Inertia?) is also
defined with respect to the reference frame of the segment that
contains it. The Body specifies its mass, center of gravity, Ixx,...
with respect to the reference frame. So the position of the center of
gravity is part of the Body, and not part of the segment (as the
position of the joint is part of the joint, and not of the segment).
* I think we also don't need the 'no-joint' segments any more. (I
believe they were introduced because of the limitations of the
previous joint implementation, which forced you to put the segment
reference frame at the joint). With the number of joints always equal
to the number of bodies, it becomes easier to write and understand
solvers (now when solvers iterate over segments, they need to
implement a special case for segments without a joint), and we can
still represent any chain/tree.

As for some of your other questions:
* The 'pose(q)' function of a segment returns the pose of the segment,
with respect to its parent segment, when its joint is at 'q'.
* I think the current design of a chain/tree built from segments (with
the small above modifications) is very simple, and yet allows us to
represent any chain/tree. I very much like the simplicity of having
the same number of joints and bodies. If we would get rid of segments,
and start adding joints and bodies directly into chains/trees, we
would have to make our solvers more complex, while we don't gain
anything in what kind of mechanisms we can represent.
* As we discussed before, a segment should only have 1 reference
frame. A specific frame for each task does not belong in the segment.
Also, to make branching possible, we don't need multiple frames in a
segment; this is already made possible by having a joint at an
arbitrary position/orientation.

Wim

manipulator dynamics

On Sat, 31 Jan 2009, Wim Meeussen wrote:

>> Some of my problems/thoughts
>>
>> I think the location of the joint does not belong to the joint.
>>
>> What is the meaning of the pose and twist functions of the Joint and Segment.
>>
>> In the case of a segment with a reference frame that can be at any place, the
>> meaning of the pose function is not very clear to me.
>>
>> What is the actual meaning of a segment, and should it actually contain a
>> joint?
>>
>> Maybe the joint is not a member of segment, maybe it should be a member of the
>> chain class?
>>
>> Maybe we need to rethink the complete design of the kinematic family?
>>
>> A joint is just a joint, it holds only information about the type (and
>> dynamical parameters).
>> A segment is like a rigid body, maybe we should rename it to body or so, it
>> only holds the information of the Intertia, cog and a frame we are interested
>> in (f_tip now).
>>
>> A chain is the interconnection of segments and joints.
>>
>> If a joint is added to a chain, we should say to which body(segment) is is
>> connected and where the position of the joint connection point is in the
>> reference frame of the body.
>>
>> If a body/segment is added to chain, we should say to which joint it is
>> attached, and where the joint is located in it's reference frame.
>>
>> The forward position kinematics of a chain would calculate the pose between
>> the root/base of the chain and the interested frame (f_tip) of one of the
>> segments/bodies.
>>
>> The forward velocity kinematics of a chain would calculate the twist of the
>> interested frame (f_tip) of one of the segments/bodies.
>>
>> The jacobian calculation will express the relation between the joint velocity
>> values and the velocity of the interested frame of one of the segments/bodies.
>>
>> Any comments?
>
>
> That's a lot of questions at once ;-)
>
> We already have a separate class for a joint (Joint) and a body
> (Inertia). Those two are combined in a Segment, which has exactly 1
> joint and 1 body. The segment is a container class that specifies the
> reference frame with respect to the reference frame of the previous
> segment. The joint and the body are defined with respect to the
> reference frame of the segment that contains them.

I follow some of these statements, others not :-) The segment is indeed the
object that connects (rigid) bodies to joints, and hence it is natural that
it contains the frames that represent where things have to be connected.
However, a joint does not belong to a segment: it can at best belong to
_two_ segments, i.e., the ones that it connects. So, the segment is the
major concept to build kinematic chains with, ie the stuff that represents
how to connect bodies to joints (and nothing more!). The dynamical and
other properties of robot links and joints should go into dedicated
classes, which the segments can then connect.

It is absolutely necessary that a segment can "contain" (or rather: give
access to) more than one frame: not just in order to allow branching, but
also to connect "non-chain" objects, such as "task (frames)" or "sensor
(frames)". Probably, we have to think about "scene graph"-like ways to
connect such sensor/task/... frames to segments, without adding extra
frames to the segment class.

> This is very close to the implementation we already have, with these changes:
> * The Joint is defined with respect to the reference frame of the
> segment that contains it, not with respect to the reference frame of
> the previous segment. So the joint specifies its position and
> orientation with respect to the reference frame.

The frame on a segment (that is, on _each_ of the _two_ segments that a
joint connects) only says where a joint (or any other "non-chain" object,
see above) can be attached.

> * The Body (should we use this name instead of Inertia?) is also
Inertia is one property of a "Body", so this more generic name is ok;
Inertia will have multiple mathematical representations, that should not
matter for the meaning and the use of a "Body". A "Body" should also allow
other, "non-chain" connections to be made to it, such as shape. However, as
was discussed in some earlier thread, it is not a scalable idea to provide
hooks for all these possible extensions in the "Body" object. Unless that
class is pure virtual, and has many children that implement one particular
combination of possible connected properties...

> defined with respect to the reference frame of the segment that
> contains it.
As I argumented before: a joint is not _contained_ in any segment.

> The Body specifies its mass, center of gravity, Ixx,...
> with respect to the reference frame. So the position of the center of
> gravity is part of the Body, and not part of the segment
I agree.

> (as the
> position of the joint is part of the joint, and not of the segment).
Yes.

> * I think we also don't need the 'no-joint' segments any more. (I
> believe they were introduced because of the limitations of the
> previous joint implementation, which forced you to put the segment
> reference frame at the joint). With the number of joints always equal
> to the number of bodies, it becomes easier to write and understand
> solvers (now when solvers iterate over segments, they need to
> implement a special case for segments without a joint), and we can
> still represent any chain/tree.

Seems almost Ok: chains can have loops, and then the number of joints can
differ from the number of bodies.

> As for some of your other questions:
> * The 'pose(q)' function of a segment returns the pose of the segment,
> with respect to its parent segment, when its joint is at 'q'.

This is ok for joints that have one single real number 'q' as their state.
(Which covers most of the cases, but certainly not all, such as spherical
joints.)

> * I think the current design of a chain/tree built from segments (with
> the small above modifications) is very simple, and yet allows us to
> represent any chain/tree.

I will fight hard to also allow _graphs_ to be represented. Which can with
what you suggest, if you do not insist on the number of joints to be equal
to the number of segments :-)

> I very much like the simplicity of having
> the same number of joints and bodies.

This simplicity is too simple for the real world :-)

> If we would get rid of segments,
> and start adding joints and bodies directly into chains/trees, we
> would have to make our solvers more complex, while we don't gain
> anything in what kind of mechanisms we can represent.

> * As we discussed before, a segment should only have 1 reference
> frame. A specific frame for each task does not belong in the segment.

I should indeed go into a separate task/sensor/... object that can be
aggregated with the segment.

> Also, to make branching possible, we don't need multiple frames in a
> segment; this is already made possible by having a joint at an
> arbitrary position/orientation.

Your concept of "having a joint at an arbitrary" position is exactly
the same as having multiple frames to indicate where joints can be attached
to a segment! :-)

Herman

Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

manipulator dynamics

Can we --in parallel to this new redesign discussion-- also process
the patch to add an additional joint constructor? I attached it again,
and will be happy to discuss any technical issues.

Wim

On Mon, Feb 2, 2009 at 7:19 AM, Herman Bruyninckx
<Herman [dot] Bruyninckx [..] ...> wrote:
> On Sat, 31 Jan 2009, Wim Meeussen wrote:
>
>>> Some of my problems/thoughts
>>>
>>> I think the location of the joint does not belong to the joint.
>>>
>>> What is the meaning of the pose and twist functions of the Joint and
>>> Segment.
>>>
>>> In the case of a segment with a reference frame that can be at any place,
>>> the
>>> meaning of the pose function is not very clear to me.
>>>
>>> What is the actual meaning of a segment, and should it actually contain a
>>> joint?
>>>
>>> Maybe the joint is not a member of segment, maybe it should be a member
>>> of the
>>> chain class?
>>>
>>> Maybe we need to rethink the complete design of the kinematic family?
>>>
>>> A joint is just a joint, it holds only information about the type (and
>>> dynamical parameters).
>>> A segment is like a rigid body, maybe we should rename it to body or so,
>>> it
>>> only holds the information of the Intertia, cog and a frame we are
>>> interested
>>> in (f_tip now).
>>>
>>> A chain is the interconnection of segments and joints.
>>>
>>> If a joint is added to a chain, we should say to which body(segment) is
>>> is
>>> connected and where the position of the joint connection point is in the
>>> reference frame of the body.
>>>
>>> If a body/segment is added to chain, we should say to which joint it is
>>> attached, and where the joint is located in it's reference frame.
>>>
>>> The forward position kinematics of a chain would calculate the pose
>>> between
>>> the root/base of the chain and the interested frame (f_tip) of one of the
>>> segments/bodies.
>>>
>>> The forward velocity kinematics of a chain would calculate the twist of
>>> the
>>> interested frame (f_tip) of one of the segments/bodies.
>>>
>>> The jacobian calculation will express the relation between the joint
>>> velocity
>>> values and the velocity of the interested frame of one of the
>>> segments/bodies.
>>>
>>> Any comments?
>>
>>
>> That's a lot of questions at once ;-)
>>
>> We already have a separate class for a joint (Joint) and a body
>> (Inertia). Those two are combined in a Segment, which has exactly 1
>> joint and 1 body. The segment is a container class that specifies the
>> reference frame with respect to the reference frame of the previous
>> segment. The joint and the body are defined with respect to the
>> reference frame of the segment that contains them.
>
> I follow some of these statements, others not :-) The segment is indeed the
> object that connects (rigid) bodies to joints, and hence it is natural that
> it contains the frames that represent where things have to be connected.
> However, a joint does not belong to a segment: it can at best belong to
> _two_ segments, i.e., the ones that it connects. So, the segment is the
> major concept to build kinematic chains with, ie the stuff that represents
> how to connect bodies to joints (and nothing more!). The dynamical and
> other properties of robot links and joints should go into dedicated
> classes, which the segments can then connect.
>
> It is absolutely necessary that a segment can "contain" (or rather: give
> access to) more than one frame: not just in order to allow branching, but
> also to connect "non-chain" objects, such as "task (frames)" or "sensor
> (frames)". Probably, we have to think about "scene graph"-like ways to
> connect such sensor/task/... frames to segments, without adding extra
> frames to the segment class.
>
>> This is very close to the implementation we already have, with these
>> changes:
>> * The Joint is defined with respect to the reference frame of the
>> segment that contains it, not with respect to the reference frame of
>> the previous segment. So the joint specifies its position and
>> orientation with respect to the reference frame.
>
> The frame on a segment (that is, on _each_ of the _two_ segments that a
> joint connects) only says where a joint (or any other "non-chain" object,
> see above) can be attached.
>
>> * The Body (should we use this name instead of Inertia?) is also
>
> Inertia is one property of a "Body", so this more generic name is ok;
> Inertia will have multiple mathematical representations, that should not
> matter for the meaning and the use of a "Body". A "Body" should also allow
> other, "non-chain" connections to be made to it, such as shape. However, as
> was discussed in some earlier thread, it is not a scalable idea to provide
> hooks for all these possible extensions in the "Body" object. Unless that
> class is pure virtual, and has many children that implement one particular
> combination of possible connected properties...
>
>> defined with respect to the reference frame of the segment that
>> contains it.
>
> As I argumented before: a joint is not _contained_ in any segment.
>
>> The Body specifies its mass, center of gravity, Ixx,...
>> with respect to the reference frame. So the position of the center of
>> gravity is part of the Body, and not part of the segment
>
> I agree.
>
>> (as the
>> position of the joint is part of the joint, and not of the segment).
>
> Yes.
>
>> * I think we also don't need the 'no-joint' segments any more. (I
>> believe they were introduced because of the limitations of the
>> previous joint implementation, which forced you to put the segment
>> reference frame at the joint). With the number of joints always equal
>> to the number of bodies, it becomes easier to write and understand
>> solvers (now when solvers iterate over segments, they need to
>> implement a special case for segments without a joint), and we can
>> still represent any chain/tree.
>
> Seems almost Ok: chains can have loops, and then the number of joints can
> differ from the number of bodies.
>
>> As for some of your other questions:
>> * The 'pose(q)' function of a segment returns the pose of the segment,
>> with respect to its parent segment, when its joint is at 'q'.
>
> This is ok for joints that have one single real number 'q' as their state.
> (Which covers most of the cases, but certainly not all, such as spherical
> joints.)
>
>> * I think the current design of a chain/tree built from segments (with
>> the small above modifications) is very simple, and yet allows us to
>> represent any chain/tree.
>
> I will fight hard to also allow _graphs_ to be represented. Which can with
> what you suggest, if you do not insist on the number of joints to be equal
> to the number of segments :-)
>
>> I very much like the simplicity of having
>> the same number of joints and bodies.
>
> This simplicity is too simple for the real world :-)
>
>> If we would get rid of segments,
>> and start adding joints and bodies directly into chains/trees, we
>> would have to make our solvers more complex, while we don't gain
>> anything in what kind of mechanisms we can represent.
>
>> * As we discussed before, a segment should only have 1 reference
>> frame. A specific frame for each task does not belong in the segment.
>
> I should indeed go into a separate task/sensor/... object that can be
> aggregated with the segment.
>
>> Also, to make branching possible, we don't need multiple frames in a
>> segment; this is already made possible by having a joint at an
>> arbitrary position/orientation.
>
> Your concept of "having a joint at an arbitrary" position is exactly
> the same as having multiple frames to indicate where joints can be attached
> to a segment! :-)
>
> Herman
>
> Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm
>
>

Ruben Smits's picture

manipulator dynamics

On Monday 02 February 2009 22:00:12 Wim Meeussen wrote:
> Can we --in parallel to this new redesign discussion-- also process
> the patch to add an additional joint constructor? I attached it again,
> and will be happy to discuss any technical issues.

I'm still revising ;)

apart from the fact that I really do not like the design (joint owning its
position in the reference frame of the segment, which is owning the joint)

is there a reason why you do not use the Rotation::Rot or Rotation::Rot2
functions to calculate the rotation about a arbitrary axis? It would make the
code a lot cleaner.

Ruben

> Wim
>
>
>
> On Mon, Feb 2, 2009 at 7:19 AM, Herman Bruyninckx
>
> <Herman [dot] Bruyninckx [..] ...> wrote:
> > On Sat, 31 Jan 2009, Wim Meeussen wrote:
> >>> Some of my problems/thoughts
> >>>
> >>> I think the location of the joint does not belong to the joint.
> >>>
> >>> What is the meaning of the pose and twist functions of the Joint and
> >>> Segment.
> >>>
> >>> In the case of a segment with a reference frame that can be at any
> >>> place, the
> >>> meaning of the pose function is not very clear to me.
> >>>
> >>> What is the actual meaning of a segment, and should it actually contain
> >>> a joint?
> >>>
> >>> Maybe the joint is not a member of segment, maybe it should be a member
> >>> of the
> >>> chain class?
> >>>
> >>> Maybe we need to rethink the complete design of the kinematic family?
> >>>
> >>> A joint is just a joint, it holds only information about the type (and
> >>> dynamical parameters).
> >>> A segment is like a rigid body, maybe we should rename it to body or
> >>> so, it
> >>> only holds the information of the Intertia, cog and a frame we are
> >>> interested
> >>> in (f_tip now).
> >>>
> >>> A chain is the interconnection of segments and joints.
> >>>
> >>> If a joint is added to a chain, we should say to which body(segment) is
> >>> is
> >>> connected and where the position of the joint connection point is in
> >>> the reference frame of the body.
> >>>
> >>> If a body/segment is added to chain, we should say to which joint it is
> >>> attached, and where the joint is located in it's reference frame.
> >>>
> >>> The forward position kinematics of a chain would calculate the pose
> >>> between
> >>> the root/base of the chain and the interested frame (f_tip) of one of
> >>> the segments/bodies.
> >>>
> >>> The forward velocity kinematics of a chain would calculate the twist of
> >>> the
> >>> interested frame (f_tip) of one of the segments/bodies.
> >>>
> >>> The jacobian calculation will express the relation between the joint
> >>> velocity
> >>> values and the velocity of the interested frame of one of the
> >>> segments/bodies.
> >>>
> >>> Any comments?
> >>
> >> That's a lot of questions at once ;-)
> >>
> >> We already have a separate class for a joint (Joint) and a body
> >> (Inertia). Those two are combined in a Segment, which has exactly 1
> >> joint and 1 body. The segment is a container class that specifies the
> >> reference frame with respect to the reference frame of the previous
> >> segment. The joint and the body are defined with respect to the
> >> reference frame of the segment that contains them.
> >
> > I follow some of these statements, others not :-) The segment is indeed
> > the object that connects (rigid) bodies to joints, and hence it is
> > natural that it contains the frames that represent where things have to
> > be connected. However, a joint does not belong to a segment: it can at
> > best belong to _two_ segments, i.e., the ones that it connects. So, the
> > segment is the major concept to build kinematic chains with, ie the stuff
> > that represents how to connect bodies to joints (and nothing more!). The
> > dynamical and other properties of robot links and joints should go into
> > dedicated classes, which the segments can then connect.
> >
> > It is absolutely necessary that a segment can "contain" (or rather: give
> > access to) more than one frame: not just in order to allow branching, but
> > also to connect "non-chain" objects, such as "task (frames)" or "sensor
> > (frames)". Probably, we have to think about "scene graph"-like ways to
> > connect such sensor/task/... frames to segments, without adding extra
> > frames to the segment class.
> >
> >> This is very close to the implementation we already have, with these
> >> changes:
> >> * The Joint is defined with respect to the reference frame of the
> >> segment that contains it, not with respect to the reference frame of
> >> the previous segment. So the joint specifies its position and
> >> orientation with respect to the reference frame.
> >
> > The frame on a segment (that is, on _each_ of the _two_ segments that a
> > joint connects) only says where a joint (or any other "non-chain" object,
> > see above) can be attached.
> >
> >> * The Body (should we use this name instead of Inertia?) is also
> >
> > Inertia is one property of a "Body", so this more generic name is ok;
> > Inertia will have multiple mathematical representations, that should not
> > matter for the meaning and the use of a "Body". A "Body" should also
> > allow other, "non-chain" connections to be made to it, such as shape.
> > However, as was discussed in some earlier thread, it is not a scalable
> > idea to provide hooks for all these possible extensions in the "Body"
> > object. Unless that class is pure virtual, and has many children that
> > implement one particular combination of possible connected properties...
> >
> >> defined with respect to the reference frame of the segment that
> >> contains it.
> >
> > As I argumented before: a joint is not _contained_ in any segment.
> >
> >> The Body specifies its mass, center of gravity, Ixx,...
> >> with respect to the reference frame. So the position of the center of
> >> gravity is part of the Body, and not part of the segment
> >
> > I agree.
> >
> >> (as the
> >> position of the joint is part of the joint, and not of the segment).
> >
> > Yes.
> >
> >> * I think we also don't need the 'no-joint' segments any more. (I
> >> believe they were introduced because of the limitations of the
> >> previous joint implementation, which forced you to put the segment
> >> reference frame at the joint). With the number of joints always equal
> >> to the number of bodies, it becomes easier to write and understand
> >> solvers (now when solvers iterate over segments, they need to
> >> implement a special case for segments without a joint), and we can
> >> still represent any chain/tree.
> >
> > Seems almost Ok: chains can have loops, and then the number of joints can
> > differ from the number of bodies.
> >
> >> As for some of your other questions:
> >> * The 'pose(q)' function of a segment returns the pose of the segment,
> >> with respect to its parent segment, when its joint is at 'q'.
> >
> > This is ok for joints that have one single real number 'q' as their
> > state. (Which covers most of the cases, but certainly not all, such as
> > spherical joints.)
> >
> >> * I think the current design of a chain/tree built from segments (with
> >> the small above modifications) is very simple, and yet allows us to
> >> represent any chain/tree.
> >
> > I will fight hard to also allow _graphs_ to be represented. Which can
> > with what you suggest, if you do not insist on the number of joints to be
> > equal to the number of segments :-)
> >
> >> I very much like the simplicity of having
> >> the same number of joints and bodies.
> >
> > This simplicity is too simple for the real world :-)
> >
> >> If we would get rid of segments,
> >> and start adding joints and bodies directly into chains/trees, we
> >> would have to make our solvers more complex, while we don't gain
> >> anything in what kind of mechanisms we can represent.
> >>
> >> * As we discussed before, a segment should only have 1 reference
> >> frame. A specific frame for each task does not belong in the segment.
> >
> > I should indeed go into a separate task/sensor/... object that can be
> > aggregated with the segment.
> >
> >> Also, to make branching possible, we don't need multiple frames in a
> >> segment; this is already made possible by having a joint at an
> >> arbitrary position/orientation.
> >
> > Your concept of "having a joint at an arbitrary" position is exactly
> > the same as having multiple frames to indicate where joints can be
> > attached to a segment! :-)
> >
> > Herman
> >
> > Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

manipulator dynamics

On Wed, Feb 4, 2009 at 4:22 AM, Ruben Smits
<ruben [dot] smits [..] ...> wrote:
> On Monday 02 February 2009 22:00:12 Wim Meeussen wrote:
>> Can we --in parallel to this new redesign discussion-- also process
>> the patch to add an additional joint constructor? I attached it again,
>> and will be happy to discuss any technical issues.
>
> I'm still revising ;)
>
> apart from the fact that I really do not like the design (joint owning its
> position in the reference frame of the segment, which is owning the joint)

The joint axis is specified in the reference frame of the segment. So
when constructing the joint, you have to know which segment you
construct it for. So, one could argue that a joint should also know
its position with respect to this reference frame.

> is there a reason why you do not use the Rotation::Rot or Rotation::Rot2
> functions to calculate the rotation about a arbitrary axis? It would make the
> code a lot cleaner.

For efficiency reasons. The main difference is that Rotation::Rot
normalizes the rotation axis every time. This makes a big difference
in performance. We could
* choose to take the performance hit to get more compact code,
* opt for changing the Rotation::Rot implementation, or
* just keep the less compact implementation.

Wim

--
Wim Meeussen
Willow Garage Inc.
<http://www.willowgarage.com)
>

manipulator dynamics

On Wed, 4 Feb 2009, Wim Meeussen wrote:

> On Wed, Feb 4, 2009 at 4:22 AM, Ruben Smits
> <ruben [dot] smits [..] ...> wrote:
>> On Monday 02 February 2009 22:00:12 Wim Meeussen wrote:
>>> Can we --in parallel to this new redesign discussion-- also process
>>> the patch to add an additional joint constructor? I attached it again,
>>> and will be happy to discuss any technical issues.
>>
>> I'm still revising ;)
>>
>> apart from the fact that I really do not like the design (joint owning its
>> position in the reference frame of the segment, which is owning the joint)
>
> The joint axis is specified in the reference frame of the segment. So
> when constructing the joint, you have to know which segment you
> construct it for.

Wrong coupling...!

> So, one could argue that a joint should also know
> its position with respect to this reference frame.
I don't argue like that :-)

>> is there a reason why you do not use the Rotation::Rot or Rotation::Rot2
>> functions to calculate the rotation about a arbitrary axis? It would make the
>> code a lot cleaner.
>
> For efficiency reasons. The main difference is that Rotation::Rot
> normalizes the rotation axis every time. This makes a big difference
> in performance. We could
> * choose to take the performance hit to get more compact code,
> * opt for changing the Rotation::Rot implementation, or
> * just keep the less compact implementation.

What is the alternative to normalization? To let the orientation drift...
Such efficiency considerations _are_ important, but they should be hidden
in a specialised solver.

Thanks for your continuing effort to get these important issues sorted out!

Herman

manipulator dynamics

>> The joint axis is specified in the reference frame of the segment. So
>> when constructing the joint, you have to know which segment you
>> construct it for.
> Wrong coupling...!

>> So, one could argue that a joint should also know
>> its position with respect to this reference frame.
>
> I don't argue like that :-)

But you did argue like that in your last email:
"
>> The Body specifies its mass, center of gravity, Ixx,...
>> with respect to the reference frame. So the position of the center of
>> gravity is part of the Body, and not part of the segment
> I agree.

>> (as the position of the joint is part of the joint, and not of the segment).
> Yes.
"

>> For efficiency reasons. The main difference is that Rotation::Rot
>> normalizes the rotation axis every time. This makes a big difference
>> in performance. We could
>> * choose to take the performance hit to get more compact code,
>> * opt for changing the Rotation::Rot implementation, or
>> * just keep the less compact implementation.

> What is the alternative to normalization? To let the orientation drift...

The axis needs to be normalized. But this doesn't mean that the Rot()
function needs to do this every time. In the joint implementation, the
axis is normalized at construction time. Therefore, the joint contains
a special Rot() implementation that does not do the normalization
every time. We could go around this problem by having the general
Rot() function expect an already normalized axis, or by adding another
Rot() function in the Rotation class.

Wim

Ruben Smits's picture

manipulator dynamics

On Wednesday 04 February 2009 20:58:21 Wim Meeussen wrote:
> >> The joint axis is specified in the reference frame of the segment. So
> >> when constructing the joint, you have to know which segment you
> >> construct it for.
> >
> > Wrong coupling...!
> >
> >> So, one could argue that a joint should also know
> >> its position with respect to this reference frame.
> >
> > I don't argue like that :-)
>
> But you did argue like that in your last email:
> "
>
> >> The Body specifies its mass, center of gravity, Ixx,...
> >> with respect to the reference frame. So the position of the center of
> >> gravity is part of the Body, and not part of the segment
> >
> > I agree.
> >
> >> (as the position of the joint is part of the joint, and not of the
> >> segment).
> >
> > Yes.
>
> "
>
> >> For efficiency reasons. The main difference is that Rotation::Rot
> >> normalizes the rotation axis every time. This makes a big difference
> >> in performance. We could
> >> * choose to take the performance hit to get more compact code,
> >> * opt for changing the Rotation::Rot implementation, or
> >> * just keep the less compact implementation.
> >
> > What is the alternative to normalization? To let the orientation drift...
>
> The axis needs to be normalized. But this doesn't mean that the Rot()
> function needs to do this every time. In the joint implementation, the
> axis is normalized at construction time. Therefore, the joint contains
> a special Rot() implementation that does not do the normalization
> every time. We could go around this problem by having the general
> Rot() function expect an already normalized axis, or by adding another
> Rot() function in the Rotation class.

The Rot2() function takes a normalized vector !!! Maybe the name is not so
clear :s

Ruben

manipulator dynamics

On Wed, 4 Feb 2009, Wim Meeussen wrote:

>>> The joint axis is specified in the reference frame of the segment. So
>>> when constructing the joint, you have to know which segment you
>>> construct it for.
>> Wrong coupling...!
>
>>> So, one could argue that a joint should also know
>>> its position with respect to this reference frame.
>>
>> I don't argue like that :-)
>
>
> But you did argue like that in your last email:
> "
>>> The Body specifies its mass, center of gravity, Ixx,...
>>> with respect to the reference frame. So the position of the center of
>>> gravity is part of the Body, and not part of the segment
>> I agree.
>
>>> (as the position of the joint is part of the joint, and not of the segment).
>> Yes.
> "

I think I have discovered the natural language ambiguity that has plagued
me for some time in this discussion! "Position of the joint" sometimes
means "what is the spatial position and orientation of the joint axis
reference frame", and sometimes it just means "the joint angle"... So, We
have inadvertently been talking next to each other quite a couple of times,
for which I apologize!

>>> For efficiency reasons. The main difference is that Rotation::Rot
>>> normalizes the rotation axis every time. This makes a big difference
>>> in performance. We could
>>> * choose to take the performance hit to get more compact code,
>>> * opt for changing the Rotation::Rot implementation, or
>>> * just keep the less compact implementation.
>
>> What is the alternative to normalization? To let the orientation drift...
>
> The axis needs to be normalized. But this doesn't mean that the Rot()
> function needs to do this every time. In the joint implementation, the
> axis is normalized at construction time. Therefore, the joint contains
> a special Rot() implementation that does not do the normalization
> every time. We could go around this problem by having the general
> Rot() function expect an already normalized axis, or by adding another
> Rot() function in the Rotation class.

Probably both kind of functions have their use cases, so at first sight
this seems to be a useful suggestion... I think their naming should reflect
their functional differences in one way or another.

Herman

manipulator dynamics

On Wed, Feb 4, 2009 at 10:54 PM, Herman Bruyninckx
<Herman [dot] Bruyninckx [..] ...> wrote:
> On Wed, 4 Feb 2009, Wim Meeussen wrote:
>
>>>> The joint axis is specified in the reference frame of the segment. So
>>>> when constructing the joint, you have to know which segment you
>>>> construct it for.
>>> Wrong coupling...!
>>
>>>> So, one could argue that a joint should also know
>>>> its position with respect to this reference frame.
>>>
>>> I don't argue like that :-)
>>
>>
>> But you did argue like that in your last email:
>> "
>>>> The Body specifies its mass, center of gravity, Ixx,...
>>>> with respect to the reference frame. So the position of the center of
>>>> gravity is part of the Body, and not part of the segment
>>> I agree.
>>
>>>> (as the position of the joint is part of the joint, and not of the segment).
>>> Yes.
>> "
>
> I think I have discovered the natural language ambiguity that has plagued
> me for some time in this discussion! "Position of the joint" sometimes
> means "what is the spatial position and orientation of the joint axis
> reference frame", and sometimes it just means "the joint angle"... So, We
> have inadvertently been talking next to each other quite a couple of times,
> for which I apologize!

I'm glad we cleared this up! It was indeed confusing. We should
probably speak of the "position of the joint axis in its reference
frame" and the "state of the joint".

Wim

--
Wim Meeussen
Willow Garage Inc.
<http://www.willowgarage.com)
>

manipulator dynamics

On Thu, 5 Feb 2009, Wim Meeussen wrote:

> On Wed, Feb 4, 2009 at 10:54 PM, Herman Bruyninckx
> <Herman [dot] Bruyninckx [..] ...> wrote:
>> On Wed, 4 Feb 2009, Wim Meeussen wrote:
>>
>>>>> The joint axis is specified in the reference frame of the segment. So
>>>>> when constructing the joint, you have to know which segment you
>>>>> construct it for.
>>>> Wrong coupling...!
>>>
>>>>> So, one could argue that a joint should also know
>>>>> its position with respect to this reference frame.
>>>>
>>>> I don't argue like that :-)
>>>
>>>
>>> But you did argue like that in your last email:
>>> "
>>>>> The Body specifies its mass, center of gravity, Ixx,...
>>>>> with respect to the reference frame. So the position of the center of
>>>>> gravity is part of the Body, and not part of the segment
>>>> I agree.
>>>
>>>>> (as the position of the joint is part of the joint, and not of the segment).
>>>> Yes.
>>> "
>>
>> I think I have discovered the natural language ambiguity that has plagued
>> me for some time in this discussion! "Position of the joint" sometimes
>> means "what is the spatial position and orientation of the joint axis
>> reference frame", and sometimes it just means "the joint angle"... So, We
>> have inadvertently been talking next to each other quite a couple of times,
>> for which I apologize!
>
>
> I'm glad we cleared this up! It was indeed confusing. We should
> probably speak of the "position of the joint axis in its reference
> frame" and the "state of the joint".
>
Indeed! This is just one of the many, many cases that I have already
experienced in my carreer where such ambiguities result in hours and hours
of lost efforts and vain discussions... :-( And, as always, nobody can be
blamed for the confusion :-)

Herman

manipulator dynamics



On Thu, Jan 29, 2009 at 11:44 AM, Ruben Smits <span dir="ltr"><ruben [dot] smits [..] ...><span> wrote:
<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">
A joint is just a joint, it holds only information about the type (and

dynamical parameters).<blockquote>

It should be scalable, so as not to have unused data if I don't do dynamics computations.

<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">

A segment is like a rigid body, maybe we should rename it to body or so, it

only holds the information of the Intertia, cog and a frame we are interested

in (f_tip now).

<blockquote>


Instead of a single frame, there should be a list of frames, thus giving support to branching structures and multiple tasks on a body.
 

<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">

A chain is the interconnection of segments and joints.
<blockquote><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">
If a joint is added to a chain, we should say to which body(segment) is is

connected and where the position of the joint connection point is in the

reference frame of the body.



If a body/segment is added to chain, we should say to which joint it is

attached, and where the joint is located in it's reference frame.

<blockquote>


I agree, but I would speak of (branching) structures instead of chains.
 

<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">

The forward position kinematics of a chain would calculate the pose between

the root/base of the chain and the interested frame (f_tip) of one of the

segments/bodies.

<blockquote><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">

The forward velocity kinematics of a chain would calculate the twist of the

interested frame (f_tip) of one of the segments/bodies.

<blockquote>



Both algorithms could do their computations between two arbitrary frames in the structure, and not constrain one of the frames to be the root/base.

 

<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">
The jacobian calculation will express the relation between the joint velocity

values and the velocity of the interested frame of one of the segments/bodies.
<blockquote>


As before, it's useful to have the velocity between two arbitrary frames, for example in self-collision avoidance tasks.



Joan

Ruben Smits's picture

manipulator dynamics

On Thursday 29 January 2009 19:35:12 Joan Oliver wrote:
> On Thu, Jan 29, 2009 at 11:44 AM, Ruben Smits
> <ruben [dot] smits [..] ...ruben [dot] smits [..] ...>> wrote:
> A joint is just a joint, it holds only information about the type (and
> dynamical parameters).
>
> It should be scalable, so as not to have unused data if I don't do dynamics
> computations.

Something like aggregate objects? To which extra information can be added.
I like the idea of aggregate objects, but i don't find a good implementation
example of this.

> A segment is like a rigid body, maybe we should rename it to body or so, it
> only holds the information of the Intertia, cog and a frame we are
> interested in (f_tip now).
>
> Instead of a single frame, there should be a list of frames, thus giving
> support to branching structures and multiple tasks on a body.

I think the branching is already taken care of by the kinematic structure, but
the list can indeed be necessary to specify multiple tasks on the same body.

> A chain is the interconnection of segments and joints.
> If a joint is added to a chain, we should say to which body(segment) is is
> connected and where the position of the joint connection point is in the
> reference frame of the body.
>
> If a body/segment is added to chain, we should say to which joint it is
> attached, and where the joint is located in it's reference frame.
>
> I agree, but I would speak of (branching) structures instead of chains.

You're right, this design should work for all kinematic tree structures.

> The forward position kinematics of a chain would calculate the pose between
> the root/base of the chain and the interested frame (f_tip) of one of the
> segments/bodies.
>
> The forward velocity kinematics of a chain would calculate the twist of the
> interested frame (f_tip) of one of the segments/bodies.
>
> Both algorithms could do their computations between two arbitrary frames in
> the structure, and not constrain one of the frames to be the root/base.

You're right but in this case i would like a solver that will not search the
path between two frames every calculation, but stores the path at
initialisation.

> The jacobian calculation will express the relation between the joint
> velocity values and the velocity of the interested frame of one of the
> segments/bodies.
>
> As before, it's useful to have the velocity between two arbitrary frames,
> for example in self-collision avoidance tasks.

All very good ideas. Thanks for your reply.

Ruben

Ruben Smits's picture

manipulator dynamics

Wim,

the code looks very good, but ;)

can you add some comments to the pose calculation? Because i cannot understand
the code without reading some kinematics book ;).

I think it should be "axis" instead of "axes".

Are you sure it is faster, because if so i would create some static factory
functions for the other types, and replace the implementation by your new one.

Ruben

On Friday 23 January 2009 03:44:00 Wim Meeussen wrote:
> >> I'm working on an additional joint class that should allow us to put
> >> the segment reference frame at any place on a segment, without a
> >> performance penalty. If everything works out, it should even work with
> >> the existing solvers, and be able to co-exist with the existing joint
> >> implementation.
>
> Here is the patch for the joints, plus a patch for the unit tests. It
> seems to work for me, but could definitely use more thorough testing.
>
> * it allows to choose a joint along an arbitrary axes, at an arbitrary
> origin, * it allows to freely choose the reference frame of the segment
> * it works with the current solvers
> * it even runs a little faster than the current kdl implementation
> * it just _adds_ a joint type, so the current joints can still be used.
>
>
> Wim
>
>
> Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

manipulator dynamics

> can you add some comments to the pose calculation? Because i cannot understand
> the code without reading some kinematics book ;).

Will do. The pose function only calculates the rotation matrix around
an arbitrary axes.

> I think it should be "axis" instead of "axes".

;-) I keep confusing those...

> Are you sure it is faster, because if so i would create some static factory
> functions for the other types, and replace the implementation by your new one.

Yes, it is about 10% faster than the current implementation. I tested
both the pose() and the twist() functions by using position and
velocity kinematics. Although, in theory the current implementation
(with axes along either X, Y or Z) should have the potential to be
even faster, but it currently does not exploit the many zero's in it's
rotation matrix. However, I'm not sure you can exploit the zero's
without changing the design with joints/segments. So optimizing the
'old' implementation might not be an option.

Wim

manipulator dynamics

Here is the modified patch:

* axes changed into axis
* some comments were added
* the assert's in the constructors are replaced with exceptions

Only the constructors didn't change, since Ruben seems to think about
creating static factory functions for the old constructors.

Wim

>> Are you sure it is faster, because if so i would create some static factory
>> functions for the other types, and replace the implementation by your new one.

> Yes, it is about 10% faster than the current implementation. I tested
> both the pose() and the twist() functions by using position and
> velocity kinematics. Although, in theory the current implementation
> (with axes along either X, Y or Z) should have the potential to be
> even faster, but it currently does not exploit the many zero's in it's
> rotation matrix. However, I'm not sure you can exploit the zero's
> without changing the design with joints/segments. So optimizing the
> 'old' implementation might not be an option.

Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

manipulator dynamics

On Friday 23 January 2009 03:44:00 Wim Meeussen wrote:
> >> I'm working on an additional joint class that should allow us to put
> >> the segment reference frame at any place on a segment, without a
> >> performance penalty. If everything works out, it should even work with
> >> the existing solvers, and be able to co-exist with the existing joint
> >> implementation.
>
> Here is the patch for the joints, plus a patch for the unit tests. It
> seems to work for me, but could definitely use more thorough testing.
>
> * it allows to choose a joint along an arbitrary axes, at an arbitrary
> origin, * it allows to freely choose the reference frame of the segment
> * it works with the current solvers
> * it even runs a little faster than the current kdl implementation
> * it just _adds_ a joint type, so the current joints can still be used.

I'm just commenting on the technical implementation here:

+    // constructor for joint along x,y or z axes, at origin of reference 
frame
     Joint::Joint(const JointType& _type, const double& _scale, const double& 
_offset,
                  const double& _inertia, const double& _damping, const 
double& _stiffness):
         type(_type),scale(_scale),offset(_offset),inertia(_inertia),damping(_damping),stiffness(_stiffness)
     {
+      assert(type != RotAxes && type != TransAxes);
     }

Don't check user input with assertions. Because:
1. If the code is compiled with -DNDEBUG, the assertion will be left out, so
you don't have a check in 'production code'
2. assert does not allow the program to recover

Assertions should only be used to test 'internal' constraints, ie to test
against coding errors *in* the library. For example, in a given function you
assume that a member variable is never 0, so you assert that variable.
In your case, you should let the constructor throw.

* You removed operator=(). This is ok if you realize that the joint can still
be copied, but will be so on a copy 'value'-to-value basis. (it looks ok for
this class)

Since you have two very similar constructors, but require distinct input, you
might prefer writing factory functions which explicitly name the type you are
constructing:

  static Joint Joint::RotAxesJoint(const Vector& _origin, const Vector& _axes, 
const double& _scale, const double& _offset,  const double& _inertia, const 
double& _damping, const double& _stiffness);
 
  Joint a( Joint::RotAxesJoint(....) );

Just my 2c.

Peter

manipulator dynamics

> Don't check user input with assertions. Because:
> Assertions should only be used to test 'internal' constraints, ie to test
> against coding errors *in* the library. For example, in a given function you
> assume that a member variable is never 0, so you assert that variable.
> In your case, you should let the constructor throw.

ok, will do that!

> * You removed operator=(). This is ok if you realize that the joint can still
> be copied, but will be so on a copy 'value'-to-value basis. (it looks ok for
> this class)

Since I added a bunch of class variables, I would have to mention them
all explicitly in the copy constructor. And because for this class the
default constructor works fine, it seemed safer to use the default
constructor instead of risking to forget on of the class variables in
the explicit copy constructor.

> Since you have two very similar constructors, but require distinct input, you
> might prefer writing factory functions which explicitly name the type you are
> constructing:

Sounds like a good idea, but then we probably want to do this for all
joint types, and only have an empty constructor; which would break
backwards compatibility. Any thoughts?

Wim

manipulator dynamics

On Friday 23 January 2009 18:54:26 Wim Meeussen wrote:
> > Don't check user input with assertions. Because:
> > Assertions should only be used to test 'internal' constraints, ie to test
> > against coding errors *in* the library. For example, in a given function
> > you assume that a member variable is never 0, so you assert that
> > variable. In your case, you should let the constructor throw.
>
> ok, will do that!
>
> > * You removed operator=(). This is ok if you realize that the joint can
> > still be copied, but will be so on a copy 'value'-to-value basis. (it
> > looks ok for this class)
>
> Since I added a bunch of class variables, I would have to mention them
> all explicitly in the copy constructor. And because for this class the
> default constructor works fine, it seemed safer to use the default
> constructor instead of risking to forget on of the class variables in
> the explicit copy constructor.

Indeed.

>
> > Since you have two very similar constructors, but require distinct input,
> > you might prefer writing factory functions which explicitly name the type
> > you are constructing:
>
> Sounds like a good idea, but then we probably want to do this for all
> joint types, and only have an empty constructor; which would break
> backwards compatibility. Any thoughts?

I didn't propose to omit/break the constructors. I was just thinking about a
more user friendly+similar API. There are factory functions for other KDL
objects (Frame, Rotation,...) as well, in addition to their constructors.

Peter

Ruben Smits's picture

manipulator dynamics

On Tuesday 27 January 2009 11:25:27 Peter Soetens wrote:
> On Friday 23 January 2009 18:54:26 Wim Meeussen wrote:
> > > Don't check user input with assertions. Because:
> > > Assertions should only be used to test 'internal' constraints, ie to
> > > test against coding errors *in* the library. For example, in a given
> > > function you assume that a member variable is never 0, so you assert
> > > that variable. In your case, you should let the constructor throw.
> >
> > ok, will do that!
> >
> > > * You removed operator=(). This is ok if you realize that the joint can
> > > still be copied, but will be so on a copy 'value'-to-value basis. (it
> > > looks ok for this class)
> >
> > Since I added a bunch of class variables, I would have to mention them
> > all explicitly in the copy constructor. And because for this class the
> > default constructor works fine, it seemed safer to use the default
> > constructor instead of risking to forget on of the class variables in
> > the explicit copy constructor.
>
> Indeed.
>
> > > Since you have two very similar constructors, but require distinct
> > > input, you might prefer writing factory functions which explicitly name
> > > the type you are constructing:
> >
> > Sounds like a good idea, but then we probably want to do this for all
> > joint types, and only have an empty constructor; which would break
> > backwards compatibility. Any thoughts?
>
> I didn't propose to omit/break the constructors. I was just thinking about
> a more user friendly+similar API. There are factory functions for other KDL
> objects (Frame, Rotation,...) as well, in addition to their constructors.

Since there is still no 1.0 release we can easily break the backwards
compatibility ;)

i would propose to remove all old types and only keep the types: Rot and
Trans. And create factory functions for all special cases we would want to
support.

Any objections?

Ruben

manipulator dynamics

>> I didn't propose to omit/break the constructors. I was just thinking about
>> a more user friendly+similar API. There are factory functions for other KDL
>> objects (Frame, Rotation,...) as well, in addition to their constructors.
>
> Since there is still no 1.0 release we can easily break the backwards
> compatibility ;)
>
> i would propose to remove all old types and only keep the types: Rot and
> Trans. And create factory functions for all special cases we would want to
> support.

I assume you are proposing this:

Joint() --> type None
Joint(origin, axis, ..., Rot) --> type Rot
Joint(origin, axis, ..., Trans) --> type Trans

or did you mean this:

Joint() --> type None
Joint::Rot(origin, axis, ...) --> type Rot
Joint::Trans(origin, axis, ...) --> type Trans

and then for the special cases:

Joint::RotX(...) --> type Rot
Joint::RotY(...) --> type Rot
Joint::RotZ(...) --> type Rot
Joint::TransX(...) --> type Trans
Joint::TransY(...) --> type Trans
Joint::TransZ(...) --> type Trans

Anyway, they both look good to me ;-)

Wim

Ruben Smits's picture

manipulator dynamics

On Tuesday 27 January 2009 18:23:28 Wim Meeussen wrote:
> >> I didn't propose to omit/break the constructors. I was just thinking
> >> about a more user friendly+similar API. There are factory functions for
> >> other KDL objects (Frame, Rotation,...) as well, in addition to their
> >> constructors.
> >
> > Since there is still no 1.0 release we can easily break the backwards
> > compatibility ;)
> >
> > i would propose to remove all old types and only keep the types: Rot and
> > Trans. And create factory functions for all special cases we would want
> > to support.
>
> I assume you are proposing this:
>
> Joint() --> type None
> Joint(origin, axis, ..., Rot) --> type Rot
> Joint(origin, axis, ..., Trans) --> type Trans
>
> or did you mean this:
>
> Joint() --> type None
> Joint::Rot(origin, axis, ...) --> type Rot
> Joint::Trans(origin, axis, ...) --> type Trans

I like this one more. But I do not like the fact that the origin information
of a joint is located in the joint class. I would expect this information to
be located in the segment class. I'm looking into your joint2.patch.

So i would only allow
Joint() --> type None
Joint::Rot(axis)
Joint::Trans(axis)

>
>
> and then for the special cases:
>
> Joint::RotX(...) --> type Rot
> Joint::RotY(...) --> type Rot
> Joint::RotZ(...) --> type Rot
> Joint::TransX(...) --> type Trans
> Joint::TransY(...) --> type Trans
> Joint::TransZ(...) --> type Trans
>
> Anyway, they both look good to me ;-)
>
> Wim

Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

Ruben Smits's picture

manipulator dynamics

Is there a reason why you removed the copy-constructor and the operator=???

Ruben

On Friday 23 January 2009 03:44:00 Wim Meeussen wrote:
> >> I'm working on an additional joint class that should allow us to put
> >> the segment reference frame at any place on a segment, without a
> >> performance penalty. If everything works out, it should even work with
> >> the existing solvers, and be able to co-exist with the existing joint
> >> implementation.
>
> Here is the patch for the joints, plus a patch for the unit tests. It
> seems to work for me, but could definitely use more thorough testing.
>
> * it allows to choose a joint along an arbitrary axes, at an arbitrary
> origin, * it allows to freely choose the reference frame of the segment
> * it works with the current solvers
> * it even runs a little faster than the current kdl implementation
> * it just _adds_ a joint type, so the current joints can still be used.
>
>
> Wim
>
>
> Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

manipulator dynamics

Is there any update about the implementation of the dynamics equations in KDL? Is there any roadmap about this? Since the equations are already available, do you have an estimation of the required time to implement this feature at least for simple single-chain robots?

Thank you,

Philippe Hamelin
from Canada :-)

manipulator dynamics

On Wed, 14 Jan 2009, philippe [dot] hamelin [..] ... wrote:

> Is there any update about the implementation of the dynamics equations in
> KDL? Is there any roadmap about this? Since the equations are already
> available, do you have an estimation of the required time to implement
> this feature at least for simple single-chain robots?
>
It has been on the agenda for quite some time already, indeed. The major
problem is to find the one month of a good implementor's time, including
the willingness to do some infrastructural work first: a decent and
scalable design to work with dynamics for _all_ kinds of kinematic chains.
The major problem that I see as being unsolved for the time being is to
decide on a way to support chains that have not just the traditional single
DOF joints, for example, (passive) spherical joints with three degrees of
freedom.

Herman

Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

manipulator dynamics

>> Is there any update about the implementation of the dynamics equations in
>> KDL? Is there any roadmap about this? Since the equations are already
>> available, do you have an estimation of the required time to implement
>> this feature at least for simple single-chain robots?

> It has been on the agenda for quite some time already, indeed. The major
> problem is to find the one month of a good implementor's time, including
> the willingness to do some infrastructural work first: a decent and
> scalable design to work with dynamics for _all_ kinds of kinematic chains.
> The major problem that I see as being unsolved for the time being is to
> decide on a way to support chains that have not just the traditional single
> DOF joints, for example, (passive) spherical joints with three degrees of
> freedom.

In the mean time, if you want an implementation of inverse dynamics
for single chains and joints with only 1 DOF, you can download a
modified version of KDL at:

svn co https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/tr...
kdl-willow

The inverse dynamics solver is implemented as a chainidsolver.hpp, in
chainidsolver_newtoneuler.cpp and chainidsolver_newtoneuler.hpp

This is basically a patch that was discussed on this mailinglist a
while ago, but didn't make it into the repository.

Wim

manipulator dynamics

On Sun, 18 Jan 2009, Wim Meeussen wrote:

>>> Is there any update about the implementation of the dynamics equations in
>>> KDL? Is there any roadmap about this? Since the equations are already
>>> available, do you have an estimation of the required time to implement
>>> this feature at least for simple single-chain robots?
>
>> It has been on the agenda for quite some time already, indeed. The major
>> problem is to find the one month of a good implementor's time, including
>> the willingness to do some infrastructural work first: a decent and
>> scalable design to work with dynamics for _all_ kinds of kinematic chains.
>> The major problem that I see as being unsolved for the time being is to
>> decide on a way to support chains that have not just the traditional single
>> DOF joints, for example, (passive) spherical joints with three degrees of
>> freedom.
>
>
> In the mean time, if you want an implementation of inverse dynamics
> for single chains and joints with only 1 DOF, you can download a
> modified version of KDL at:
>
> svn co https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/tr...
> kdl-willow
>
> The inverse dynamics solver is implemented as a chainidsolver.hpp, in
> chainidsolver_newtoneuler.cpp and chainidsolver_newtoneuler.hpp
>
> This is basically a patch that was discussed on this mailinglist a
> while ago, but didn't make it into the repository.
>
Indeed. And one of the reasons was that it should be given a more precise
name: there are plenty of "Newton Euler" algorithms out there, and
implementing more than one could make sense. Hence, a name for the solver
that identified the implemented algorithm would be nice :-)

Thanks anyway!

Herman

Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

manipulator dynamics

>> In the mean time, if you want an implementation of inverse dynamics
>> for single chains and joints with only 1 DOF, you can download a
>> modified version of KDL at:
>>
>> svn co
>> https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/tr...
>> kdl-willow
>>
>> The inverse dynamics solver is implemented as a chainidsolver.hpp, in
>> chainidsolver_newtoneuler.cpp and chainidsolver_newtoneuler.hpp
>>
>> This is basically a patch that was discussed on this mailinglist a
>> while ago, but didn't make it into the repository.
>>
> Indeed. And one of the reasons was that it should be given a more precise
> name: there are plenty of "Newton Euler" algorithms out there, and
> implementing more than one could make sense. Hence, a name for the solver
> that identified the implemented algorithm would be nice :-)

Also, the API of the solver is too restricted to represent a general
inverse dynamics solver. We first need to come up with a general ID
API before this code could be added to KDL.

Wim

manipulator dynamics

On Mon, 19 Jan 2009, Wim Meeussen wrote:

>>> In the mean time, if you want an implementation of inverse dynamics
>>> for single chains and joints with only 1 DOF, you can download a
>>> modified version of KDL at:
>>>
>>> svn co
>>> https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/tr...
>>> kdl-willow
>>>
>>> The inverse dynamics solver is implemented as a chainidsolver.hpp, in
>>> chainidsolver_newtoneuler.cpp and chainidsolver_newtoneuler.hpp
>>>
>>> This is basically a patch that was discussed on this mailinglist a
>>> while ago, but didn't make it into the repository.
>>>
>> Indeed. And one of the reasons was that it should be given a more precise
>> name: there are plenty of "Newton Euler" algorithms out there, and
>> implementing more than one could make sense. Hence, a name for the solver
>> that identified the implemented algorithm would be nice :-)
>
> Also, the API of the solver is too restricted to represent a general
> inverse dynamics solver. We first need to come up with a general ID
> API before this code could be added to KDL.
>
What are _your_ expectations of a "general ID API"...?

In my opinion, the really general API is nothing else but

ReturnCode ID (KinematicChain, CurrentState, NewState);

which is linked to specific implementations ("solvers", that each (can)
have their own set of solver properties ("epsilon", number of iterations,
numerical parameters, ...)

Herman

Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

manipulator dynamics

> What are _your_ expectations of a "general ID API"...?
> In my opinion, the really general API is nothing else but
>
> ReturnCode ID (KinematicChain, CurrentState, NewState);
>
> which is linked to specific implementations ("solvers", that each (can)
> have their own set of solver properties ("epsilon", number of iterations,
> numerical parameters, ...)

This is also what I see as an ID API. This is also the style of API
that KDL uses for kinematics. But in our previous discussion, the
suggested API was very different:

On Tue, Jul 22, 2008 at 1:35 AM, Herman Bruyninckx
<Herman [dot] Bruyninckx [..] ...> wrote:
> Basically, my idea of abstract API was as follows:
>
> outState ChainID (Chain, inState, Solver);
>
> where "Chain" is a specific KinematicChain object, "Solver" is a specific
> numerical algorithm, and "inState" and "outState" are the (chain and
> solver-specific!) state objects (they will in general not be of the same
> type, since they contain different sets of joint, Cartesian and chain
> variables).

Assuming we go with the API:

ReturnCode ID (KinematicChain, CurrentState, NewState);

What should be CurrentState? Should it be JntArrayAcc? And should
NewState be JntArrayEffort?

Thanks!

Wim

manipulator dynamics

On Tue, 20 Jan 2009, Wim Meeussen wrote:

>> What are _your_ expectations of a "general ID API"...?
>> In my opinion, the really general API is nothing else but
>>
>> ReturnCode ID (KinematicChain, CurrentState, NewState);
>>
>> which is linked to specific implementations ("solvers", that each (can)
>> have their own set of solver properties ("epsilon", number of iterations,
>> numerical parameters, ...)
>
>
> This is also what I see as an ID API. This is also the style of API
> that KDL uses for kinematics. But in our previous discussion, the
> suggested API was very different:
>
>
> On Tue, Jul 22, 2008 at 1:35 AM, Herman Bruyninckx
> <Herman [dot] Bruyninckx [..] ...> wrote:
>> Basically, my idea of abstract API was as follows:
>>
>> outState ChainID (Chain, inState, Solver);
>>
>> where "Chain" is a specific KinematicChain object, "Solver" is a specific
>> numerical algorithm, and "inState" and "outState" are the (chain and
>> solver-specific!) state objects (they will in general not be of the same
>> type, since they contain different sets of joint, Cartesian and chain
>> variables).

We are indeed not yet completely clear how to go ahead... The first
suggestion is 'stateless' (= it specifies the solver explicitly) but gives
information about its internals...

> Assuming we go with the API:
>
> ReturnCode ID (KinematicChain, CurrentState, NewState);
>
> What should be CurrentState? Should it be JntArrayAcc? And should
> NewState be JntArrayEffort?

This depends on:
(i) the specific kinematic chain: some chains cannot have a simple array
of joint values.
(ii) the solver: some take into account joint limits, for example.
Hence, the API choice also involves the choice about how we give all this
information. The "aggregation" concept is maybe an answer: a new specific
object is created by putting together all these different parts of
information.

Please comment.

Herman

Ruben Smits's picture

manipulator dynamics

On Wednesday 04 February 2009 18:03:33 you wrote:
> On Wed, Feb 4, 2009 at 4:22 AM, Ruben Smits
>
> <ruben [dot] smits [..] ...> wrote:
> > On Monday 02 February 2009 22:00:12 Wim Meeussen wrote:
> >> Can we --in parallel to this new redesign discussion-- also process
> >> the patch to add an additional joint constructor? I attached it again,
> >> and will be happy to discuss any technical issues.
> >
> > I'm still revising ;)
> >
> > apart from the fact that I really do not like the design (joint owning
> > its position in the reference frame of the segment, which is owning the
> > joint)
>
> The joint axis is specified in the reference frame of the segment. So
> when constructing the joint, you have to know which segment you
> construct it for. So, one could argue that a joint should also know
> its position with respect to this reference frame.
>
> > is there a reason why you do not use the Rotation::Rot or Rotation::Rot2
> > functions to calculate the rotation about a arbitrary axis? It would make
> > the code a lot cleaner.
>
> For efficiency reasons. The main difference is that Rotation::Rot
> normalizes the rotation axis every time. This makes a big difference
> in performance. We could
> * choose to take the performance hit to get more compact code,
> * opt for changing the Rotation::Rot implementation, or
> * just keep the less compact implementation.

The Rot2 implementation does not normalize the axis!!!!
I also changed the Rot2 implementation to let it have the least amount of
multiplications and additions (12M+9A)

I would change to the Rot2 implemantation, which results in the same
performance with more compact and nicer looking code ;)

>
> Wim
>
> --
> Wim Meeussen
> Willow Garage Inc.
> <http://www.willowgarage.com)

>

manipulator dynamics

>> For efficiency reasons. The main difference is that Rotation::Rot
>> normalizes the rotation axis every time. This makes a big difference
>> in performance. We could
>> * choose to take the performance hit to get more compact code,
>> * opt for changing the Rotation::Rot implementation, or
>> * just keep the less compact implementation.

> The Rot2 implementation does not normalize the axis!!!!
> I also changed the Rot2 implementation to let it have the least amount of
> multiplications and additions (12M+9A)

Great! I had not looked at this one because I thought it was part of
the Rotation2 class (2D rotation).

> I would change to the Rot2 implemantation, which results in the same
> performance with more compact and nicer looking code ;)

Great again!

Wim

manipulator dynamics

On Thu, Feb 5, 2009 at 12:09 AM, Ruben Smits
<ruben [dot] smits [..] ...> wrote:
> On Monday 02 February 2009 22:00:12 you wrote:
>> Can we --in parallel to this new redesign discussion-- also process
>> the patch to add an additional joint constructor? I attached it again,
>> and will be happy to discuss any technical issues.
>
> make check fails when I include your patch. The forward-inverse position
> kinematics fail.

Yes, and interestingly enough it does _not_ fail when you uncomment
the other tests, and only run the forward-inverse position
kinematics. When you run all tests together, and the f/i pos kin
fails, it fails because in one of the solvers the maximum number of
iterations was reached, not because the results of inverse and
forward pos kin were different. I don't have any clue as from where
this problem comes form.

> Could you also add some tests to the kinfam test which
> explicitly tests joints and segments created with the new constructor?

It might take a while... I'm waaayyy overspending my time on kdl lately ;-)

Wim

manipulator dynamics

On Tue, Jan 20, 2009 at 1:15 PM, Herman Bruyninckx
<Herman [dot] Bruyninckx [..] ...> wrote:
> On Tue, 20 Jan 2009, Wim Meeussen wrote:
>
>>> What are _your_ expectations of a "general ID API"...?
>>> In my opinion, the really general API is nothing else but
>>>
>>> ReturnCode ID (KinematicChain, CurrentState, NewState);
>>>
>>> which is linked to specific implementations ("solvers", that each (can)
>>> have their own set of solver properties ("epsilon", number of iterations,
>>> numerical parameters, ...)
>>
>>
>> This is also what I see as an ID API. This is also the style of API
>> that KDL uses for kinematics. But in our previous discussion, the
>> suggested API was very different:
>>
>>
>> On Tue, Jul 22, 2008 at 1:35 AM, Herman Bruyninckx
>> <Herman [dot] Bruyninckx [..] ...> wrote:
>>>
>>> Basically, my idea of abstract API was as follows:
>>>
>>> outState ChainID (Chain, inState, Solver);
>>>
>>> where "Chain" is a specific KinematicChain object, "Solver" is a specific
>>> numerical algorithm, and "inState" and "outState" are the (chain and
>>> solver-specific!) state objects (they will in general not be of the same
>>> type, since they contain different sets of joint, Cartesian and chain
>>> variables).
>
> We are indeed not yet completely clear how to go ahead... The first
> suggestion is 'stateless' (= it specifies the solver explicitly) but gives
> information about its internals...
>
>> Assuming we go with the API:
>>
>> ReturnCode ID (KinematicChain, CurrentState, NewState);
>>
>> What should be CurrentState? Should it be JntArrayAcc? And should
>> NewState be JntArrayEffort?
>
> This depends on:
> (i) the specific kinematic chain: some chains cannot have a simple array
> of joint values.
> (ii) the solver: some take into account joint limits, for example.
> Hence, the API choice also involves the choice about how we give all this
> information. The "aggregation" concept is maybe an answer: a new specific
> object is created by putting together all these different parts of
> information.

This discussion also applies to the current kinematics api, and is a
more general discussion about a redesign of the kdl api's. This is
exactly where our id-patch ended last time. I agree we need to
redesign the api, but requiring a redesign of the kdl api's before a
patch (that uses the _current_ kdl api) gets accepted, is not
realistic. It would be nice if KLD could either specify the api we
should use, or decouple the id-patch and the api redesign. The patch
works, doesn't break anything, and follows the current api. Since we
couldn't wait for the redesign (this discussion started 6 months ago),
we created our own kdl repository, and I hate to see both repositories
grow more and more apart as we both apply new patches.

Wim

manipulator dynamics

2009/1/20 Herman Bruyninckx <span dir="ltr"><Herman [dot] Bruyninckx [..] ...><span>
<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">

On Mon, 19 Jan 2009, Wim Meeussen wrote:



<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;"><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">
<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">
In the mean time, if you want an implementation of inverse dynamics

for single chains and joints with only 1 DOF, you can download a

modified version of KDL at:



svn co

https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/trunk/3rdparty/kdl/kdl-willow

kdl-willow



The inverse dynamics solver is implemented as a chainidsolver.hpp, in

chainidsolver_newtoneuler.cpp and chainidsolver_newtoneuler.hpp



This is basically a patch that was discussed on this mailinglist a

while ago, but didn't make it into the repository.



<blockquote>
Indeed. And one of the reasons was that it should be given a more precise

name: there are plenty of "Newton Euler" algorithms out there, and

implementing more than one could make sense. Hence, a name for the solver

that identified the implemented algorithm would be nice :-)

<blockquote>


Also, the API of the solver is too restricted to represent a general

inverse dynamics solver. We first need to come up with a general ID

API before this code could be added to KDL.



<blockquote>

What are _your_ expectations of a "general ID API"...?



In my opinion, the really general API is nothing else but



 ReturnCode ID (KinematicChain, CurrentState, NewState);



which is linked to specific implementations ("solvers", that each (can)

have their own set of solver properties ("epsilon", number of iterations,

numerical parameters, ...)
<font color="#888888">


Herman<font>

<blockquote>


My opinion is along the same lines as Herman:

- I think that the definition of the Kinematic(Dynamic)Chain must be broad
enough to contain all the kinematic and dynamic parameters required for
different types of solver.

- If we consider that the definition of the "State" contains only the
state on a joint-by-joint basis (eg. position and speed), then its definition can also
be general. However, in the case of serial robots, it is interesting to
get the mass matrix and the matrix of Coriolis and centrifugal forces. I
don't think these concepts really apply to all types of systems so it may be just one on the custom properties/methods of the solver.

Is there an open-source library who does this work already? Perhaps we could investigate it for that kind of interface question?


Philippe Hamelin

manipulator dynamics

On Tue, 20 Jan 2009, Philippe Hamelin wrote:

> 2009/1/20 Herman Bruyninckx <Herman [dot] Bruyninckx [..] ...>
> On Mon, 19 Jan 2009, Wim Meeussen wrote:
>
> In the mean time, if you
> want an implementation of
> inverse dynamics
> for single chains and joints
> with only 1 DOF, you can
> download a
> modified version of KDL at:
>
> svn co
> https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/trunk
> /3rdparty/kdl/kdl-willow
> kdl-willow
>
> The inverse dynamics solver
> is implemented as a
> chainidsolver.hpp, in
> chainidsolver_newtoneuler.cpp
> and
> chainidsolver_newtoneuler.hpp
>
> This is basically a patch
> that was discussed on this
> mailinglist a
> while ago, but didn't make
> it into the repository.
>
> Indeed. And one of the reasons was that
> it should be given a more precise
> name: there are plenty of "Newton Euler"
> algorithms out there, and
> implementing more than one could make
> sense. Hence, a name for the solver
> that identified the implemented
> algorithm would be nice :-)
>
>
> Also, the API of the solver is too restricted to
> represent a general
> inverse dynamics solver. We first need to come up
> with a general ID
> API before this code could be added to KDL.
>
> What are _your_ expectations of a "general ID API"...?
>
> In my opinion, the really general API is nothing else but
>
>  ReturnCode ID (KinematicChain, CurrentState, NewState);
>
> which is linked to specific implementations ("solvers", that each
> (can)
> have their own set of solver properties ("epsilon", number of
> iterations,
> numerical parameters, ...)
>
> Herman
>
>
> My opinion is along the same lines as Herman:
>
> - I think that the definition of the Kinematic(Dynamic)Chain must be broad
> enough to contain all the kinematic and dynamic parameters required for
> different types of solver.

I do not fully agree :-) I think it is a bad idea to make a "fat" kinematic
chain object, that contains all possibly useful parameters for kinematics
and dynamics. It's a bad idea because then almost every application will
use only a fraction of that object, which is a waste of resources, and a
fact that will "scare" potential users away to simpler alternatives. (Do
such simpler, but still serious alternatives exist, BTW...?)

> - If we consider that the definition of the "State" contains only the state
> on a joint-by-joint basis (eg. position and speed), then its definition can
> also be general. However, in the case of serial robots, it is interesting to
> get the mass matrix and the matrix of Coriolis and centrifugal forces. I
> don't think these concepts really apply to all types of systems so it may be
> just one on the custom properties/methods of the solver.

I don't think so: my idea is to use the kinematic chain as a very thin
object that only stores the interconnection information; and all other
relevant data structures (joint values, dynamic parameters, ...) are
"aggregated" to it in a loosely coupled way,
<http://en.wikipedia.org/wiki/Object_composition#Aggregation>
such as in a "scene graph" in computer animation programs. This gives much
more "shallow" interfaces, at the cost of a larger variety of aggregated
objects. KDL should support all the smaller objects, _and_ generic methods
to support aggregation while keeping the useful ("crosscutting aspect")
things such as reporting, setting/getting of properties, error handling, ...
<http://en.wikipedia.org/wiki/Aspect-oriented_software_development#Crosscutting_Concerns>

(Reading the link above makes me wonder whether Orocos shouldn't promote
its "Aspect Oriented Programming" support more! :-))

> Is there an open-source library who does this work already? Perhaps we could
> investigate it for that kind of interface question?

I do not think so... But I am very interested in discussing about such
libraries if they show up.

Oops, I lied a bit... I do know more than one open source library that does
dynamics:
- ROBOOP <http://www.cours.polymtl.ca/roboop /> (the geographical proximity
to you makes me think you should know that already :-))
- OpenHRP3 <http://www.openrtp.jp/openhrp3/en/index.html>, the Japanese
project that has two dynamic solvers.
- OpenSim <https://simtk.org/home/opensim>, which has (an early version of)
the dynamics algorithm used in Khatib's group.
Some documentation is here:
<https://simtk.org/project/xml/downloads.xml?group_id=91>
It is hard to find the code, and even though this project releases its
code under a free software license, it does not work as a real open
source project.

Herman

Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

manipulator dynamics

On Jan 20, 2009, at 08:48 , Herman Bruyninckx wrote:

> On Tue, 20 Jan 2009, Philippe Hamelin wrote:
>
>> 2009/1/20 Herman Bruyninckx <Herman [dot] Bruyninckx [..] ...>
>> On Mon, 19 Jan 2009, Wim Meeussen wrote:
>>
>> In the mean time, if you
>> want an implementation of
>> inverse dynamics
>> for single chains and joints
>> with only 1 DOF, you can
>> download a
>> modified version of KDL at:
>>
>> svn co
>> https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/trunk
>> /3rdparty/kdl/kdl-willow
>> kdl-willow
>>
>> The inverse dynamics solver
>> is implemented as a
>> chainidsolver.hpp, in
>> chainidsolver_newtoneuler.cpp
>> and
>> chainidsolver_newtoneuler.hpp
>>
>> This is basically a patch
>> that was discussed on this
>> mailinglist a
>> while ago, but didn't make
>> it into the repository.
>>
>> Indeed. And one of the reasons was that
>> it should be given a more precise
>> name: there are plenty of "Newton Euler"
>> algorithms out there, and
>> implementing more than one could make
>> sense. Hence, a name for the solver
>> that identified the implemented
>> algorithm would be nice :-)
>>
>> Also, the API of the solver is too restricted to
>> represent a general
>> inverse dynamics solver. We first need to come up
>> with a general ID
>> API before this code could be added to KDL.
>> What are _your_ expectations of a "general ID API"...?
>> In my opinion, the really general API is nothing else but
>> ReturnCode ID (KinematicChain, CurrentState, NewState);
>> which is linked to specific implementations ("solvers", that each
>> (can)
>> have their own set of solver properties ("epsilon", number of
>> iterations,
>> numerical parameters, ...)
>> Herman
>> My opinion is along the same lines as Herman:
>> - I think that the definition of the Kinematic(Dynamic)Chain must
>> be broad
>> enough to contain all the kinematic and dynamic parameters required
>> for
>> different types of solver.
>
> I do not fully agree :-) I think it is a bad idea to make a "fat"
> kinematic
> chain object, that contains all possibly useful parameters for
> kinematics
> and dynamics. It's a bad idea because then almost every application
> will
> use only a fraction of that object, which is a waste of resources,
> and a
> fact that will "scare" potential users away to simpler alternatives.
> (Do
> such simpler, but still serious alternatives exist, BTW...?)

Agreed. You end up with an MS-eseque, polluted API ...

>> - If we consider that the definition of the "State" contains only
>> the state
>> on a joint-by-joint basis (eg. position and speed), then its
>> definition can
>> also be general. However, in the case of serial robots, it is
>> interesting to
>> get the mass matrix and the matrix of Coriolis and centrifugal
>> forces. I
>> don't think these concepts really apply to all types of systems so
>> it may be
>> just one on the custom properties/methods of the solver.
>
> I don't think so: my idea is to use the kinematic chain as a very thin
> object that only stores the interconnection information; and all other
> relevant data structures (joint values, dynamic parameters, ...) are
> "aggregated" to it in a loosely coupled way,
> <http://en.wikipedia.org/wiki/Object_composition#Aggregation>
> such as in a "scene graph" in computer animation programs. This
> gives much
> more "shallow" interfaces, at the cost of a larger variety of
> aggregated
> objects. KDL should support all the smaller objects, _and_ generic
> methods
> to support aggregation while keeping the useful ("crosscutting
> aspect")
> things such as reporting, setting/getting of properties, error
> handling, ...
> <http://en.wikipedia.org/wiki/Aspect-oriented_software_development#Crosscutting_Concerns
> >

Agreed completely. The scene graph analogy is a good one. There can be
quite a learning curve to these approaches, however, we've found that
the payoff occurs once only a small number of aggregate classes have
been constructed.

> (Reading the link above makes me wonder whether Orocos shouldn't
> promote
> its "Aspect Oriented Programming" support more! :-))

It should!

>> Is there an open-source library who does this work already? Perhaps
>> we could
>> investigate it for that kind of interface question?
>
> I do not think so... But I am very interested in discussing about such
> libraries if they show up.
>
> Oops, I lied a bit... I do know more than one open source library
> that does
> dynamics:
> - ROBOOP <http://www.cours.polymtl.ca/roboop /> (the geographical
> proximity
> to you makes me think you should know that already :-))

This one has absolutely hideous real-time performance. IIRC, (nearly?)
every variable involves a dynamic memory allocation. Bad Bad Bad! We
changed one of our controllers from ROBoop to KDL, and had a 10x speed
increase.

S

manipulator dynamics




2009/1/20 S Roderick <span dir="ltr"><kiwi.net@mac.com><span>
<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">

On Jan 20, 2009, at 08:48 , Herman Bruyninckx wrote:



<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">
On Tue, 20 Jan 2009, Philippe Hamelin wrote:



<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">
2009/1/20 Herman Bruyninckx <Herman [dot] Bruyninckx [..] ...>

    On Mon, 19 Jan 2009, Wim Meeussen wrote:



                      In the mean time, if you

                      want an implementation of

                      inverse dynamics

                      for single chains and joints

                      with only 1 DOF, you can

                      download a

                      modified version of KDL at:



                      svn co

https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/trunk

                      /3rdparty/kdl/kdl-willow

                      kdl-willow



                      The inverse dynamics solver

                      is implemented as a

                      chainidsolver.hpp, in

                      chainidsolver_newtoneuler.cpp

                      and

                      chainidsolver_newtoneuler.hpp



                      This is basically a patch

                      that was discussed on this

                      mailinglist a

                      while ago, but didn't make

                      it into the repository.



                Indeed. And one of the reasons was that

                it should be given a more precise

                name: there are plenty of "Newton Euler"

                algorithms out there, and

                implementing more than one could make

                sense. Hence, a name for the solver

                that identified the implemented

                algorithm would be nice :-)



          Also, the API of the solver is too restricted to

          represent a general

          inverse dynamics solver. We first need to come up

          with a general ID

          API before this code could be added to KDL.

What are _your_ expectations of a "general ID API"...?

In my opinion, the really general API is nothing else but

 ReturnCode ID (KinematicChain, CurrentState, NewState);

which is linked to specific implementations ("solvers", that each

(can)

have their own set of solver properties ("epsilon", number of

iterations,

numerical parameters, ...)

Herman

My opinion is along the same lines as Herman:

- I think that the definition of the Kinematic(Dynamic)Chain must be broad

enough to contain all the kinematic and dynamic parameters required for

different types of solver.

<blockquote>


I do not fully agree :-) I think it is a bad idea to make a "fat" kinematic

chain object, that contains all possibly useful parameters for kinematics

and dynamics. It's a bad idea because then almost every application will

use only a fraction of that object, which is a waste of resources, and a

fact that will "scare" potential users away to simpler alternatives. (Do

such simpler, but still serious alternatives exist, BTW...?)

<blockquote>

Agreed. You end up with an MS-eseque, polluted API ...





<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;"><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">

- If we consider that the definition of the "State" contains only the state

on a joint-by-joint basis (eg. position and speed), then its definition can

also be general. However, in the case of serial robots, it is interesting to

get the mass matrix and the matrix of Coriolis and centrifugal forces. I

don't think these concepts really apply to all types of systems so it may be

just one on the custom properties/methods of the solver.

<blockquote>


I don't think so: my idea is to use the kinematic chain as a very thin

object that only stores the interconnection information; and all other

relevant data structures (joint values, dynamic parameters, ...) are

"aggregated" to it in a loosely coupled way,

 <http://en.wikipedia.org/wiki/Object_composition#Aggregation>

such as in a "scene graph" in computer animation programs. This gives much

more "shallow" interfaces, at the cost of a larger variety of aggregated

objects. KDL should support all the smaller objects, _and_ generic methods

to support aggregation while keeping the useful ("crosscutting aspect")

things such as reporting, setting/getting of properties, error handling, ...

<http://en.wikipedia.org/wiki/Aspect-oriented_software_development#Crosscutting_Concerns>

<blockquote>

Agreed completely. The scene graph analogy is a good one. There can be quite a learning curve to these approaches, however,  we've found that the payoff occurs once only a small number of aggregate classes have been constructed.





<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">
(Reading the link above makes me wonder whether Orocos shouldn't promote

its "Aspect Oriented Programming" support more! :-))

<blockquote>

It should!





<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;"><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">

Is there an open-source library who does this work already? Perhaps we could

investigate it for that kind of interface question?

<blockquote>


I do not think so... But I am very interested in discussing about such

libraries if they show up.



Oops, I lied a bit... I do know more than one open source library that does

dynamics:

- ROBOOP <http://www.cours.polymtl.ca/roboop/> (the geographical proximity

 to you makes me think you should know that already :-))

<blockquote>

This one has absolutely hideous real-time performance. IIRC, (nearly?) every variable involves a dynamic memory allocation. Bad Bad Bad! We changed one of our controllers from ROBoop to KDL, and had a 10x speed increase.





S

--

Orocos-Users mailing list

Orocos-Users [..] ...

http://lists.mech.kuleuven.be/mailman/listinfo/orocos-users


<blockquote>



You
have an interesting point. I really do not know the concept of "Scene
Graph" but I admit that the principle of aggregation is a good
practice. Initially, I saw the KinematicChain like the
kinematic parameters of the system. But from what I understand you want
to use it as an "excuse" to interconnect frames and stores parameters? Do you have relevant information about scene graph to educate me? :-)

Philippe

manipulator dynamics

On Tue, 20 Jan 2009, Philippe Hamelin wrote:

>
>
> 2009/1/20 S Roderick <kiwi [dot] net [..] ...>
> On Jan 20, 2009, at 08:48 , Herman Bruyninckx wrote:
>
> On Tue, 20 Jan 2009, Philippe Hamelin wrote:
>
> 2009/1/20 Herman Bruyninckx
> <Herman [dot] Bruyninckx [..] ...>
>     On Mon, 19 Jan 2009, Wim Meeussen wrote:
>
>                       In the mean time, if you
>                       want an implementation
> of
>                       inverse dynamics
>                       for single chains and
> joints
>                       with only 1 DOF, you can
>                       download a
>                       modified version of KDL
> at:
>
>                       svn co
> https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/trunk
>
>                       /3rdparty/kdl/kdl-willow
>                       kdl-willow
>
>                       The inverse dynamics
> solver
>                       is implemented as a
>                       chainidsolver.hpp, in
>                      
> chainidsolver_newtoneuler.cpp
>                       and
>                      
> chainidsolver_newtoneuler.hpp
>
>                       This is basically a
> patch
>                       that was discussed on
> this
>                       mailinglist a
>                       while ago, but didn't
> make
>                       it into the repository.
>
>                 Indeed. And one of the reasons
> was that
>                 it should be given a more
> precise
>                 name: there are plenty of
> "Newton Euler"
>                 algorithms out there, and
>                 implementing more than one
> could make
>                 sense. Hence, a name for the
> solver
>                 that identified the
> implemented
>                 algorithm would be nice :-)
>
>           Also, the API of the solver is too
> restricted to
>           represent a general
>           inverse dynamics solver. We first
> need to come up
>           with a general ID
>           API before this code could be added
> to KDL.
> What are _your_ expectations of a "general ID
> API"...?
> In my opinion, the really general API is
> nothing else but
>  ReturnCode ID (KinematicChain, CurrentState,
> NewState);
> which is linked to specific implementations
> ("solvers", that each
> (can)
> have their own set of solver properties
> ("epsilon", number of
> iterations,
> numerical parameters, ...)
> Herman
> My opinion is along the same lines as Herman:
> - I think that the definition of the
> Kinematic(Dynamic)Chain must be broad
> enough to contain all the kinematic and
> dynamic parameters required for
> different types of solver.
>
>
> I do not fully agree :-) I think it is a bad idea to make
> a "fat" kinematic
> chain object, that contains all possibly useful parameters
> for kinematics
> and dynamics. It's a bad idea because then almost every
> application will
> use only a fraction of that object, which is a waste of
> resources, and a
> fact that will "scare" potential users away to simpler
> alternatives. (Do
> such simpler, but still serious alternatives exist,
> BTW...?)
>
>
> Agreed. You end up with an MS-eseque, polluted API ...
>
> - If we consider that the definition of the
> "State" contains only the state
> on a joint-by-joint basis (eg. position and
> speed), then its definition can
> also be general. However, in the case of
> serial robots, it is interesting to
> get the mass matrix and the matrix of Coriolis
> and centrifugal forces. I
> don't think these concepts really apply to all
> types of systems so it may be
> just one on the custom properties/methods of
> the solver.
>
>
> I don't think so: my idea is to use the kinematic chain as
> a very thin
> object that only stores the interconnection information;
> and all other
> relevant data structures (joint values, dynamic
> parameters, ...) are
> "aggregated" to it in a loosely coupled way,
>  <http://en.wikipedia.org/wiki/Object_composition#Aggregation>
> such as in a "scene graph" in computer animation programs.
> This gives much
> more "shallow" interfaces, at the cost of a larger variety
> of aggregated
> objects. KDL should support all the smaller objects, _and_
> generic methods
> to support aggregation while keeping the useful
> ("crosscutting aspect")
> things such as reporting, setting/getting of properties,
> error handling, ...
> <http://en.wikipedia.org/wiki/Aspect-oriented_software_development#Crosscut
> ting_Concerns>
>
>
> Agreed completely. The scene graph analogy is a good one. There can be
> quite a learning curve to these approaches, however,  we've found that
> the payoff occurs once only a small number of aggregate classes have
> been constructed.
>
> (Reading the link above makes me wonder whether Orocos
> shouldn't promote
> its "Aspect Oriented Programming" support more! :-))
>
>
> It should!
>
> Is there an open-source library who does this
> work already? Perhaps we could
> investigate it for that kind of interface
> question?
>
>
> I do not think so... But I am very interested in
> discussing about such
> libraries if they show up.
>
> Oops, I lied a bit... I do know more than one open source
> library that does
> dynamics:
> - ROBOOP <http://www.cours.polymtl.ca/roboop /> (the
> geographical proximity
>  to you makes me think you should know that already :-))
>
>
> This one has absolutely hideous real-time performance. IIRC, (nearly?)
> every variable involves a dynamic memory allocation. Bad Bad Bad! We
> changed one of our controllers from ROBoop to KDL, and had a 10x speed
> increase.
>
> S
> --
> Orocos-Users mailing list
> Orocos-Users [..] ...
> http://lists.mech.kuleuven.be/mailman/listinfo/orocos-users
>
> Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm
>
>
> You have an interesting point. I really do not know the concept of "Scene
> Graph"

<http://en.wikipedia.org/wiki/Scene_graph> :-)

> but I admit that the principle of aggregation is a good practice.
> Initially, I saw the KinematicChain like the kinematic parameters of the
> system. But from what I understand you want to use it as an "excuse" to
> interconnect frames and stores parameters? Do you have relevant information
> about scene graph to educate me? :-)

See the Wikipedia link above. And a short explanation how it is used as the
core in the computer animation package Blender:
<http://www.blender.org/development/architecture />.

The difference between point dynamics (and single ridig body dynamics) on
the one hand, and kinematic chain dynamics on the other hand is
fundamentally due to the _interconnection_ of several (ideal, nonideal)
rigid bodies and joints; so introducing a separate data structure to
represent this coupling (and _only_ this coupling) has proven to be a good
practice. At least for the framework developers! End users will most often
prefer to have more customized "fat" objects to work with, but both goals
are not each others' enemies, _if_ well designed, and _if_ (as S mentions)
some efforts are done in the framework to provide more user-friendly
aggregated objects.

Herman

Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

Ruben Smits's picture

manipulator dynamics

On 19 Jan 2009, at 08:10, Herman Bruyninckx wrote:

> On Sun, 18 Jan 2009, Wim Meeussen wrote:
>
>>>> Is there any update about the implementation of the dynamics
>>>> equations in
>>>> KDL? Is there any roadmap about this? Since the equations are
>>>> already
>>>> available, do you have an estimation of the required time to
>>>> implement
>>>> this feature at least for simple single-chain robots?
>>
>>> It has been on the agenda for quite some time already, indeed. The
>>> major
>>> problem is to find the one month of a good implementor's time,
>>> including
>>> the willingness to do some infrastructural work first: a decent and
>>> scalable design to work with dynamics for _all_ kinds of kinematic
>>> chains.
>>> The major problem that I see as being unsolved for the time being
>>> is to
>>> decide on a way to support chains that have not just the
>>> traditional single
>>> DOF joints, for example, (passive) spherical joints with three
>>> degrees of
>>> freedom.
>>
>>
>> In the mean time, if you want an implementation of inverse dynamics
>> for single chains and joints with only 1 DOF, you can download a
>> modified version of KDL at:
>>
>> svn co https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/tr...
>> kdl-willow
>>
>> The inverse dynamics solver is implemented as a chainidsolver.hpp, in
>> chainidsolver_newtoneuler.cpp and chainidsolver_newtoneuler.hpp
>>
>> This is basically a patch that was discussed on this mailinglist a
>> while ago, but didn't make it into the repository.
>>
> Indeed. And one of the reasons was that it should be given a more
> precise
> name: there are plenty of "Newton Euler" algorithms out there, and
> implementing more than one could make sense. Hence, a name for the
> solver
> that identified the implemented algorithm would be nice :-)
>

Another reason why it didn't make it into the repositories is because
it has some dynamic memory allocations in every calculation of the
inverse dynamics. We are not really fond of that.

Ruben

manipulator dynamics

On Tue, 1 Jul 2008, sachinc wrote:

> I am a new user to KDL. We are investigating the use of KDL for a personal
> robotics program being developed at the company I work for. I have some
> specific questions about some of the features in KDL that I was hoping some
> of the developers could answer.
>
> (1) Can we do manipulator dynamics in KDL?
Not yet... We have all the equations ready, and there is not so much to add
to the current version, but it has not yet been done :-(

> I have poked around a little in
> the documentation but can't seem to find examples for this.
>
> (2) How can we contribute code back? Can we submit patches that will be
> integrated into the code base?

After discussion :-) Yes, Orocos is an open source project, and as such it
welcomes contributions!

> (3) We were looking at computing the forward kinematics for intermediate link
> frames in addition to doing it for the end-effector so we can use this for
> collision checking. How can I access the intermediate frame poses?
I hope that Ruben (our KDL maintainer) will provide you with the detailed
answer to this question.

> Regards,
> Sachin Chitta
>
> Willow Garage Inc.
> (http://www.willowgarage.com)
Nice to see a posting with this origin! One of our recent PhD students (and
major Orocos developers, albeit not on the KDL sub-project) moves to the
US, and I adviced him to look for a job with Willow Garage... :-)

Best regards,

Herman

Disclaimer: http://www.kuleuven.be/cwis/email_disclaimer.htm

Ruben Smits's picture

manipulator dynamics

On Tuesday 01 July 2008 20:00:58 sachinc wrote:
> Hi,
>
> I am a new user to KDL. We are investigating the use of KDL for a personal
> robotics program being developed at the company I work for. I have some
> specific questions about some of the features in KDL that I was hoping some
> of the developers could answer.

I'll try to answer your questions as good as possible ;)

> (1) Can we do manipulator dynamics in KDL? I have poked around a little in
> the documentation but can't seem to find examples for this.

We do not yet have dynamics. But i think someone (a master student) was
working on parts of this code. I do not have any details about the code itself
or the status of this code. I'll try to figure this out soon.

> (2) How can we contribute code back? Can we submit patches that will be
> integrated into the code base?

You can always apply patches, they normally are quickly added to the code.

> (3) We were looking at computing the forward kinematics for intermediate
> link frames in addition to doing it for the end-effector so we can use this
> for collision checking. How can I access the intermediate frame poses?
>

We already have this on the svn trunk. See
:

virtual int JntToCart (const JntArray &q_in, Frame &p_out, int segmentNr=-1)

allows you to give a segmentNr for intermediate frame poses.

I don't know which version you are using but the latest release is becoming
really old. I have been triggered a lot lately to release a new version, i'm
working on that, for now it is best that you use the sources from trunk.

Ruben

> Thank you,
>
> Regards,
> Sachin Chitta
>
> Willow Garage Inc.
> (http://www.willowgarage.com)