Access to joint axis

Hi,

Could we add an access function to the axis of a Joint?
Something like this:

+ Vector Joint::JointAxis() const
+ {
+ switch(type)
+ {
+ case RotAxis:
+ return axis;
+ break;
+ case RotX:
+ return Vector(1.,0.,0.);
+ break;
+ case RotY:
+ return Vector(0.,1.,0.);
+ break;
+ case RotZ:
+ return Vector(0.,0.,1.);
+ break;
+ case TransAxis:
+ return axis;
+ break;
+ case TransX:
+ return Vector(1.,0.,0.);
+ break;
+ case TransY:
+ return Vector(0.,1.,0.);
+ break;
+ case TransZ:
+ return Vector(0.,0.,1.);
+ break;
+ case None:
+ return Vector::Zero();
+ break;
+ }
+ }

Access to joint axis

Hi,

I would like to pick up the discussion below. Can we add an access
function for the joint axis?

Wim

On Wed, Feb 4, 2009 at 2:10 PM, Wim Meeussen <meeussen [..] ...> wrote:
> Hi,
>
> Could we add an access function to the axis of a Joint?
> Something like this:
>
>
> + Vector Joint::JointAxis() const
> + {
> + switch(type)
> + {
> + case RotAxis:
> + return axis;
> + break;
> + case RotX:
> + return Vector(1.,0.,0.);
> + break;
> + case RotY:
> + return Vector(0.,1.,0.);
> + break;
> + case RotZ:
> + return Vector(0.,0.,1.);
> + break;
> + case TransAxis:
> + return axis;
> + break;
> + case TransX:
> + return Vector(1.,0.,0.);
> + break;
> + case TransY:
> + return Vector(0.,1.,0.);
> + break;
> + case TransZ:
> + return Vector(0.,0.,1.);
> + break;
> + case None:
> + return Vector::Zero();
> + break;
> + }
> + }
>
> --
> --
> Wim Meeussen
> Willow Garage Inc.
> <http://www.willowgarage.com)
>

Ruben Smits's picture

Access to joint axis

On Wednesday 04 February 2009 23:10:49 Wim Meeussen wrote:
> Hi,
>
> Could we add an access function to the axis of a Joint?
> Something like this:
>
>
> + Vector Joint::JointAxis() const
> + {
> + switch(type)
> + {
> + case RotAxis:
> + return axis;
> + break;
> + case RotX:
> + return Vector(1.,0.,0.);
> + break;
> + case RotY:
> + return Vector(0.,1.,0.);
> + break;
> + case RotZ:
> + return Vector(0.,0.,1.);
> + break;
> + case TransAxis:
> + return axis;
> + break;
> + case TransX:
> + return Vector(1.,0.,0.);
> + break;
> + case TransY:
> + return Vector(0.,1.,0.);
> + break;
> + case TransZ:
> + return Vector(0.,0.,1.);
> + break;
> + case None:
> + return Vector::Zero();
> + break;
> + }
> + }

Yes we could. It would return the joint axis it the joint's reference frame.
Maybe we could also extend this and add the same function to the segment
class, which would then return the joint axis in the segments reference frame.

Ruben

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

>

Access to joint axis

On Wed, Feb 4, 2009 at 11:53 PM, Ruben Smits
<ruben [dot] smits [..] ...> wrote:
> On Wednesday 04 February 2009 23:10:49 Wim Meeussen wrote:
>> Hi,
>>
>> Could we add an access function to the axis of a Joint?
>> Something like this:
>>
>>
>> + Vector Joint::JointAxis() const
>> + {
>> + switch(type)
>> + {
>> + case RotAxis:
>> + return axis;
>> + break;
>> + case RotX:
>> + return Vector(1.,0.,0.);
>> + break;
>> + case RotY:
>> + return Vector(0.,1.,0.);
>> + break;
>> + case RotZ:
>> + return Vector(0.,0.,1.);
>> + break;
>> + case TransAxis:
>> + return axis;
>> + break;
>> + case TransX:
>> + return Vector(1.,0.,0.);
>> + break;
>> + case TransY:
>> + return Vector(0.,1.,0.);
>> + break;
>> + case TransZ:
>> + return Vector(0.,0.,1.);
>> + break;
>> + case None:
>> + return Vector::Zero();
>> + break;
>> + }
>> + }
>
> Yes we could. It would return the joint axis it the joint's reference frame.
> Maybe we could also extend this and add the same function to the segment
> class, which would then return the joint axis in the segments reference frame.

The segment has a reference frame, and the joint is defined in that
segment reference frame. But the joint itself does not have a
reference frame, it is only an axis and a position of that axis,
represented in the segment reference frame. So, a getJointAxis()
function would return the same if called from the joint or from the
segment: the joint axis, represented in the segment reference frame.

Wim

ps. Maybe getAxis() is a better name than getJointAxis() ? Since we
call it on a joint anyway.

Access to joint axis

On Thu, 5 Feb 2009, Ruben Smits wrote:

