Since the recent discussion about the description of the kinematics in
KDL, i was thinking of a new design.
I would like to make a base class for Joint, this will define two
functions that are needed to make the solvers work, they are the
functions that calculate position and velocity information from the
jointspace to the cartesian space:
JntToCart(PosValue), JntToCart(PosValue,TwistValue)
Every type of Joint will have to inherit from this class, some
examples RotationalJoint, TranslationalJoint, SphericalJoint,
HelicalJoint, GimbalJoint, this list can be long, but it allows us to
support more type of joints, also adding a new type of joint will be a
lot easier.
Every type of joint will have to specify how it PosValue, TwistValue,
AccelerationValue looks like, this can be a single value for 1D joints
but also be a quaternion for a spherical joint.
Also for this PosValue we need a base class to allow general solvers
to be usefull for all types of joints.
To define the rest of the information which is inside of a joint, my
idea was to put only the physical information inside, physical joint-
limits at the position, velocity, acceleration and force level (i'm
not sure this exist for all these levels), joint-level inertia,
stiffness, damping. I don't know if this is a good idea or this set is
complete, i would like some input on this.
I don't know if the same abstraction is needed for the Segment, but it
should contain the following information (in my opinion): Joint
location wrt reference frame, 6D inertia. It does not contain any
information about the interconnection (how is the reference frame
attached to the previous segment. This is interconnection information
and should be located in:
The kinematic descriptions(chain, tree), they only contain
interconnection information.
In the end we end up (hopefully) with a complete, stateless
description which can be used by all the solvers. All extra
information, e.g. how to create a sequence of position values for a
given kinematic description should be located in factories.
I hope to get some feedback on this, because i like my new idea and
would like to start with some initial code for this.
Ruben
New design for KDL::Joint/Segment/Chain
On Fri, 19 Dec 2008, Ruben Smits wrote:
> Since the recent discussion about the description of the kinematics in
> KDL, i was thinking of a new design.
>
> I would like to make a base class for Joint, this will define two
> functions that are needed to make the solvers work, they are the
> functions that calculate position and velocity information from the
> jointspace to the cartesian space:
>
> JntToCart(PosValue), JntToCart(PosValue,TwistValue)
These method calls don't seem to be 100% right or complete: when going from
"Jnt"-space to "Cart"-space, one indeed needs the "PosValue" of the joints,
but also something like the "VelValue", and not a "TwistValue" since twists
are not a joint space concept...
> Every type of Joint will have to inherit from this class, some
> examples RotationalJoint, TranslationalJoint, SphericalJoint,
> HelicalJoint, GimbalJoint, this list can be long, but it allows us to
> support more type of joints, also adding a new type of joint will be a
> lot easier.
Okay...
> Every type of joint will have to specify how it PosValue, TwistValue,
> AccelerationValue looks like, this can be a single value for 1D joints
> but also be a quaternion for a spherical joint.
> Also for this PosValue we need a base class to allow general solvers
> to be usefull for all types of joints.
So, in principle, we get a similar hierarchy as with the Joint: one
"SphericalJoint" class with multiple children, each using a different
internal mathematical representation?
> To define the rest of the information which is inside of a joint, my
> idea was to put only the physical information inside, physical joint-
> limits at the position, velocity, acceleration and force level (i'm
> not sure this exist for all these levels), joint-level inertia,
> stiffness, damping. I don't know if this is a good idea or this set is
> complete, i would like some input on this.
Please, make a distinction between the class that represents a _physical_
joint (where some ---but not all!--- of the constraints you mention make
sense) and a _kinematic_ joint (which is the purely mathematical concept of
an ideal motion constraint between two segments).
Most of the constraints you mention are not part of a joint, but of the
concrete mechanical structure of the robot in which the joint is
integrated.
I suggest to keep the Joint limited to the purely mathematical constraint
concept, with the possibility to attach other physical objects such as:
segments (purely passive rigid body), motor (with its own inertia,
friction, time constant, force generator, ...), transmission
(WolpertGhahramani2000,with its own inertia, friction, time constant,
play), lumped parameter elastic coupling, ...
> I don't know if the same abstraction is needed for the Segment, but it
> should contain the following information (in my opinion): Joint
> location wrt reference frame, 6D inertia.
Ideally, I would like to be able to make a child class that is a pure
planar segment, with 3D inertia etc. So, the base class has an physical
"Inertia" field, which again can have many mathematical representation
implementations...
> It does not contain any
> information about the interconnection (how is the reference frame
> attached to the previous segment. This is interconnection information
> and should be located in:
>
> The kinematic descriptions(chain, tree), they only contain
> interconnection information.
Agreed.
> In the end we end up (hopefully) with a complete, stateless
> description which can be used by all the solvers. All extra
> information, e.g. how to create a sequence of position values for a
> given kinematic description should be located in factories.
Agreed.
Complementary to this separation of factory from runtim use, this approach
allows to have (later, in the medium-term future:-) automatic code
generation that can do away with all extra indirections that this design
suggestion is introducing...
> I hope to get some feedback on this, because i like my new idea and
> would like to start with some initial code for this.
Let's wait for some more comments...
Herman
New design for KDL::Joint/Segment/Chain
On 19 Dec 2008, at 16:50, Herman Bruyninckx wrote:
> On Fri, 19 Dec 2008, Ruben Smits wrote:
>
>> Since the recent discussion about the description of the kinematics
>> in
>> KDL, i was thinking of a new design.
>>
>> I would like to make a base class for Joint, this will define two
>> functions that are needed to make the solvers work, they are the
>> functions that calculate position and velocity information from the
>> jointspace to the cartesian space:
>>
>> JntToCart(PosValue), JntToCart(PosValue,TwistValue)
>
> These method calls don't seem to be 100% right or complete: when
> going from
> "Jnt"-space to "Cart"-space, one indeed needs the "PosValue" of the
> joints,
> but also something like the "VelValue", and not a "TwistValue" since
> twists
> are not a joint space concept...
>
These are indeed not right and complete. It must have been:
CartPosValueOut = JntToCart(JointPosValueIn), or
JntToCart(JointPosValueIn,CartPosValueOut)
and
[CartPosValueOut
,CartVelValueOut]=JntToCart(JointPosValueIn,JointVelValueIn) or
JntToCart
(JointPosValueIn,JointVelValueIn,CartPosValueOut,CartVelValueIn)
[...]
Ruben