Dear mailing list members,
i have a question concerning the inverse kinematic.
We are using the ChainIkSolverPos_NR_JL solver with 100000 max iterations and 1e-6 accuracy.
When i want to calculate the forward kinematic for the given test case and use the result as input for my inverse kinematic, i don't allways get the right joint angles back.
In our opinion the inverse kinematic solver doesn’t flip the joint angles if a maximum or minimum is reached. I.e. the resulting joint angle should be 179.5 degrees, the inverse kinematic reaches -179.5 (which is the minimum), but don't flip to check the other side, even if the number of iterations is below the maximum number.
Here a testcase where the result of the inverse kinematic solver don't match with the start position of the forward kinematic.
15.0, -25.0, 60.0, 30.0, -75.0, 179.0
Has anybody of you an idea or a workaround to solve this problem?
Attached you can find the used robot, the constraints and the initial position for the inverse kinematic.
Thanks for your help,
Stefan Huber
used chain:
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::None),
KDL::Frame(KDL::Vector(0.0, 0.22, 0.0))));
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotY),
KDL::Frame(KDL::Vector(0.35, 0.675 - 0.22, 0.0))));
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),
KDL::Frame(KDL::Vector(0.0, 1.825 - 0.675, 0.0))));
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),
KDL::Frame(KDL::Vector(0.752, -0.041, 0.0))));
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotX),
KDL::Frame(KDL::Vector(0.448, 0.0, 0.0))));
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),
KDL::Frame(KDL::Vector(0.22, 0.0, 0.0))));
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotX),
KDL::Frame(KDL::Vector(0.02, 0.0, 0.0))));
Joint limits:
jointArrayMin = -179.99, -75.0, -45.0, -30, -120.0, -179.99;
jointArrayMax = 180.0, 50.0, 80.0, 30,-70.0, 180.0;
Initial pos: 0, 0, 0, 0, -90, 0
---------------------------------------------------
Stefan Huber MSc
Research Associate
at the
Institute for Research and Development on Advanced Radiation Technologies (radART)
Muellner Hauptstrasse 48
A-5020 Salzburg
Paracelsus Medical University (PMU)
Strubergasse 21
A-5020 Salzburg
mail: stefan [dot] huber [..] ...
webpage: www.pmu.ac.at/en/768.htm
phone: +43 662 4482 4239
inverse kinematic solver problems
On Thu, 24 Jan 2013, Stefan Huber wrote:
> Dear mailing list members,
>
> i have a question concerning the inverse kinematic.
> We are using the ChainIkSolverPos_NR_JL solver with 100000 max iterations and 1e-6 accuracy.
>
> When i want to calculate the forward kinematic for the given test case and use the result as input for my inverse kinematic, i don't allways get the right joint angles back.
>
> In our opinion the inverse kinematic solver doesn’t flip the joint angles
> if a maximum or minimum is reached. I.e. the resulting joint angle should
> be 179.5 degrees, the inverse kinematic reaches -179.5 (which is the
> minimum), but don't flip to check the other side, even if the number of
> iterations is below the maximum number.
The algorithm is numeric, so it converges to the "closest" local minimum.
In case you have to have some control over which configuration you want,
you will have to add something around this solver.
_And_, as always, you'd better look at your problem at the _velocity_
level, not at the position level: selecting the right configuration is
something you do at each instant in the trajectory of your robot from its
initial configuration/position to the desired one.
> Here a testcase where the result of the inverse kinematic solver don't match with the start position of the forward kinematic.
> 15.0, -25.0, 60.0, 30.0, -75.0, 179.0
>
> Has anybody of you an idea or a workaround to solve this problem?
>
> Attached you can find the used robot, the constraints and the initial position for the inverse kinematic.
>
> Thanks for your help,
> Stefan Huber
Herman
> used chain:
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::None),
> KDL::Frame(KDL::Vector(0.0, 0.22, 0.0))));
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotY),
> KDL::Frame(KDL::Vector(0.35, 0.675 - 0.22, 0.0))));
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),
> KDL::Frame(KDL::Vector(0.0, 1.825 - 0.675, 0.0))));
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),
> KDL::Frame(KDL::Vector(0.752, -0.041, 0.0))));
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotX),
> KDL::Frame(KDL::Vector(0.448, 0.0, 0.0))));
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),
> KDL::Frame(KDL::Vector(0.22, 0.0, 0.0))));
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotX),
> KDL::Frame(KDL::Vector(0.02, 0.0, 0.0))));
>
> Joint limits:
> jointArrayMin = -179.99, -75.0, -45.0, -30, -120.0, -179.99;
> jointArrayMax = 180.0, 50.0, 80.0, 30,-70.0, 180.0;
>
> Initial pos: 0, 0, 0, 0, -90, 0
>
> ---------------------------------------------------
> Stefan Huber MSc
>
> Research Associate
>
> at the
>
> Institute for Research and Development on Advanced Radiation Technologies (radART)
> Muellner Hauptstrasse 48
> A-5020 Salzburg
>
> Paracelsus Medical University (PMU)
> Strubergasse 21
> A-5020 Salzburg
>
> mail: stefan [dot] huber [..] ...
> webpage: www.pmu.ac.at/en/768.htm
>
> phone: +43 662 4482 4239
>
>
inverse kinematic solver problems
Hi Stefan, I ran into a similar issue, where making sure I was using the jntarray of the previous pose resolved the issue. So, keeping track of the state of your input jntarray is important. Perhaps something to lookinto?
-Jelle
On 24 jan. 2013, at 17:30, "Stefan Huber" <Huber [dot] Ste [..] ...> wrote:
> Dear mailing list members,
>
> i have a question concerning the inverse kinematic.
> We are using the ChainIkSolverPos_NR_JL solver with 100000 max iterations and 1e-6 accuracy.
>
> When i want to calculate the forward kinematic for the given test case and use the result as input for my inverse kinematic, i don't allways get the right joint angles back.
>
> In our opinion the inverse kinematic solver doesn’t flip the joint angles if a maximum or minimum is reached. I.e. the resulting joint angle should be 179.5 degrees, the inverse kinematic reaches -179.5 (which is the minimum), but don't flip to check the other side, even if the number of iterations is below the maximum number.
>
> Here a testcase where the result of the inverse kinematic solver don't match with the start position of the forward kinematic.
> 15.0, -25.0, 60.0, 30.0, -75.0, 179.0
>
> Has anybody of you an idea or a workaround to solve this problem?
>
> Attached you can find the used robot, the constraints and the initial position for the inverse kinematic.
>
> Thanks for your help,
> Stefan Huber
>
> used chain:
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::None),
> KDL::Frame(KDL::Vector(0.0, 0.22, 0.0))));
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotY),
> KDL::Frame(KDL::Vector(0.35, 0.675 - 0.22, 0.0))));
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),
> KDL::Frame(KDL::Vector(0.0, 1.825 - 0.675, 0.0))));
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),
> KDL::Frame(KDL::Vector(0.752, -0.041, 0.0))));
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotX),
> KDL::Frame(KDL::Vector(0.448, 0.0, 0.0))));
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),
> KDL::Frame(KDL::Vector(0.22, 0.0, 0.0))));
> chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotX),
> KDL::Frame(KDL::Vector(0.02, 0.0, 0.0))));
>
> Joint limits:
> jointArrayMin = -179.99, -75.0, -45.0, -30, -120.0, -179.99;
> jointArrayMax = 180.0, 50.0, 80.0, 30,-70.0, 180.0;
>
> Initial pos: 0, 0, 0, 0, -90, 0
>
> ---------------------------------------------------
> Stefan Huber MSc
>
> Research Associate
>
> at the
>
> Institute for Research and Development on Advanced Radiation Technologies (radART)
> Muellner Hauptstrasse 48
> A-5020 Salzburg
>
> Paracelsus Medical University (PMU)
> Strubergasse 21
> A-5020 Salzburg
>
> mail: stefan [dot] huber [..] ...
> webpage: www.pmu.ac.at/en/768.htm
>
> phone: +43 662 4482 4239
>
>