> On Wednesday 04 February 2009 23:10:49 Wim Meeussen wrote:
>> Hi,
>>
>> Could we add an access function to the axis of a Joint?
>> Something like this:
>>
>>
>> + Vector Joint::JointAxis() const
>> + {
>> + switch(type)
>> + {
>> + case RotAxis:
>> + return axis;
>> + break;
>> + case RotX:
>> + return Vector(1.,0.,0.);
>> + break;
>> + case RotY:
>> + return Vector(0.,1.,0.);
>> + break;
>> + case RotZ:
>> + return Vector(0.,0.,1.);
>> + break;
>> + case TransAxis:
>> + return axis;
>> + break;
>> + case TransX:
>> + return Vector(1.,0.,0.);
>> + break;
>> + case TransY:
>> + return Vector(0.,1.,0.);
>> + break;
>> + case TransZ:
>> + return Vector(0.,0.,1.);
>> + break;
>> + case None:
>> + return Vector::Zero();
>> + break;
>> + }
>> + }
>
> Yes we could. It would return the joint axis it the joint's reference frame.
> Maybe we could also extend this and add the same function to the segment
> class, which would then return the joint axis in the segments reference frame.
>
There is an important difference between Joint and Segment in this case:
the Segment can have multiple Joints! So, the API will be a bit different:
Segments will be able to get back a "list" or "bag" of the Joints connected
to them.

Herman

Ruben Smits's picture

Access to joint axis

On Thursday 05 February 2009 09:38:07 Herman Bruyninckx wrote:
> On Thu, 5 Feb 2009, Ruben Smits wrote:
> > On Wednesday 04 February 2009 23:10:49 Wim Meeussen wrote:
> >> Hi,
> >>
> >> Could we add an access function to the axis of a Joint?
> >> Something like this:
> >>
> >>
> >> + Vector Joint::JointAxis() const
> >> + {
> >> + switch(type)
> >> + {
> >> + case RotAxis:
> >> + return axis;
> >> + break;
> >> + case RotX:
> >> + return Vector(1.,0.,0.);
> >> + break;
> >> + case RotY:
> >> + return Vector(0.,1.,0.);
> >> + break;
> >> + case RotZ:
> >> + return Vector(0.,0.,1.);
> >> + break;
> >> + case TransAxis:
> >> + return axis;
> >> + break;
> >> + case TransX:
> >> + return Vector(1.,0.,0.);
> >> + break;
> >> + case TransY:
> >> + return Vector(0.,1.,0.);
> >> + break;
> >> + case TransZ:
> >> + return Vector(0.,0.,1.);
> >> + break;
> >> + case None:
> >> + return Vector::Zero();
> >> + break;
> >> + }
> >> + }
> >
> > Yes we could. It would return the joint axis it the joint's reference
> > frame. Maybe we could also extend this and add the same function to the
> > segment class, which would then return the joint axis in the segments
> > reference frame.
>
> There is an important difference between Joint and Segment in this case:
> the Segment can have multiple Joints! So, the API will be a bit different:
> Segments will be able to get back a "list" or "bag" of the Joints connected
> to them.

a Segment can indeed have multiple _children_ joints, but it (in case of
branching structures) only have one _parent_ frame.

Ruben

> Herman

Access to joint axis

On Thu, 5 Feb 2009, Ruben Smits wrote:

> On Thursday 05 February 2009 09:38:07 Herman Bruyninckx wrote:
>> On Thu, 5 Feb 2009, Ruben Smits wrote:
>>> On Wednesday 04 February 2009 23:10:49 Wim Meeussen wrote:
>>>> Hi,
>>>>
>>>> Could we add an access function to the axis of a Joint?
>>>> Something like this:
>>>>
>>>>
>>>> + Vector Joint::JointAxis() const
>>>> + {
>>>> + switch(type)
>>>> + {
>>>> + case RotAxis:
>>>> + return axis;
>>>> + break;
>>>> + case RotX:
>>>> + return Vector(1.,0.,0.);
>>>> + break;
>>>> + case RotY:
>>>> + return Vector(0.,1.,0.);
>>>> + break;
>>>> + case RotZ:
>>>> + return Vector(0.,0.,1.);
>>>> + break;
>>>> + case TransAxis:
>>>> + return axis;
>>>> + break;
>>>> + case TransX:
>>>> + return Vector(1.,0.,0.);
>>>> + break;
>>>> + case TransY:
>>>> + return Vector(0.,1.,0.);
>>>> + break;
>>>> + case TransZ:
>>>> + return Vector(0.,0.,1.);
>>>> + break;
>>>> + case None:
>>>> + return Vector::Zero();
>>>> + break;
>>>> + }
>>>> + }
>>>
>>> Yes we could. It would return the joint axis it the joint's reference
>>> frame. Maybe we could also extend this and add the same function to the
>>> segment class, which would then return the joint axis in the segments
>>> reference frame.
>>
>> There is an important difference between Joint and Segment in this case:
>> the Segment can have multiple Joints! So, the API will be a bit different:
>> Segments will be able to get back a "list" or "bag" of the Joints connected
>> to them.
>
> a Segment can indeed have multiple _children_ joints, but it (in case of
> branching structures) only have one _parent_ frame.
>
True! Eventually we will include graphs too, but they will always be solved
by forming temporary tree structures anyway, so I agree that at this moment
this would not impose a too severe constraint.

