Position only IK

Hi,

I have been using the KDL inverse kinematics solver, KDL::ChainIkSolverPos_NR_JL. I would very much like to do position only inverse kinematics. I saw that Moveit, which uses KDL can do position only inverse kinematics.

My questions is: "How to set the ik solver, to only consider the target position and not its orientation".

Thanks

Position only IK

> My questions is: "How to set the ik solver, to only consider the target
> position and not its orientation”.

Why not check out KDL::ChainIkSolverVel_wdls <http://docs.ros.org/groovy/api/orocos_kdl/html/classKDL_1_1ChainIkSolverVel__wdls.html>, and set the task space weight to 0 for the rotational components?

Ruben Smits's picture

Position only IK

On Wed, Mar 25, 2015 at 2:30 PM, <guillaume [dot] dechambrier [..] ...> wrote:

> I have had a look, thanks this is already a good help. However when I use
> it
> with ChainIkSolverPos_NR, I get the following error:
>
> usr/include/eigen3/Eigen/src/Core/Block.h:141:
> Eigen::Block::Block(XprType&,
> Eigen::Block::Index, Eigen::Block::Index, Eigen::Block::Index,
> Eigen::Block::Index) [with XprType = Eigen::Matrix; int BlockRows = -1; int
> BlockCols = -1; bool InnerPanel = false; Eigen::Block::Index = long int]:
> Assertion `a_startRow >= 0 && blockRows >= 0 && a_startRow = 0 && blockCols
> >= 0 && a_startCol
>

Could you provide a longer backtrace to see which code in KDL is triggering
this?

R.

> --
> Orocos-Users mailing list
> Orocos-Users [..] ...
> http://lists.mech.kuleuven.be/mailman/listinfo/orocos-users
>

Ruben Smits's picture

Position only IK

On Wed, Mar 25, 2015 at 10:54 PM, <guillaume [dot] dechambrier [..] ...> wrote:

> I don't think the problem is to do with Eigen but more with my Chain. Here
> is
> my chain:
>
> Rotation R;
> R.Identity();
> KDL::Chain chain2;
> chain2.addSegment(
>
> Segment("link_dof0",Joint("joint_dof0",Vector(0.0934,0.02957,0),Vector(0,0,1),Joint::RotAxis),
> Frame(R,Vector(0.0934,0.02957,0)) ));
> chain2.addSegment(
> Segment("link_dof1",Joint("joint_dof1",Vector(0,0,0),
> Vector(0,-1,0),Joint::RotAxis), Frame(R,Vector(0,0,0))
> ));
> chain2.addSegment(
> Segment("link_dof2",Joint("joint_dof2",Vector(0.04794,0,0),
> Vector(0,-1,0),Joint::RotAxis), Frame(R,Vector(0.04794,0,0)) ));
> chain2.addSegment(
> Segment("link_dof3",Joint("joint_dof3",Vector(0.02827,0,0),
> Vector(0,-1,0),Joint::RotAxis), Frame(R,Vector(0.02827,0,0)) ));
> chain2.addSegment(
> Segment("link_dof4",Joint("joint_dof4",Joint::None),
> Frame(R,Vector(0.02612,0,0)) ));
>
>
> It works fine for forward kinematics and inverse kinematics when using
> "ChainIkSolverVel_pinv". But when I try with "ChainIkSolverVel_wdls" I get
> the error mentioned previously with "Block".
>
> I have tried this kinematic chain, which was in another example I found on
> this site:
>
> chain1.addSegment( Segment( Joint(Joint::RotZ),
> Frame(Vector(0.0,0.0,1.020)) ) );
>
>
> chain1.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.480))));
>
>
> chain1.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.645))));
> chain1.addSegment(Segment(Joint(Joint::RotZ)));
>
>
> chain1.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.120))));
> chain1.addSegment(Segment(Joint(Joint::RotZ)));
>
> I have NO error at all with "ChainIkSolverVel_wdls". It makes me think that
> there is something in my first kinematic chain that
> ""ChainIkSolverVel_wdls"
> specifically doesn't like.
>
>
Hmm, I keep thinking that there is a bug here that is not related to your
chain, but just triggered by it, which version of KDL are you using?

R.

>
> --
> Orocos-Users mailing list
> Orocos-Users [..] ...
> http://lists.mech.kuleuven.be/mailman/listinfo/orocos-users
>

Ruben Smits's picture

Position only IK

Which version of eigen and KDL are you using, I've never seen this before.

R.

On Wed, Mar 25, 2015 at 2:30 PM, <guillaume [dot] dechambrier [..] ...> wrote:

> I have had a look, thanks this is already a good help. However when I use
> it
> with ChainIkSolverPos_NR, I get the following error:
>
> usr/include/eigen3/Eigen/src/Core/Block.h:141:
> Eigen::Block::Block(XprType&,
> Eigen::Block::Index, Eigen::Block::Index, Eigen::Block::Index,
> Eigen::Block::Index) [with XprType = Eigen::Matrix; int BlockRows = -1; int
> BlockCols = -1; bool InnerPanel = false; Eigen::Block::Index = long int]:
> Assertion `a_startRow >= 0 && blockRows >= 0 && a_startRow = 0 && blockCols
> >= 0 && a_startCol
> --
> Orocos-Users mailing list
> Orocos-Users [..] ...
> http://lists.mech.kuleuven.be/mailman/listinfo/orocos-users
>

