http://bugs.orocos.org/show_bug.cgi?id=947
Summary: GetRot() fails with 180 degree rotations around
principal axes
Product: KDL
Version: 1.0.1
Platform: All
OS/Version: All
Status: NEW
Severity: critical
Priority: P3
Component: Primitives
AssignedTo: orocos-dev [..] ...
ReportedBy: kiwi [dot] net [..] ...
CC: orocos-dev [..] ...
Estimated Hours: 0.0
Created attachment 787
--> http://bugs.orocos.org/attachment.cgi?id=787
Test case
Tested in v1.0.1, but the git KDL code is identical so I believe that the issue
is still present. Demonstrated in macosx and gnulinux
KDL::Rotation z = KDL::Rotation::RotX(deg2rad(180)); KDL::Vector axis; double angle = z.GetRotAngle(axis); std::cout << z << "\n" << z.GetRot() << "\n" << axis << "," << angle << std::endl;
produces
[ 1, 0, 0; 0, -1,-1.22465e-16; 0, 1.22465e-16, -1] [ 1.22465e-16, 0, 0] [ nan, -inf, 0],3.14159
That's not right, or am I completely missing something?
More complete test case attached. Definite problems at 180 degree rotations
around x, y, and z. Answers are ok close to 180 degrees.
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947
[Bug 947] GetRot() fails with 180 degree rotations around princi
On Sat, 21 Apr 2012, Erwin Aertbelien wrote:
>
> http://bugs.orocos.org/show_bug.cgi?id=947
>
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947
[Bug 947] GetRot() fails with 180 degree rotations around princi
On Apr 20, 2012, at 15:55 , Erwin Aertbelien wrote:
>
> http://bugs.orocos.org/show_bug.cgi?id=947
>
[Bug 947] GetRot() fails with 180 degree rotations around princi
On Fri, 20 Apr 2012, S Roderick wrote:
> On Apr 20, 2012, at 15:55 , Erwin Aertbelien wrote:
>
>>
>> http://bugs.orocos.org/show_bug.cgi?id=947
>>
>> --- Comment #7 from Erwin Aertbelien <Erwin [dot] Aertbelien [..] ...> 2012-04-20 21:55:24 CEST ---
>> Some additional remarks on the use of this routine.
>>
>> In case of (axis,angle=PI), the axis and angle are indeterminate in the sense
>> that (-axis,PI), (axis,PI), (-axis,-PI) (axis,-PI) are also valid responses.
>> The routine chooses an angle such that the angle falls in the range [0,PI],
>> and it chooses an axis such that, for axes with z-component not equal to zero,
>> its z-component is positive.
>>
>> It is perhaps good to warn about the following, correct but perhaps unexpected
>> behaviour:
>> If you are continuously changing an angle from 0 to PI with a fixed rotation
>> axis
>> and call GetRotAngle on the resulting Rotation matrices, you can have a
>> suddenly changing rotation axis when you arrive at angle==PI.
>
> For us, this was buried under the OCL::CartesianGeneratorPos component starting from (x,y,z, -5,0,90) (RPY) and being sent to (x,y,z, +5,0,-90), which amounts to a 180? rotation about Z. The generator though that those two orientations were identical (as KDL::diff uses GetRot()), and so did nothing but immediately stepped from one to the other. And the hardware stupidly followed ...
>
> So while what you say above may be true, there are layers in KDL (and beyond) that are not currently aware of that. I'm curious how we should deal with this kind of issues in KDL itself?
>
Deprecate these trajectory generators... If they show such behaviour, they
should go.
> Cheers
> S
Herman
[Bug 947] GetRot() fails with 180 degree rotations around princi
On 04/21/2012 10:33 AM, Herman Bruyninckx wrote:
> On Fri, 20 Apr 2012, S Roderick wrote:
>
>> On Apr 20, 2012, at 15:55 , Erwin Aertbelien wrote:
>>
>>>
>>> http://bugs.orocos.org/show_bug.cgi?id=947
>>>
>>> --- Comment #7 from Erwin Aertbelien
>>> <Erwin [dot] Aertbelien [..] ...> 2012-04-20 21:55:24 CEST ---
>>> Some additional remarks on the use of this routine.
>>>
>>> In case of (axis,angle=PI), the axis and angle are indeterminate in
>>> the sense
>>> that (-axis,PI), (axis,PI), (-axis,-PI) (axis,-PI) are also valid
>>> responses.
>>> The routine chooses an angle such that the angle falls in the range
>>> [0,PI],
>>> and it chooses an axis such that, for axes with z-component not equal
>>> to zero,
>>> its z-component is positive.
>>>
>>> It is perhaps good to warn about the following, correct but perhaps
>>> unexpected
>>> behaviour:
>>> If you are continuously changing an angle from 0 to PI with a fixed
>>> rotation
>>> axis
>>> and call GetRotAngle on the resulting Rotation matrices, you can have a
>>> suddenly changing rotation axis when you arrive at angle==PI.
>>
>> For us, this was buried under the OCL::CartesianGeneratorPos component
>> starting from (x,y,z, -5,0,90) (RPY) and being sent to (x,y,z,
>> +5,0,-90), which amounts to a 180? rotation about Z. The generator
>> though that those two orientations were identical (as KDL::diff uses
>> GetRot()), and so did nothing but immediately stepped from one to the
>> other. And the hardware stupidly followed ...
>>
>> So while what you say above may be true, there are layers in KDL (and
>> beyond) that are not currently aware of that. I'm curious how we
>> should deal with this kind of issues in KDL itself?
>>
> Deprecate these trajectory generators... If they show such behaviour, they
> should go.
>
There are two issues:
(1) bug in GetRotAngle (solved)
(2) usage of the trajectory generator routines (cfr other mail).
I do _not_ agree that these trajectory generators should be deprecated.
They provide standard functionality, as is also present
in industrial robot controllers/languages such as KUKA's KRL (where they
have the same problem).
The essential problem here is that you specify the rotational movement
by its endpoints. As long as you do this, you can have the described
type of problems. In many use-cases people do not care, in cases that
they do care, they can specify an intermediate point such that the
angles are < 180 degrees.
We should offer to KDL users the typical robotics paradigm of specifying
a lineair motion by its end points.
I'm getting more and more convinced that I should strictly forbid the
use of angles == 180 degrees in the interpolators. However, I cannot do
this without API change. Currently the begin and end are specified in
the constructor; there is no decent way to return a status/failure.
>> Cheers
>> S
>
> Herman
[Bug 947] GetRot() fails with 180 degree rotations around princi
On Sat, 21 Apr 2012, Erwin Aertbelien wrote:
>
>
> On 04/21/2012 10:33 AM, Herman Bruyninckx wrote:
>> On Fri, 20 Apr 2012, S Roderick wrote:
>>
>>> On Apr 20, 2012, at 15:55 , Erwin Aertbelien wrote:
>>>
>>>>
>>>> http://bugs.orocos.org/show_bug.cgi?id=947
>>>>
>>>> --- Comment #7 from Erwin Aertbelien
>>>> <Erwin [dot] Aertbelien [..] ...> 2012-04-20 21:55:24 CEST ---
>>>> Some additional remarks on the use of this routine.
>>>>
>>>> In case of (axis,angle=PI), the axis and angle are indeterminate in
>>>> the sense
>>>> that (-axis,PI), (axis,PI), (-axis,-PI) (axis,-PI) are also valid
>>>> responses.
>>>> The routine chooses an angle such that the angle falls in the range
>>>> [0,PI],
>>>> and it chooses an axis such that, for axes with z-component not equal
>>>> to zero,
>>>> its z-component is positive.
>>>>
>>>> It is perhaps good to warn about the following, correct but perhaps
>>>> unexpected
>>>> behaviour:
>>>> If you are continuously changing an angle from 0 to PI with a fixed
>>>> rotation
>>>> axis
>>>> and call GetRotAngle on the resulting Rotation matrices, you can have a
>>>> suddenly changing rotation axis when you arrive at angle==PI.
>>>
>>> For us, this was buried under the OCL::CartesianGeneratorPos component
>>> starting from (x,y,z, -5,0,90) (RPY) and being sent to (x,y,z,
>>> +5,0,-90), which amounts to a 180? rotation about Z. The generator
>>> though that those two orientations were identical (as KDL::diff uses
>>> GetRot()), and so did nothing but immediately stepped from one to the
>>> other. And the hardware stupidly followed ...
>>>
>>> So while what you say above may be true, there are layers in KDL (and
>>> beyond) that are not currently aware of that. I'm curious how we
>>> should deal with this kind of issues in KDL itself?
>>>
>> Deprecate these trajectory generators... If they show such behaviour, they
>> should go.
>>
> There are two issues:
> (1) bug in GetRotAngle (solved)
> (2) usage of the trajectory generator routines (cfr other mail).
>
> I do _not_ agree that these trajectory generators should be deprecated. They
> provide standard functionality, as is also present
> in industrial robot controllers/languages such as KUKA's KRL (where they have
> the same problem).
Exactly! And we should make _progress_ not keeping a status quo if that
status quo means erroneous behaviour.
> The essential problem here is that you specify the rotational movement by its
> endpoints. As long as you do this, you can have the described type of
> problems.
Indeed. That's why I see for many years already that trajectory generation
is _an application_ in itself, and not a geometric algorithm. Hence: it
trajectory generators should be removed from KDL; (some of) their geometric
foundations can stay.
> In many use-cases people do not care, in cases that
> they do care, they can specify an intermediate point such that the
> angles are < 180 degrees.
> We should offer to KDL users the typical robotics paradigm of specifying a
> lineair motion by its end points.
Yes, but as an _application_, not as a KDL functionality.
> I'm getting more and more convinced that I should strictly forbid the use of
> angles == 180 degrees in the interpolators. However, I cannot do this
> without API change.
Don't be afraid of API changes if they remove erroneous behaviour! Breaking
hardware because of the errors is _a lot_ worse...
> Currently the begin and end are specified in the
> constructor; there is no decent way to return a status/failure.
This is just another symptom of what I said about trajectory generation not
being a _function_ but an application.
Herman
[Bug 947] GetRot() fails with 180 degree rotations around princi
On Apr 21, 2012, at 05:39 , Herman Bruyninckx wrote:
> On Sat, 21 Apr 2012, Erwin Aertbelien wrote:
>
>>
>>
>> On 04/21/2012 10:33 AM, Herman Bruyninckx wrote:
>>> On Fri, 20 Apr 2012, S Roderick wrote:
>>>> On Apr 20, 2012, at 15:55 , Erwin Aertbelien wrote:
>>>>> http://bugs.orocos.org/show_bug.cgi?id=947
>>>>> --- Comment #7 from Erwin Aertbelien
>>>>> <Erwin [dot] Aertbelien [..] ...> 2012-04-20 21:55:24 CEST ---
>>>>> Some additional remarks on the use of this routine.
>>>>> In case of (axis,angle=PI), the axis and angle are indeterminate in
>>>>> the sense
>>>>> that (-axis,PI), (axis,PI), (-axis,-PI) (axis,-PI) are also valid
>>>>> responses.
>>>>> The routine chooses an angle such that the angle falls in the range
>>>>> [0,PI],
>>>>> and it chooses an axis such that, for axes with z-component not equal
>>>>> to zero,
>>>>> its z-component is positive.
>>>>> It is perhaps good to warn about the following, correct but perhaps
>>>>> unexpected
>>>>> behaviour:
>>>>> If you are continuously changing an angle from 0 to PI with a fixed
>>>>> rotation
>>>>> axis
>>>>> and call GetRotAngle on the resulting Rotation matrices, you can have a
>>>>> suddenly changing rotation axis when you arrive at angle==PI.
>>>> For us, this was buried under the OCL::CartesianGeneratorPos component
>>>> starting from (x,y,z, -5,0,90) (RPY) and being sent to (x,y,z,
>>>> +5,0,-90), which amounts to a 180? rotation about Z. The generator
>>>> though that those two orientations were identical (as KDL::diff uses
>>>> GetRot()), and so did nothing but immediately stepped from one to the
>>>> other. And the hardware stupidly followed ...
>>>> So while what you say above may be true, there are layers in KDL (and
>>>> beyond) that are not currently aware of that. I'm curious how we
>>>> should deal with this kind of issues in KDL itself?
>>> Deprecate these trajectory generators... If they show such behaviour, they
>>> should go.
>> There are two issues:
>> (1) bug in GetRotAngle (solved)
>> (2) usage of the trajectory generator routines (cfr other mail).
>>
>> I do _not_ agree that these trajectory generators should be deprecated. They provide standard functionality, as is also present
>> in industrial robot controllers/languages such as KUKA's KRL (where they have the same problem).
>
> Exactly! And we should make _progress_ not keeping a status quo if that
> status quo means erroneous behaviour.
Herman, I personally have over 1000 hours of operational time on robots using these generators, at my current employer alone. I have no idea of my total time with them over the last several years. And I'm one of several users. Let's not make a knee jerk reaction and remove useful functionality due to one occurence of a highly unusual corner case.
>> The essential problem here is that you specify the rotational movement by its endpoints. As long as you do this, you can have the described type of problems.
>
>
> Indeed. That's why I see for many years already that trajectory generation
> is _an application_ in itself, and not a geometric algorithm. Hence: it
> trajectory generators should be removed from KDL; (some of) their geometric
> foundations can stay.
>
>> In many use-cases people do not care, in cases that
>> they do care, they can specify an intermediate point such that the
>> angles are < 180 degrees.
>> We should offer to KDL users the typical robotics paradigm of specifying a lineair motion by its end points.
>
> Yes, but as an _application_, not as a KDL functionality.
It's not in KDL. It's in OCL v1, which was removed in the v2 update anyway. So Herman's wish is already granted ...
>> I'm getting more and more convinced that I should strictly forbid the use of angles == 180 degrees in the interpolators. However, I cannot do this without API change.
>
> Don't be afraid of API changes if they remove erroneous behaviour! Breaking
> hardware because of the errors is _a lot_ worse...
>
>> Currently the begin and end are specified in the constructor; there is no decent way to return a status/failure.
>
> This is just another symptom of what I said about trajectory generation not
> being a _function_ but an application.
I think that you are both confused as to what occurred here. We are using a modified instance of OCL::CartesianGeneratorPos that contains some KDL::VelocityProfile_Trap objects, which do the actual trajectory generation. We have modified both to be able to specifying velocities instead of a time duration. None of the SetProfile's in VelocityProfile_Trap return an error, but could easily be modified to. But that wouldn't have caught this problem. This incident occured because the KDL::diff() function used by CartesianGeneratorPos::moveTo() contained an error (as it uses GetRot() underneath). If you wanted to prevent the 180 problem, this is a likely location to catch that IMHO.
If we (the community) wanted to help reduce/prevent this problem in the future I would recommend
- more comprehensive unit tests
- coverage analysis
- deprecation or labelling as experimental of partially working functionality (last I checked a couple of years ago, all the pathxxx stuff in KDL is broken)
- adding more examples (KDL comes with one example program). And no, unit tests are _not_ examples.
My 2c
S
[Bug 947] GetRot() fails with 180 degree rotations around princi
On Sat, 21 Apr 2012, Stephen Roderick wrote:
> On Apr 21, 2012, at 05:39 , Herman Bruyninckx wrote:
>
>> On Sat, 21 Apr 2012, Erwin Aertbelien wrote:
>>
>>>
>>>
>>> On 04/21/2012 10:33 AM, Herman Bruyninckx wrote:
>>>> On Fri, 20 Apr 2012, S Roderick wrote:
>>>>> On Apr 20, 2012, at 15:55 , Erwin Aertbelien wrote:
>>>>>> http://bugs.orocos.org/show_bug.cgi?id=947
>>>>>> --- Comment #7 from Erwin Aertbelien
>>>>>> <Erwin [dot] Aertbelien [..] ...> 2012-04-20 21:55:24 CEST ---
>>>>>> Some additional remarks on the use of this routine.
>>>>>> In case of (axis,angle=PI), the axis and angle are indeterminate in
>>>>>> the sense
>>>>>> that (-axis,PI), (axis,PI), (-axis,-PI) (axis,-PI) are also valid
>>>>>> responses.
>>>>>> The routine chooses an angle such that the angle falls in the range
>>>>>> [0,PI],
>>>>>> and it chooses an axis such that, for axes with z-component not equal
>>>>>> to zero,
>>>>>> its z-component is positive.
>>>>>> It is perhaps good to warn about the following, correct but perhaps
>>>>>> unexpected
>>>>>> behaviour:
>>>>>> If you are continuously changing an angle from 0 to PI with a fixed
>>>>>> rotation
>>>>>> axis
>>>>>> and call GetRotAngle on the resulting Rotation matrices, you can have a
>>>>>> suddenly changing rotation axis when you arrive at angle==PI.
>>>>> For us, this was buried under the OCL::CartesianGeneratorPos component
>>>>> starting from (x,y,z, -5,0,90) (RPY) and being sent to (x,y,z,
>>>>> +5,0,-90), which amounts to a 180? rotation about Z. The generator
>>>>> though that those two orientations were identical (as KDL::diff uses
>>>>> GetRot()), and so did nothing but immediately stepped from one to the
>>>>> other. And the hardware stupidly followed ...
>>>>> So while what you say above may be true, there are layers in KDL (and
>>>>> beyond) that are not currently aware of that. I'm curious how we
>>>>> should deal with this kind of issues in KDL itself?
>>>> Deprecate these trajectory generators... If they show such behaviour, they
>>>> should go.
>>> There are two issues:
>>> (1) bug in GetRotAngle (solved)
>>> (2) usage of the trajectory generator routines (cfr other mail).
>>>
>>> I do _not_ agree that these trajectory generators should be deprecated. They provide standard functionality, as is also present
>>> in industrial robot controllers/languages such as KUKA's KRL (where they have the same problem).
>>
>> Exactly! And we should make _progress_ not keeping a status quo if that
>> status quo means erroneous behaviour.
>
> Herman, I personally have over 1000 hours of operational time on robots using these generators, at my current employer alone. I have no idea of my total time with them over the last several years. And I'm one of several users. Let's not make a knee jerk reaction and remove useful functionality due to one occurence of a highly unusual corner case.
>
I do think code should be made perfect, and removed if erroneous corner
cases exist, however unusual, and be replaced by better versions.
>>> The essential problem here is that you specify the rotational movement by its endpoints. As long as you do this, you can have the described type of problems.
>>
>>
>> Indeed. That's why I see for many years already that trajectory generation
>> is _an application_ in itself, and not a geometric algorithm. Hence: it
>> trajectory generators should be removed from KDL; (some of) their geometric
>> foundations can stay.
>>
>>> In many use-cases people do not care, in cases that
>>> they do care, they can specify an intermediate point such that the
>>> angles are < 180 degrees.
>>> We should offer to KDL users the typical robotics paradigm of specifying a lineair motion by its end points.
>>
>> Yes, but as an _application_, not as a KDL functionality.
>
> It's not in KDL. It's in OCL v1, which was removed in the v2 update
> anyway. So Herman's wish is already granted ...
Just putting things in a particular sub-project does not solve the
problem...
>>> I'm getting more and more convinced that I should strictly forbid the use of angles == 180 degrees in the interpolators. However, I cannot do this without API change.
>>
>> Don't be afraid of API changes if they remove erroneous behaviour! Breaking
>> hardware because of the errors is _a lot_ worse...
>>
>>> Currently the begin and end are specified in the constructor; there is no decent way to return a status/failure.
>>
>> This is just another symptom of what I said about trajectory generation not
>> being a _function_ but an application.
>
> I think that you are both confused as to what occurred here.
Maybe we are, but that is not so relevant for the future of this particular
piece of code.
> We are using
> a modified instance of OCL::CartesianGeneratorPos that contains some
> KDL::VelocityProfile_Trap objects, which do the actual trajectory
> generation. We have modified both to be able to specifying velocities
> instead of a time duration.
To specify velocities for what exactly?
> None of the SetProfile's in
> VelocityProfile_Trap return an error, but could easily be modified to.
> But that wouldn't have caught this problem. This incident occured because
> the KDL::diff() function
The many overloaded "diff()" functions in KDL are another source of
multiple errors over the last years, not in the least because it is to me
still unclear what the real meaning is (I can not read the code
sufficiently clearly to be 100% sure), and secondly because the "delta
time" parameter is semantically out of bounds.
> used by CartesianGeneratorPos::moveTo()
> contained an error (as it uses GetRot() underneath). If you wanted to
> prevent the 180 problem, this is a likely location to catch that IMHO.
> If we (the community) wanted to help reduce/prevent this problem in the future I would recommend
> - more comprehensive unit tests
> - coverage analysis
> - deprecation or labelling as experimental of partially working functionality (last I checked a couple of years ago, all the pathxxx stuff in KDL is broken)
> - adding more examples (KDL comes with one example program). And no, unit tests are _not_ examples.
Agreed.
KDL would benefit from a new version that only contains the best
quality code with the best quality documentation.
_And_ a KDL version that focuses on _kinematics_ and _dynamics_. Since now
it contains a lot of geometrical and trajectory generation code, that
better be moved to their own separate libraries, because neither of them
_are_ kinematics or dynamics, and because those other libraries will be a
lot easier to reuse for purposes outside of kinematics and dynamics.
> My 2c
> S
Herman
[Bug 947] GetRot() fails with 180 degree rotations around princi
On Apr 22, 2012, at 09:55 , Herman Bruyninckx wrote:
> On Sat, 21 Apr 2012, Stephen Roderick wrote:
>
>> On Apr 21, 2012, at 05:39 , Herman Bruyninckx wrote:
>>
>>> On Sat, 21 Apr 2012, Erwin Aertbelien wrote:
>>>
>>>>
>>>>
>>>> On 04/21/2012 10:33 AM, Herman Bruyninckx wrote:
>>>>> On Fri, 20 Apr 2012, S Roderick wrote:
>>>>>> On Apr 20, 2012, at 15:55 , Erwin Aertbelien wrote:
>>>>>>> http://bugs.orocos.org/show_bug.cgi?id=947
>>>>>>> --- Comment #7 from Erwin Aertbelien
>>>>>>> <Erwin [dot] Aertbelien [..] ...> 2012-04-20 21:55:24 CEST ---
>>>>>>> Some additional remarks on the use of this routine.
>>>>>>> In case of (axis,angle=PI), the axis and angle are indeterminate in
>>>>>>> the sense
>>>>>>> that (-axis,PI), (axis,PI), (-axis,-PI) (axis,-PI) are also valid
>>>>>>> responses.
>>>>>>> The routine chooses an angle such that the angle falls in the range
>>>>>>> [0,PI],
>>>>>>> and it chooses an axis such that, for axes with z-component not equal
>>>>>>> to zero,
>>>>>>> its z-component is positive.
>>>>>>> It is perhaps good to warn about the following, correct but perhaps
>>>>>>> unexpected
>>>>>>> behaviour:
>>>>>>> If you are continuously changing an angle from 0 to PI with a fixed
>>>>>>> rotation
>>>>>>> axis
>>>>>>> and call GetRotAngle on the resulting Rotation matrices, you can have a
>>>>>>> suddenly changing rotation axis when you arrive at angle==PI.
>>>>>> For us, this was buried under the OCL::CartesianGeneratorPos component
>>>>>> starting from (x,y,z, -5,0,90) (RPY) and being sent to (x,y,z,
>>>>>> +5,0,-90), which amounts to a 180? rotation about Z. The generator
>>>>>> though that those two orientations were identical (as KDL::diff uses
>>>>>> GetRot()), and so did nothing but immediately stepped from one to the
>>>>>> other. And the hardware stupidly followed ...
>>>>>> So while what you say above may be true, there are layers in KDL (and
>>>>>> beyond) that are not currently aware of that. I'm curious how we
>>>>>> should deal with this kind of issues in KDL itself?
>>>>> Deprecate these trajectory generators... If they show such behaviour, they
>>>>> should go.
>>>> There are two issues:
>>>> (1) bug in GetRotAngle (solved)
>>>> (2) usage of the trajectory generator routines (cfr other mail).
>>>>
>>>> I do _not_ agree that these trajectory generators should be deprecated. They provide standard functionality, as is also present
>>>> in industrial robot controllers/languages such as KUKA's KRL (where they have the same problem).
>>>
>>> Exactly! And we should make _progress_ not keeping a status quo if that
>>> status quo means erroneous behaviour.
>>
>> Herman, I personally have over 1000 hours of operational time on robots using these generators, at my current employer alone. I have no idea of my total time with them over the last several years. And I'm one of several users. Let's not make a knee jerk reaction and remove useful functionality due to one occurence of a highly unusual corner case.
>>
>
> I do think code should be made perfect, and removed if erroneous corner
> cases exist, however unusual, and be replaced by better versions.
So finding one bug after 1000's of hours of operations, and you'd rather remove the code than fix it. Seriously!?
>>>> I'm getting more and more convinced that I should strictly forbid the use of angles == 180 degrees in the interpolators. However, I cannot do this without API change.
>>>
>>> Don't be afraid of API changes if they remove erroneous behaviour! Breaking
>>> hardware because of the errors is _a lot_ worse...
>>>
>>>> Currently the begin and end are specified in the constructor; there is no decent way to return a status/failure.
>>>
>>> This is just another symptom of what I said about trajectory generation not
>>> being a _function_ but an application.
>>
>> I think that you are both confused as to what occurred here.
>
> Maybe we are, but that is not so relevant for the future of this particular
> piece of code.
>
>> We are using
>> a modified instance of OCL::CartesianGeneratorPos that contains some
>> KDL::VelocityProfile_Trap objects, which do the actual trajectory
>> generation. We have modified both to be able to specifying velocities
>> instead of a time duration.
>
> To specify velocities for what exactly?
We specify a % of max joint velocities to use, rather than a time and then try to guess what speed we'll get.
>> None of the SetProfile's in
>> VelocityProfile_Trap return an error, but could easily be modified to.
>> But that wouldn't have caught this problem. This incident occured because
>> the KDL::diff() function
>
> The many overloaded "diff()" functions in KDL are another source of
> multiple errors over the last years, not in the least because it is to me
> still unclear what the real meaning is (I can not read the code
> sufficiently clearly to be 100% sure), and secondly because the "delta
> time" parameter is semantically out of bounds.
The code is poorly documented, I'll give you that. And I'm not sure that there are any test cases for it.
>> used by CartesianGeneratorPos::moveTo()
>> contained an error (as it uses GetRot() underneath). If you wanted to
>> prevent the 180 problem, this is a likely location to catch that IMHO.
>
>> If we (the community) wanted to help reduce/prevent this problem in the future I would recommend
>> - more comprehensive unit tests
>> - coverage analysis
>> - deprecation or labelling as experimental of partially working functionality (last I checked a couple of years ago, all the pathxxx stuff in KDL is broken)
>> - adding more examples (KDL comes with one example program). And no, unit tests are _not_ examples.
>
> Agreed.
> KDL would benefit from a new version that only contains the best
> quality code with the best quality documentation.
+1
> _And_ a KDL version that focuses on _kinematics_ and _dynamics_. Since now
> it contains a lot of geometrical and trajectory generation code, that
> better be moved to their own separate libraries, because neither of them
> _are_ kinematics or dynamics, and because those other libraries will be a
> lot easier to reuse for purposes outside of kinematics and dynamics.
Given the very low level of enhancements that have occurred with KDL these past few years, why don't we concentrate on incremental improvement than a more extensive revolutionary redesign? Despite the issues you see with it, it's still a useful product that simply needs some TLC.
S
[Bug 947] GetRot() fails with 180 degree rotations around princi
On Mon, 23 Apr 2012, Stephen Roderick wrote:
> On Apr 22, 2012, at 09:55 , Herman Bruyninckx wrote:
>
>> On Sat, 21 Apr 2012, Stephen Roderick wrote:
>>
>>> On Apr 21, 2012, at 05:39 , Herman Bruyninckx wrote:
>>>
>>>> On Sat, 21 Apr 2012, Erwin Aertbelien wrote:
>>>>
>>>>>
>>>>>
>>>>> On 04/21/2012 10:33 AM, Herman Bruyninckx wrote:
>>>>>> On Fri, 20 Apr 2012, S Roderick wrote:
>>>>>>> On Apr 20, 2012, at 15:55 , Erwin Aertbelien wrote:
>>>>>>>> http://bugs.orocos.org/show_bug.cgi?id=947
>>>>>>>> --- Comment #7 from Erwin Aertbelien
>>>>>>>> <Erwin [dot] Aertbelien [..] ...> 2012-04-20 21:55:24 CEST ---
>>>>>>>> Some additional remarks on the use of this routine.
>>>>>>>> In case of (axis,angle=PI), the axis and angle are indeterminate in
>>>>>>>> the sense
>>>>>>>> that (-axis,PI), (axis,PI), (-axis,-PI) (axis,-PI) are also valid
>>>>>>>> responses.
>>>>>>>> The routine chooses an angle such that the angle falls in the range
>>>>>>>> [0,PI],
>>>>>>>> and it chooses an axis such that, for axes with z-component not equal
>>>>>>>> to zero,
>>>>>>>> its z-component is positive.
>>>>>>>> It is perhaps good to warn about the following, correct but perhaps
>>>>>>>> unexpected
>>>>>>>> behaviour:
>>>>>>>> If you are continuously changing an angle from 0 to PI with a fixed
>>>>>>>> rotation
>>>>>>>> axis
>>>>>>>> and call GetRotAngle on the resulting Rotation matrices, you can have a
>>>>>>>> suddenly changing rotation axis when you arrive at angle==PI.
>>>>>>> For us, this was buried under the OCL::CartesianGeneratorPos component
>>>>>>> starting from (x,y,z, -5,0,90) (RPY) and being sent to (x,y,z,
>>>>>>> +5,0,-90), which amounts to a 180? rotation about Z. The generator
>>>>>>> though that those two orientations were identical (as KDL::diff uses
>>>>>>> GetRot()), and so did nothing but immediately stepped from one to the
>>>>>>> other. And the hardware stupidly followed ...
>>>>>>> So while what you say above may be true, there are layers in KDL (and
>>>>>>> beyond) that are not currently aware of that. I'm curious how we
>>>>>>> should deal with this kind of issues in KDL itself?
>>>>>> Deprecate these trajectory generators... If they show such behaviour, they
>>>>>> should go.
>>>>> There are two issues:
>>>>> (1) bug in GetRotAngle (solved)
>>>>> (2) usage of the trajectory generator routines (cfr other mail).
>>>>>
>>>>> I do _not_ agree that these trajectory generators should be deprecated. They provide standard functionality, as is also present
>>>>> in industrial robot controllers/languages such as KUKA's KRL (where they have the same problem).
>>>>
>>>> Exactly! And we should make _progress_ not keeping a status quo if that
>>>> status quo means erroneous behaviour.
>>>
>>> Herman, I personally have over 1000 hours of operational time on robots using these generators, at my current employer alone. I have no idea of my total time with them over the last several years. And I'm one of several users. Let's not make a knee jerk reaction and remove useful functionality due to one occurence of a highly unusual corner case.
>>>
>>
>> I do think code should be made perfect, and removed if erroneous corner
>> cases exist, however unusual, and be replaced by better versions.
>
> So finding one bug after 1000's of hours of operations, and you'd rather remove the code than fix it. Seriously!?
"Fixing" = "replace by better version", obviously! :-) Sorry for my too
sloppy statement!
>>>>> I'm getting more and more convinced that I should strictly forbid the use of angles == 180 degrees in the interpolators. However, I cannot do this without API change.
>>>>
>>>> Don't be afraid of API changes if they remove erroneous behaviour! Breaking
>>>> hardware because of the errors is _a lot_ worse...
>>>>
>>>>> Currently the begin and end are specified in the constructor; there is no decent way to return a status/failure.
>>>>
>>>> This is just another symptom of what I said about trajectory generation not
>>>> being a _function_ but an application.
>>>
>>> I think that you are both confused as to what occurred here.
>>
>> Maybe we are, but that is not so relevant for the future of this particular
>> piece of code.
>>
>>> We are using
>>> a modified instance of OCL::CartesianGeneratorPos that contains some
>>> KDL::VelocityProfile_Trap objects, which do the actual trajectory
>>> generation. We have modified both to be able to specifying velocities
>>> instead of a time duration.
>>
>> To specify velocities for what exactly?
>
> We specify a % of max joint velocities to use, rather than a time and
> then try to guess what speed we'll get.
Isn't that what the trapezoidal profile code is doing: you specify a
maximum velocity (it is irrelevant if that maximum is a percentage of
another value....), and then the time ("speed" in your sentence?) is an
outcome of the computation.
>>> None of the SetProfile's in
>>> VelocityProfile_Trap return an error, but could easily be modified to.
>>> But that wouldn't have caught this problem. This incident occured because
>>> the KDL::diff() function
>>
>> The many overloaded "diff()" functions in KDL are another source of
>> multiple errors over the last years, not in the least because it is to me
>> still unclear what the real meaning is (I can not read the code
>> sufficiently clearly to be 100% sure), and secondly because the "delta
>> time" parameter is semantically out of bounds.
>
> The code is poorly documented, I'll give you that. And I'm not sure that
> there are any test cases for it.
I think we need more than test cases: tutorials with best practice use
cases. But I know that this requires effort. So, I am willing to sponsor an
Summer intern for helping out with this kind of KDL refactoring, if a
motivated candidate can be found. So, give me a signal if you happen to
know someone :-)
>>> used by CartesianGeneratorPos::moveTo()
>>> contained an error (as it uses GetRot() underneath). If you wanted to
>>> prevent the 180 problem, this is a likely location to catch that IMHO.
>>
>>> If we (the community) wanted to help reduce/prevent this problem in the future I would recommend
>>> - more comprehensive unit tests
>>> - coverage analysis
>>> - deprecation or labelling as experimental of partially working functionality (last I checked a couple of years ago, all the pathxxx stuff in KDL is broken)
>>> - adding more examples (KDL comes with one example program). And no, unit tests are _not_ examples.
>>
>> Agreed.
>> KDL would benefit from a new version that only contains the best
>> quality code with the best quality documentation.
>
> +1
>> _And_ a KDL version that focuses on _kinematics_ and _dynamics_. Since now
>> it contains a lot of geometrical and trajectory generation code, that
>> better be moved to their own separate libraries, because neither of them
>> _are_ kinematics or dynamics, and because those other libraries will be a
>> lot easier to reuse for purposes outside of kinematics and dynamics.
>
> Given the very low level of enhancements that have occurred with KDL
> these past few years, why don't we concentrate on incremental improvement
> than a more extensive revolutionary redesign? Despite the issues you see
> with it, it's still a useful product that simply needs some TLC.
In my opinion, one of the major reasons for the low level of enhancemens is
exactly the fact that KDL has too may functionalities, and that scares
contributors away: too many things to learn ("estimate" rather...) before
one can be sure that one is making a contribution. Smaller, focused
libraries have a lot lower entry thresholds.
So, I an not advocating a 'revolutionary redesign', but to start with a
decent "cutting in smaller pieces" of the existing code:
- geometry: Frames and their operations (time derivaties, distance
measures,...); Forces and their operations.
- KDL: kinematic and dynamic transformations of geometric properties
through kinematic chains.
- trajectory generation: evolutions of Frames/Forces over time and space.
> S
Herman
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947
Ruben Smits <ruben [dot] smits [..] ...> changed:
What |Removed |Added
----------------------------------------------------------------------------
Status|NEW |RESOLVED
CC| |ruben.smits@intermodalics.e
| |u
Resolution| |FIXED
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947
Erwin Aertbelien <Erwin [dot] Aertbelien [..] ...> changed:
What |Removed |Added
----------------------------------------------------------------------------
CC| |Erwin [dot] Aertbelien [..] ...
| |ven.be
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947
Erwin Aertbelien <Erwin [dot] Aertbelien [..] ...> changed:
What |Removed |Added
----------------------------------------------------------------------------
Attachment #788 is|0 |1
obsolete| |
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947
[Bug 947] New: GetRot() fails with 180 degree rotations around p
Does the output change if you do:
The value of eps is by default set to 0.000001, maybe that is too small already?
Ruben
On Fri, Apr 20, 2012 at 3:17 AM, S Roderick <kiwi [dot] net [..] ...> wrote:
>
> http://bugs.orocos.org/show_bug.cgi?id=947
>
> Summary: GetRot() fails with 180 degree rotations around
> principal axes
> Product: KDL
> Version: 1.0.1
> Platform: All
> OS/Version: All
> Status: NEW
> Severity: critical
> Priority: P3
> Component: Primitives
> AssignedTo: orocos-dev [..] ...
> ReportedBy: kiwi [dot] net [..] ...
> CC: orocos-dev [..] ...
> Estimated Hours: 0.0
>
>
> Created attachment 787
> --> http://bugs.orocos.org/attachment.cgi?id=787
> Test case
>
> Tested in v1.0.1, but the git KDL code is identical so I believe that the issue
> is still present. Demonstrated in macosx and gnulinux
>
>
>
> produces
>
>
>
> That's not right, or am I completely missing something?
>
> More complete test case attached. Definite problems at 180 degree rotations
> around x, y, and z. Answers are ok close to 180 degrees.
>
> --
> Configure bugmail: http://bugs.orocos.org/userprefs.cgi?tab=email
> ------- You are receiving this mail because: -------
> You are on the CC list for the bug.
> You are the assignee for the bug.
> --
> Orocos-Dev mailing list
> Orocos-Dev [..] ...
> http://lists.mech.kuleuven.be/mailman/listinfo/orocos-dev
[Bug 947] GetRot() fails with 180 degree rotations around princi
http://bugs.orocos.org/show_bug.cgi?id=947