Herman

Ruben Smits's picture

Access to joint axis

On Thursday 05 February 2009 09:44:24 Ruben Smits wrote:
> On Thursday 05 February 2009 09:38:07 Herman Bruyninckx wrote:
> > On Thu, 5 Feb 2009, Ruben Smits wrote:
> > > On Wednesday 04 February 2009 23:10:49 Wim Meeussen wrote:
> > >> Hi,
> > >>
> > >> Could we add an access function to the axis of a Joint?
> > >> Something like this:
> > >>
> > >>
> > >> + Vector Joint::JointAxis() const
> > >> + {
> > >> + switch(type)
> > >> + {
> > >> + case RotAxis:
> > >> + return axis;
> > >> + break;
> > >> + case RotX:
> > >> + return Vector(1.,0.,0.);
> > >> + break;
> > >> + case RotY:
> > >> + return Vector(0.,1.,0.);
> > >> + break;
> > >> + case RotZ:
> > >> + return Vector(0.,0.,1.);
> > >> + break;
> > >> + case TransAxis:
> > >> + return axis;
> > >> + break;
> > >> + case TransX:
> > >> + return Vector(1.,0.,0.);
> > >> + break;
> > >> + case TransY:
> > >> + return Vector(0.,1.,0.);
> > >> + break;
> > >> + case TransZ:
> > >> + return Vector(0.,0.,1.);
> > >> + break;
> > >> + case None:
> > >> + return Vector::Zero();
> > >> + break;
> > >> + }
> > >> + }
> > >
> > > Yes we could. It would return the joint axis it the joint's reference
> > > frame. Maybe we could also extend this and add the same function to the
> > > segment class, which would then return the joint axis in the segments
> > > reference frame.
> >
> > There is an important difference between Joint and Segment in this case:
> > the Segment can have multiple Joints! So, the API will be a bit
> > different: Segments will be able to get back a "list" or "bag" of the
> > Joints connected to them.
>
> a Segment can indeed have multiple _children_ joints, but it (in case of
> branching structures) only have one _parent_ frame.

I off-course mean _parent_ joint!!!!!!!

Ruben

Access to joint axis

On Wed, 4 Feb 2009, Wim Meeussen wrote:

> Could we add an access function to the axis of a Joint?

The frame in which this axis is to be interpreted is always unambiguously
clear?

Herman

> Something like this:
>
>
> + Vector Joint::JointAxis() const
> + {
> + switch(type)
> + {
> + case RotAxis:
> + return axis;
> + break;
> + case RotX:
> + return Vector(1.,0.,0.);
> + break;
> + case RotY:
> + return Vector(0.,1.,0.);
> + break;
> + case RotZ:
> + return Vector(0.,0.,1.);
> + break;
> + case TransAxis:
> + return axis;
> + break;
> + case TransX:
> + return Vector(1.,0.,0.);
> + break;
> + case TransY:
> + return Vector(0.,1.,0.);
> + break;
> + case TransZ:
> + return Vector(0.,0.,1.);
> + break;
> + case None:
> + return Vector::Zero();
> + break;
> + }
> + }
>
>

Ruben Smits's picture

Access to joint axis

On Thursday 05 February 2009 09:50:39 Herman Bruyninckx wrote:
> On Thu, 5 Feb 2009, Ruben Smits wrote:
> > On Thursday 05 February 2009 09:38:07 Herman Bruyninckx wrote:
> >> On Thu, 5 Feb 2009, Ruben Smits wrote:
> >>> On Wednesday 04 February 2009 23:10:49 Wim Meeussen wrote:
> >>>> Hi,
> >>>>
> >>>> Could we add an access function to the axis of a Joint?
> >>>> Something like this:
> >>>>
> >>>>
> >>>> + Vector Joint::JointAxis() const
> >>>> + {
> >>>> + switch(type)
> >>>> + {
> >>>> + case RotAxis:
> >>>> + return axis;
> >>>> + break;
> >>>> + case RotX:
> >>>> + return Vector(1.,0.,0.);
> >>>> + break;
> >>>> + case RotY:
> >>>> + return Vector(0.,1.,0.);
> >>>> + break;
> >>>> + case RotZ:
> >>>> + return Vector(0.,0.,1.);
> >>>> + break;
> >>>> + case TransAxis:
> >>>> + return axis;
> >>>> + break;
> >>>> + case TransX:
> >>>> + return Vector(1.,0.,0.);
> >>>> + break;
> >>>> + case TransY:
> >>>> + return Vector(0.,1.,0.);
> >>>> + break;
> >>>> + case TransZ:
> >>>> + return Vector(0.,0.,1.);
> >>>> + break;
> >>>> + case None:
> >>>> + return Vector::Zero();
> >>>> + break;
> >>>> + }
> >>>> + }
> >>>
> >>> Yes we could. It would return the joint axis it the joint's reference
> >>> frame. Maybe we could also extend this and add the same function to the
> >>> segment class, which would then return the joint axis in the segments
> >>> reference frame.
> >>
> >> There is an important difference between Joint and Segment in this case:
> >> the Segment can have multiple Joints! So, the API will be a bit
> >> different: Segments will be able to get back a "list" or "bag" of the
> >> Joints connected to them.
> >
> > a Segment can indeed have multiple _children_ joints, but it (in case of
> > branching structures) only have one _parent_ frame.
>
> True! Eventually we will include graphs too, but they will always be solved
> by forming temporary tree structures anyway, so I agree that at this moment
> this would not impose a too severe constraint.

