ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Solving inverse kinematics for special configuration (IKFast)

asked 2018-06-15 12:22:27 -0500

prex gravatar image

updated 2018-06-17 07:22:45 -0500

I'm trying to solve the inverse kinematics problem for a custom made robot arm. The robot arm has a special design with the following 5 DoF in serial configuration:

  • x-axis prismatic joint
  • y-axis prismatic joint
  • revolute joint about z-axis
  • revolute joint about x-axis
  • z-axis prismatic joint

Therefore, I can not reach every configuration in space, namely I'm limited in one of the end-effector angles. For better understanding of the model, I added the URDF at the end.

I was trying to use IKFast to generate an inverse kinematics .cpp file. But when using IK Type "Transform6D" I get an error:

CannotSolveError: need 6 joints

I must admit that it's not totally clear for me what this IK Types mean. I know how to calculate kinematics and inverse kinematics by hand and I can not imagine why this IK Type should matter.

Even trying "TranslationDirection5D" did results in:

CannotSolveError: raghavan roth equations too complex

So I'm wondering if IKFast can solve my problem or how I can do it. I just need the inverse kinematics calculations as "stand alone" (for simplicity) which I will then use in my ROS node. I was following this tutorial:

http://wiki.ros.org/Industrial/Tutori...

URDF file (Link 7 is just a tool frame with fixed Joint 6):

<robot name="or_robot">
  <link name="link1" />
  <link name="link2" />
  <link name="link3" />
  <link name="link4" />
  <link name="link5" />
  <link name="link6" />
  <link name="link7" />

  <joint name="joint1" type="prismatic">
    <parent link="link1"/>
    <child link="link2"/>
    <origin xyz="0 0 0.2" rpy="0 0 0" />
    <axis xyz="0 1 0" />
    <limit effort="1000.0" lower="0.0" upper="0.05" velocity="0.5"/>
  </joint>

  <joint name="joint2" type="prismatic">
    <parent link="link2"/>
    <child link="link3"/>
    <origin xyz="0 0 0" rpy="0 0 0" />
    <axis xyz="1 0 0" />
    <limit effort="1000.0" lower="0.0" upper="0.05" velocity="0.5"/>
  </joint>

  <joint name="joint3" type="revolute">
    <parent link="link3"/>
    <child link="link4"/>
    <origin xyz="0 0 0" rpy="0 0 0" />
    <axis xyz="0 0 1" />
    <limit effort="1000.0" lower="-0.4" upper="1.57" velocity="0.5"/>
  </joint>

  <joint name="joint4" type="revolute">
    <parent link="link4"/>
    <child link="link5"/>
    <origin xyz="0.1 0 0" rpy="0 0.2618 0" />
    <axis xyz="0 1 0" />
    <limit effort="1000.0" lower="0.0" upper="0.785" velocity="0.5"/>
  </joint>

  <joint name="joint5" type="prismatic">
    <parent link="link5"/>
    <child link="link6"/>
    <origin xyz="0 0 -0.05" rpy="0 0 0" />
    <axis xyz="0 0 -1" />
    <limit effort="1000.0" lower="0.0" upper="0.048" velocity="0.5"/>
  </joint>

  <joint name="joint6" type="fixed">
    <parent link="link6"/>
    <child link="link7"/>
    <origin xyz="0 0 -0.02" rpy="0 0 0" />
  </joint>

</robot>

Edit: changed units

edit retag flag offensive close merge delete

Comments

Just a note: you have a robot spanning a volume of 50 by 50 by 48 metres? And the links are 20, 50, 100 and 200 metres apart?

gvdhoorn gravatar image gvdhoorn  ( 2018-06-15 14:11:13 -0500 )edit

I know how to calculate kinematics and inverse kinematics by hand and I can not imagine why this IK Type should matter.

So can you tell me then how to solve for an arbitrary 6D pose with a 5dof robot?

gvdhoorn gravatar image gvdhoorn  ( 2018-06-15 14:12:45 -0500 )edit
1

I just need [..]

Be careful with these types of 'just' sentences. They are typically not as simple as they may seem.

gvdhoorn gravatar image gvdhoorn  ( 2018-06-15 14:13:34 -0500 )edit

Ups, I was looking for units and couldn't find anything. So I was expecting mm. But this shouldn't be the problem. Will change it.

I was not expecting it to work for arbitrary 6D poses. But you are right. It can not work with a closed form solution which is generated by IKFast.

prex gravatar image prex  ( 2018-06-15 14:23:17 -0500 )edit
1

I was looking for units and couldn't find anything.

Everything in ROS is SI units (REP-103). That includes URDF.

gvdhoorn gravatar image gvdhoorn  ( 2018-06-15 14:24:52 -0500 )edit

It can not work with a closed form solution which is generated by IKFast.

if you mean: ikfast can't work for your robot in general, then I would not necessarily agree with that. I've generated IKFast plugins for 5dof robots in the past.

gvdhoorn gravatar image gvdhoorn  ( 2018-06-16 08:04:21 -0500 )edit

I mean it can't work with the "transform6D" mode because of closed form. I also tried to add an additional revolute link for the 6D solution. But I always get "too complex" errors.

prex gravatar image prex  ( 2018-06-16 13:07:32 -0500 )edit

Then can you tell me which parameters to alter or how to do it? I can just choose the IK Type.

prex gravatar image prex  ( 2018-06-16 13:09:15 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-06-24 10:57:45 -0500

prex gravatar image

Not sure if this counts as an answer, but I solved my issue by using Orocos KDL library instead of IKFast. IKFast couldn't find a closed form solution. So I was expecting a numerical solver to work better. And KDL obviously did the job.

edit flag offensive delete link more

Comments

1

If a numerical solution is good enough, I'd advise you to look at trac_ik. It's much more performant and has a much higher solve rate than KDL.

gvdhoorn gravatar image gvdhoorn  ( 2018-06-24 11:41:13 -0500 )edit

Thanks, I will consider that for the final version. But at the moment KDL seems to be very fast for my application.

prex gravatar image prex  ( 2018-06-24 12:31:46 -0500 )edit

trac_ik is faster, always. And has a higher solve rate + solutions will be more accurate. Check the paper + website.

gvdhoorn gravatar image gvdhoorn  ( 2018-06-24 12:53:33 -0500 )edit

thank you I have to accpet this solution

ddl_hust gravatar image ddl_hust  ( 2019-05-05 10:56:36 -0500 )edit

TRAC-IK performs a lot better than default KDL IK solver in my use case (8 dof robot).

It is as simple as installing the corresponding ROS package and using the MoveIt setup assistant to use trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin.

cv_ros_user gravatar image cv_ros_user  ( 2020-12-01 17:17:01 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-06-15 12:22:27 -0500

Seen: 1,016 times

Last updated: Jun 24 '18