Position only IK

I don't think the problem is to do with Eigen but more with my Chain. Here is my chain:

    Rotation R;
    R.Identity();
    KDL::Chain chain2;
    chain2.addSegment(  Segment("link_dof0",Joint("joint_dof0",Vector(0.0934,0.02957,0),Vector(0,0,1),Joint::RotAxis),  Frame(R,Vector(0.0934,0.02957,0))  ));
    chain2.addSegment(  Segment("link_dof1",Joint("joint_dof1",Vector(0,0,0),           Vector(0,-1,0),Joint::RotAxis), Frame(R,Vector(0,0,0))             ));
    chain2.addSegment(  Segment("link_dof2",Joint("joint_dof2",Vector(0.04794,0,0),     Vector(0,-1,0),Joint::RotAxis), Frame(R,Vector(0.04794,0,0))       ));
    chain2.addSegment(  Segment("link_dof3",Joint("joint_dof3",Vector(0.02827,0,0),     Vector(0,-1,0),Joint::RotAxis), Frame(R,Vector(0.02827,0,0))       ));
    chain2.addSegment(  Segment("link_dof4",Joint("joint_dof4",Joint::None),  Frame(R,Vector(0.02612,0,0))       ));
It works fine for forward kinematics and inverse kinematics when using "ChainIkSolverVel_pinv". But when I try with "ChainIkSolverVel_wdls" I get the error mentioned previously with "Block".

I have tried this kinematic chain, which was in another example I found on this site:

    chain1.addSegment(  Segment(    Joint(Joint::RotZ),     Frame(Vector(0.0,0.0,1.020))     )    );
    chain1.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.480))));
    chain1.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.645))));
    chain1.addSegment(Segment(Joint(Joint::RotZ)));
    chain1.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.120))));
    chain1.addSegment(Segment(Joint(Joint::RotZ)));
I have NO error at all with "ChainIkSolverVel_wdls". It makes me think that there is something in my first kinematic chain that ""ChainIkSolverVel_wdls" specifically doesn't like.

Position only IK

I have had a look, thanks this is already a good help. However when I use it with ChainIkSolverPos_NR, I get the following error:

usr/include/eigen3/Eigen/src/Core/Block.h:141: Eigen::Block<XprType, BlockRows, BlockCols, InnerPanel>::Block(XprType&, Eigen::Block<XprType, BlockRows, BlockCols, InnerPanel>::Index, Eigen::Block<XprType, BlockRows, BlockCols, InnerPanel>::Index, Eigen::Block<XprType, BlockRows, BlockCols, InnerPanel>::Index, Eigen::Block<XprType, BlockRows, BlockCols, InnerPanel>::Index) [with XprType = Eigen::Matrix<double, -1, -1>; int BlockRows = -1; int BlockCols = -1; bool InnerPanel = false; Eigen::Block<XprType, BlockRows, BlockCols, InnerPanel>::Index = long int]: Assertion `a_startRow >= 0 && blockRows >= 0 && a_startRow <= xpr.rows() - blockRows && a_startCol >= 0 && blockCols >= 0 && a_startCol <= xpr.cols() - blockCols' failed.

I something is wrong with the initialization of ChainIkSolverVel__wdls, but when I use ChainIkSolverVel_pinv I get no such error.

Just starting out using KDL, so still learning :)