But will this list of children joints/segments be part of the parent segment
or part of the kinematic structure (chain/tree)

We already agreed that a Segment is the collection of a Body(/Inertia) and a
Joint.

My proposal would be to let the Segment store the joint, and its location (wrt
to the segments reference frame), and the inertia expressed in the reference
frame of the segment.

The kinematic structure will store the information of the parent segments and
children, and the offset frames between the parents reference frame and the
childrens joint reference frame.

Ruben

Access to joint axis

> We already agreed that a Segment is the collection of a Body(/Inertia) and a
> Joint.
>
> My proposal would be to let the Segment store the joint, and its location (wrt
> to the segments reference frame), and the inertia expressed in the reference
> frame of the segment.
>
> The kinematic structure will store the information of the parent segments and
> children, and the offset frames between the parents reference frame and the
> childrens joint reference frame.

A few thoughts:
* As we discussed before, I think you mean that the position of the
joint axis, relative to the reference frame of the segment, is a
property of the joint (as the position of the center of gravity of the
body, relative to the reference frame of the segment, is a property of
the body).

* You define the offset frames between the parents reference frame and
the children's joint reference frame in the kinematic structure. This
means that the constructor of a segment does not need a reference
frame any more, because you put this information in the kinematic
structure. The result is that you cannot request the "pose(q)" of a
segment any more. --> I suggest to leave the information of the
reference frame in the segment (where it is now), and only put the
connection information in the kinematic structure: the kinematic
structure knows about child and parent segments, not about their
reference frames.

Wim

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

Ruben Smits's picture

Access to joint axis

On Thursday 05 February 2009 19:17:07 you wrote:
> > We already agreed that a Segment is the collection of a Body(/Inertia)
> > and a Joint.
> >
> > My proposal would be to let the Segment store the joint, and its location
> > (wrt to the segments reference frame), and the inertia expressed in the
> > reference frame of the segment.
> >
> > The kinematic structure will store the information of the parent segments
> > and children, and the offset frames between the parents reference frame
> > and the childrens joint reference frame.
>
> A few thoughts:
> * As we discussed before, I think you mean that the position of the
> joint axis, relative to the reference frame of the segment, is a
> property of the joint (as the position of the center of gravity of the
> body, relative to the reference frame of the segment, is a property of
> the body).

No, I exactly mean what I said ;), I see a joint as an axis, which can return
a pose between its zero position and it's position at jointvalue q.

I really think that the position of a joint (its axis) in the reference frame
of the segment is information that belongs to the segment. Because without the
reference frame of the segment this information has no meaning. That's why IMO
it belongs to the segment. The same holds for the inertia. The inertia is
expressed in some reference frame attached to the segment. If it is not the
reference frame of the segment itself, at construction the reference frame of
the inertia has to be given such that the constructor of the segment can
transform the inertia to its own reference frame.

> * You define the offset frames between the parents reference frame and
> the children's joint reference frame in the kinematic structure. This
> means that the constructor of a segment does not need a reference
> frame any more, because you put this information in the kinematic
> structure. The result is that you cannot request the "pose(q)" of a
> segment any more.

What does the pose of a segment really means?

I think it is the relative pose between its reference frame at the zero
position of its joint and its reference frame at jointvalue q. For this
calculation it does not matter how the segment is connected to its parents,
which makes perfect sense to me. A segment does not know where its parents or
children are. This information belongs to the the interconnection structure.

> --> I suggest to leave the information of the
> reference frame in the segment (where it is now), and only put the
> connection information in the kinematic structure: the kinematic
> structure knows about child and parent segments, not about their
> reference frames.
>

As I stated above, I do not agree :p, since it is a redesign proposition I do
not think we should be scared to change things completely. If we redesign, we
should end up in a better decoupled and semantically sound representation for
kinematic structures.

Ruben

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

Access to joint axis

> I really think that the position of a joint (its axis) in the reference frame
> of the segment is information that belongs to the segment. Because without the
> reference frame of the segment this information has no meaning. That's why IMO
> it belongs to the segment. The same holds for the inertia. The inertia is
> expressed in some reference frame attached to the segment. If it is not the
> reference frame of the segment itself, at construction the reference frame of
> the inertia has to be given such that the constructor of the segment can
> transform the inertia to its own reference frame.

You say the joint position belongs to the segment because it has no
meaning without the reference frame of the segment. Then the joint
axis should also belong to the segment, because is has no meaning
without the reference frame of the segment. So you would end up with a
joint object only containing friction/limits/etc and a type Rot/Trans.

Or if you go the route equivalent to the one you suggest for the
inertia: A joint would define an axis and position, relative to its
_own_ reference frame. And when you construct a segment, you specify
where the joint reference frame is relative to the segment reference
frame. But in this case a joint would still contain an axis and a
position, but in its own reference frame. The result is just an extra
reference frame.

Or we could keep it simple, and define the joint axis and position
directly into the segment reference frame.

> As I stated above, I do not agree :p, since it is a redesign proposition I do
> not think we should be scared to change things completely. If we redesign, we
> should end up in a better decoupled and semantically sound representation for
> kinematic structures.

Is this a short term plan? If not, will you accept any patches for the
current kdl version?

Wim

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

Access to joint axis

On Fri, 6 Feb 2009, Wim Meeussen wrote:

>> I really think that the position of a joint (its axis) in the reference frame
>> of the segment is information that belongs to the segment. Because without the
>> reference frame of the segment this information has no meaning. That's why IMO
>> it belongs to the segment. The same holds for the inertia. The inertia is
>> expressed in some reference frame attached to the segment. If it is not the
>> reference frame of the segment itself, at construction the reference frame of
>> the inertia has to be given such that the constructor of the segment can
>> transform the inertia to its own reference frame.
>
> You say the joint position belongs to the segment because it has no
> meaning without the reference frame of the segment. Then the joint
> axis should also belong to the segment, because is has no meaning
> without the reference frame of the segment. So you would end up with a
> joint object only containing friction/limits/etc and a type Rot/Trans.

Yes. And all of its time derivatives, and actuator torques, ...

Herman

> Or if you go the route equivalent to the one you suggest for the
> inertia: A joint would define an axis and position, relative to its
> _own_ reference frame. And when you construct a segment, you specify
> where the joint reference frame is relative to the segment reference
> frame. But in this case a joint would still contain an axis and a
> position, but in its own reference frame. The result is just an extra
> reference frame.
>
> Or we could keep it simple, and define the joint axis and position
> directly into the segment reference frame.
>
>
>> As I stated above, I do not agree :p, since it is a redesign proposition I do
>> not think we should be scared to change things completely. If we redesign, we
>> should end up in a better decoupled and semantically sound representation for
>> kinematic structures.
>
> Is this a short term plan? If not, will you accept any patches for the
> current kdl version?
>
> Wim
>
>
>
> --
> Wim Meeussen
> Willow Garage Inc.
> <http://www.willowgarage.com)
>

Access to joint axis

>> You say the joint position belongs to the segment because it has no
>> meaning without the reference frame of the segment. Then the joint
>> axis should also belong to the segment, because is has no meaning
>> without the reference frame of the segment. So you would end up with a
>> joint object only containing friction/limits/etc and a type Rot/Trans.

> Yes. And all of its time derivatives, and actuator torques, ...

Yes, and this is in my opinion a good option to consider for a redesign.

Apart from that, the _current_ kdl design is different (it has the
orientation of the joint axis inside the joint), and we were trying to
get a extra joint constructor (that is compatible with the current
design) into the current kdl tree. My argument above was that putting
the joint position outside the joint is not compatible with the
current design: the position of the joint axis fits together with the
orientation of the joint axis, which is currently inside the joint
object.

I'm still hoping that we could collaborate on the kdl project, and
contribute code and ideas.

Wim

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

Access to joint axis

On Sun, 8 Feb 2009, Wim Meeussen wrote:

>>> You say the joint position belongs to the segment because it has no
>>> meaning without the reference frame of the segment. Then the joint
>>> axis should also belong to the segment, because is has no meaning
>>> without the reference frame of the segment. So you would end up with a
>>> joint object only containing friction/limits/etc and a type Rot/Trans.
>
>> Yes. And all of its time derivatives, and actuator torques, ...
>
> Yes, and this is in my opinion a good option to consider for a redesign.

I think (hope...) that adding such extra information does not need a
redesign, but should be possible via specialisation.

> Apart from that, the _current_ kdl design is different (it has the
> orientation of the joint axis inside the joint), and we were trying to
> get a extra joint constructor (that is compatible with the current
> design) into the current kdl tree. My argument above was that putting
> the joint position outside the joint is not compatible with the
> current design: the position of the joint axis fits together with the
> orientation of the joint axis, which is currently inside the joint
> object.

Agreed. But since we are still before 1.0, such changes should be
possible, _if_ well thought-out and supported by the community. And that's
what we are currently discussing...

> I'm still hoping that we could collaborate on the kdl project, and
> contribute code and ideas.

Me too! But you _are_ contributing code and ideas! It's just not so clear
to all parties involved what is "the best" way to proceed at this moment.
There is only one thing worse than not having patches included in the main
tree: having patches included that can lead to large legacy overhead...

Herman

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

Access to joint axis

On Thu, 5 Feb 2009, Ruben Smits wrote:

> On Thursday 05 February 2009 09:50:39 Herman Bruyninckx wrote:
>> On Thu, 5 Feb 2009, Ruben Smits wrote:
>>> On Thursday 05 February 2009 09:38:07 Herman Bruyninckx wrote:
>>>> On Thu, 5 Feb 2009, Ruben Smits wrote:
>>>>> On Wednesday 04 February 2009 23:10:49 Wim Meeussen wrote:
>>>>>> Hi,
>>>>>>
>>>>>> Could we add an access function to the axis of a Joint?
>>>>>> Something like this:
>>>>>>
>>>>>>
>>>>>> + Vector Joint::JointAxis() const
>>>>>> + {
>>>>>> + switch(type)
>>>>>> + {
>>>>>> + case RotAxis:
>>>>>> + return axis;
>>>>>> + break;
>>>>>> + case RotX:
>>>>>> + return Vector(1.,0.,0.);
>>>>>> + break;
>>>>>> + case RotY:
>>>>>> + return Vector(0.,1.,0.);
>>>>>> + break;
>>>>>> + case RotZ:
>>>>>> + return Vector(0.,0.,1.);
>>>>>> + break;
>>>>>> + case TransAxis:
>>>>>> + return axis;
>>>>>> + break;
>>>>>> + case TransX:
>>>>>> + return Vector(1.,0.,0.);
>>>>>> + break;
>>>>>> + case TransY:
>>>>>> + return Vector(0.,1.,0.);
>>>>>> + break;
>>>>>> + case TransZ:
>>>>>> + return Vector(0.,0.,1.);
>>>>>> + break;
>>>>>> + case None:
>>>>>> + return Vector::Zero();
>>>>>> + break;
>>>>>> + }
>>>>>> + }
>>>>>
>>>>> Yes we could. It would return the joint axis it the joint's reference
>>>>> frame. Maybe we could also extend this and add the same function to the
>>>>> segment class, which would then return the joint axis in the segments
>>>>> reference frame.
>>>>
>>>> There is an important difference between Joint and Segment in this case:
>>>> the Segment can have multiple Joints! So, the API will be a bit
>>>> different: Segments will be able to get back a "list" or "bag" of the
>>>> Joints connected to them.
>>>
>>> a Segment can indeed have multiple _children_ joints, but it (in case of
>>> branching structures) only have one _parent_ frame.
>>
>> True! Eventually we will include graphs too, but they will always be solved
>> by forming temporary tree structures anyway, so I agree that at this moment
>> this would not impose a too severe constraint.
>
> But will this list of children joints/segments be part of the parent segment
> or part of the kinematic structure (chain/tree)
>
> We already agreed that a Segment is the collection of a Body(/Inertia) and a
> Joint.
>
> My proposal would be to let the Segment store the joint, and its location (wrt
> to the segments reference frame), and the inertia expressed in the reference
> frame of the segment.
>
> The kinematic structure will store the information of the parent segments and
> children, and the offset frames between the parents reference frame and the
> childrens joint reference frame.

Good suggestion, with an attractive degree of decoupling and clarity!

Herman

Access to joint axis

>> > So I will apply the joint2.patch if the unit-tests are not failing any
>> > more, and specific tests for the new joint constructor are added.

>> As I suggested before, this problem seems to be related to the solver,
>> and not to my patch. When I run the solvertest _without_ my patch, and
>> seed the random number generator, the test still fails from time to
>> time. The problem is that the solver does not converge within a
>> certain number of iterations. You can't expect me to debug this
>> solver. This seems to be an endless battle to get a very simple patch
>> into kdl.

> Ok, since it is not due to the solver, I'll apply your patch. But I hope to
> have the new design ready asap after the discussion about the new design is
> finished.
>
> Can you resend the patch with the usage of the Rotation::Rot2 function instead
> of your own Rotation calculation?

Ok, so I added the rot2 function, and seeded the rnd number generators
in the solvertest. You'll see the tests fail from time to time,
depending on which random numbers were generated. Also, the joint axis
access function is added. The patch is in attachment. Thanks for
sticking with me on this one.

Wim

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

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

>

Ruben Smits's picture

Access to joint axis

On Tuesday 17 February 2009 01:44:10 Wim Meeussen wrote:
> >> > So I will apply the joint2.patch if the unit-tests are not failing any
> >> > more, and specific tests for the new joint constructor are added.
> >>
> >> As I suggested before, this problem seems to be related to the solver,
> >> and not to my patch. When I run the solvertest _without_ my patch, and
> >> seed the random number generator, the test still fails from time to
> >> time. The problem is that the solver does not converge within a
> >> certain number of iterations. You can't expect me to debug this
> >> solver. This seems to be an endless battle to get a very simple patch
> >> into kdl.
> >
> > Ok, since it is not due to the solver, I'll apply your patch. But I hope
> > to have the new design ready asap after the discussion about the new
> > design is finished.
> >
> > Can you resend the patch with the usage of the Rotation::Rot2 function
> > instead of your own Rotation calculation?
>
> Ok, so I added the rot2 function, and seeded the rnd number generators
> in the solvertest. You'll see the tests fail from time to time,
> depending on which random numbers were generated. Also, the joint axis
> access function is added. The patch is in attachment. Thanks for
> sticking with me on this one.

It is committed on trunk:

svn ci -m"Added arbitrary axis joint construction, thanks Wim for sending the
patch"
Sending src/joint.cpp
Sending src/joint.hpp
Sending src/segment.cpp
Sending tests/solvertest.cpp
Sending tests/solvertest.hpp
Transmitting file data .....
Committed revision 29985.

Ruben

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

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

>

Ruben Smits's picture

Access to joint axis

On Friday 06 February 2009 19:22:40 you wrote:
> > I really think that the position of a joint (its axis) in the reference
> > frame of the segment is information that belongs to the segment. Because
> > without the reference frame of the segment this information has no
> > meaning. That's why IMO it belongs to the segment. The same holds for the
> > inertia. The inertia is expressed in some reference frame attached to the
> > segment. If it is not the reference frame of the segment itself, at
> > construction the reference frame of the inertia has to be given such that
> > the constructor of the segment can transform the inertia to its own
> > reference frame.
>
> You say the joint position belongs to the segment because it has no
> meaning without the reference frame of the segment. Then the joint
> axis should also belong to the segment, because is has no meaning
> without the reference frame of the segment. So you would end up with a
> joint object only containing friction/limits/etc and a type Rot/Trans.
>
> Or if you go the route equivalent to the one you suggest for the
> inertia: A joint would define an axis and position, relative to its
> _own_ reference frame. And when you construct a segment, you specify
> where the joint reference frame is relative to the segment reference
> frame. But in this case a joint would still contain an axis and a
> position, but in its own reference frame. The result is just an extra
> reference frame.
>
> Or we could keep it simple, and define the joint axis and position
> directly into the segment reference frame.
>
> > As I stated above, I do not agree :p, since it is a redesign proposition
> > I do not think we should be scared to change things completely. If we
> > redesign, we should end up in a better decoupled and semantically sound
> > representation for kinematic structures.
>
> Is this a short term plan? If not, will you accept any patches for the
> current kdl version?

We will accept patches for the current kdl version ;). But i'm preparing a
draft document and api for the new kinematic structure design. I hope to post
it this week on the mailinglist and hope to get _lots_ ;) of feedback. If the
api is crystallized we can start a development branch to port the
implementations.

So I will apply the joint2.patch if the unit-tests are not failing any more,
and specific tests for the new joint constructor are added.

Ruben

Access to joint axis

>> Is this a short term plan? If not, will you accept any patches for the
>> current kdl version?

> We will accept patches for the current kdl version ;). But i'm preparing a
> draft document and api for the new kinematic structure design. I hope to post
> it this week on the mailinglist and hope to get _lots_ ;) of feedback. If the
> api is crystallized we can start a development branch to port the
> implementations.

> So I will apply the joint2.patch if the unit-tests are not failing any more,
> and specific tests for the new joint constructor are added.

As I suggested before, this problem seems to be related to the solver,
and not to my patch. When I run the solvertest _without_ my patch, and
seed the random number generator, the test still fails from time to
time. The problem is that the solver does not converge within a
certain number of iterations. You can't expect me to debug this
solver. This seems to be an endless battle to get a very simple patch
into kdl.

Wim

$ ./solvertest
.F

solvertest.cpp:315:Assertion
Test name: SolverTest::FkPosAndIkPosTest
assertion failed
- Expression: 0<=ret

Failures !!!
Run: 1 Failure total: 1 Failures: 1 Errors: 0

Access to joint axis

On Feb 10, 2009, at 09:35 , Herman Bruyninckx wrote:

> On Tue, 10 Feb 2009, S Roderick wrote:
>
>> On Feb 10, 2009, at 03:42 , Ruben Smits wrote:
>>
>>> On Friday 06 February 2009 19:22:40 you wrote:
>>>>> I really think that the position of a joint (its axis) in the
>>>>> reference
>>>>> frame of the segment is information that belongs to the segment.
>>>>> Because
>>>>> without the reference frame of the segment this information has no
>>>>> meaning. That's why IMO it belongs to the segment. The same holds
>>>>> for the
>>>>> inertia. The inertia is expressed in some reference frame attached
>>>>> to the
>>>>> segment. If it is not the reference frame of the segment itself,
>>>>> at
>>>>> construction the reference frame of the inertia has to be given
>>>>> such that
>>>>> the constructor of the segment can transform the inertia to its
>>>>> own
>>>>> reference frame.
>>>>
>>>> You say the joint position belongs to the segment because it has no
>>>> meaning without the reference frame of the segment. Then the joint
>>>> axis should also belong to the segment, because is has no meaning
>>>> without the reference frame of the segment. So you would end up
>>>> with a
>>>> joint object only containing friction/limits/etc and a type Rot/
>>>> Trans.
>>>>
>>>> Or if you go the route equivalent to the one you suggest for the
>>>> inertia: A joint would define an axis and position, relative to its
>>>> _own_ reference frame. And when you construct a segment, you
>>>> specify
>>>> where the joint reference frame is relative to the segment
>>>> reference
>>>> frame. But in this case a joint would still contain an axis and a
>>>> position, but in its own reference frame. The result is just an
>>>> extra
>>>> reference frame.
>>>>
>>>> Or we could keep it simple, and define the joint axis and position
>>>> directly into the segment reference frame.
>>>>
>>>>> As I stated above, I do not agree :p, since it is a redesign
>>>>> proposition
>>>>> I do not think we should be scared to change things completely. If
>>>>> we
>>>>> redesign, we should end up in a better decoupled and semantically
>>>>> sound
>>>>> representation for kinematic structures.
>>>>
>>>> Is this a short term plan? If not, will you accept any patches for
>>>> the
>>>> current kdl version?
>>>
>>> We will accept patches for the current kdl version ;). But i'm
>>> preparing a
>>> draft document and api for the new kinematic structure design. I
>>> hope to post
>>> it this week on the mailinglist and hope to get _lots_ ;) of
>>> feedback. If the
>>> api is crystallized we can start a development branch to port the
>>> implementations.
>>
>> I hope there'll be UML diagrams in there? That way, us mere mortals
>> can provide useful feedback after getting got lost long ago, in the
>> mountain of wonderful technical detail of this discussion. I'd say
>> the
>> same for the "manipulator dynamics" thread, too.
>>
> I really think this discussion cannot be captured in UML... It's
> about the
> most appropriate _data_ structures and most efficient _solver
> algorithms_
> to deal with kinematics and dynamics. But I hope you can prove me
> wrong,
> such that I will be able to learn something new :-)
> (The resulting class design is, of course, representable in UML.)

This is all I was after - the class design. It'll help me (at least)
understand how things are going to change, and the consequences for my
projects/code.

And one should hope that the final design *could* be captured in
UML ... not much hope for software *engineering* otherwise ... :-)
S

Access to joint axis

On Feb 10, 2009, at 03:42 , Ruben Smits wrote:

> On Friday 06 February 2009 19:22:40 you wrote:
>>> I really think that the position of a joint (its axis) in the
>>> reference
>>> frame of the segment is information that belongs to the segment.
>>> Because
>>> without the reference frame of the segment this information has no
>>> meaning. That's why IMO it belongs to the segment. The same holds
>>> for the
>>> inertia. The inertia is expressed in some reference frame attached
>>> to the
>>> segment. If it is not the reference frame of the segment itself, at
>>> construction the reference frame of the inertia has to be given
>>> such that
>>> the constructor of the segment can transform the inertia to its own
>>> reference frame.
>>
>> You say the joint position belongs to the segment because it has no
>> meaning without the reference frame of the segment. Then the joint
>> axis should also belong to the segment, because is has no meaning
>> without the reference frame of the segment. So you would end up
>> with a
>> joint object only containing friction/limits/etc and a type Rot/
>> Trans.
>>
>> Or if you go the route equivalent to the one you suggest for the
>> inertia: A joint would define an axis and position, relative to its
>> _own_ reference frame. And when you construct a segment, you specify
>> where the joint reference frame is relative to the segment reference
>> frame. But in this case a joint would still contain an axis and a
>> position, but in its own reference frame. The result is just an extra
>> reference frame.
>>
>> Or we could keep it simple, and define the joint axis and position
>> directly into the segment reference frame.
>>
>>> As I stated above, I do not agree :p, since it is a redesign
>>> proposition
>>> I do not think we should be scared to change things completely. If
>>> we
>>> redesign, we should end up in a better decoupled and semantically
>>> sound
>>> representation for kinematic structures.
>>
>> Is this a short term plan? If not, will you accept any patches for
>> the
>> current kdl version?
>
> We will accept patches for the current kdl version ;). But i'm
> preparing a
> draft document and api for the new kinematic structure design. I
> hope to post
> it this week on the mailinglist and hope to get _lots_ ;) of
> feedback. If the
> api is crystallized we can start a development branch to port the
> implementations.

I hope there'll be UML diagrams in there? That way, us mere mortals
can provide useful feedback after getting got lost long ago, in the
mountain of wonderful technical detail of this discussion. I'd say the
same for the "manipulator dynamics" thread, too.

Cheers
S