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

Difficulty using ikfast generator, "need 6 joints error" with Kuka Youbot

asked 2013-06-25 12:02:12 -0600

aespielberg gravatar image

updated 2013-07-02 11:42:28 -0600

Hi,

I'm new to ikfast and I'm trying to understand it. I've been following the documentation here: http://moveit.ros.org/wiki/Kinematics/IKFast

I'm using a Kuka youbot urdf file which I converted to a .dae file.

When I do an --info links on my robot, I get the following:

name index parents

base_footprint 0
base_link 1 base_footprint
arm_link_0 2 base_link
arm_link_1 3 arm_link_0
arm_link_2 4 arm_link_1
arm_link_3 5 arm_link_2
arm_link_4 6 arm_link_3
arm_link_5 7 arm_link_4
gripper_palm_link 8 arm_link_5
gripper_finger_link_l 9 gripper_palm_link gripper_finger_link_r 10 gripper_palm_link base_laser_front_link 11 base_link
caster_link_bl 12 base_link
wheel_link_bl 13 caster_link_bl
caster_link_br 14 base_link
wheel_link_br 15 caster_link_br
caster_link_fl 16 base_link
wheel_link_fl 17 caster_link_fl
caster_link_fr 18 base_link
wheel_link_fr 19 caster_link_fr
plate_link 20 base_link

And when I look up the joints, I get: name index parents
andy@andy-VirtualBox:~/catkin_ws/collada_files2$ openrave0.8-robot.py youbot.dae --info joints

name joint_index dof_index parent_link child_link mimic

arm_joint_1 0 0 arm_link_0 arm_link_1
arm_joint_2 1 1 arm_link_1 arm_link_2
arm_joint_3 2 2 arm_link_2 arm_link_3
arm_joint_4 3 3 arm_link_3 arm_link_4
arm_joint_5 4 4 arm_link_4 arm_link_5
gripper_finger_joint_l 5 5 gripper_palm_link gripper_finger_link_l
gripper_finger_joint_r 6 6 gripper_palm_link gripper_finger_link_r
base_footprint_joint -1 -1 base_footprint base_link
arm_joint_0 -1 -1 base_link arm_link_0
gripper_palm_joint -1 -1 arm_link_5 gripper_palm_link
base_laser_front_hokuyo_urg04_laser_joint -1 -1 base_link base_laser_front_link
caster_joint_bl -1 -1 base_link caster_link_bl
wheel_joint_bl -1 -1 caster_link_bl wheel_link_bl
caster_joint_br -1 -1 base_link caster_link_br
wheel_joint_br -1 -1 caster_link_br wheel_link_br
caster_joint_fl -1 -1 base_link caster_link_fl
wheel_joint_fl -1 -1 caster_link_fl wheel_link_fl
caster_joint_fr -1 -1 base_link caster_link_fr
wheel_joint_fr -1 -1 caster_link_fr wheel_link_fr
plate_joint -1 -1 base_link

Now, I apologize for my newness to the ikfast package, so I'm trying to understand exactly what this means. I assume a -1 means no dof is provided by the joint (so, it's fixed or something), and that each number 0 through 6 provides the cumulative dof at that joint.

Therefore, my understanding is that the correct 6DOF command to generate the IKSolver would be:

python /usr/lib/python2.7/dist-packages/openravepy/_openravepy_0_8/ikfast.py --robot=youbot.dae --iktype=transform6d --baselink=3 --eelink=10 --savefile=output_ikfast61.cpp

But I get the following error:

/usr/lib/python2.7/dist-packages/openravepy/_openravepy_0_8/ikfast.py:1122: RuntimeWarning: invalid value encountered in divide axisangle /= angle INFO: moved translation [0, 0, 13/100] to right end INFO: moved translation [0, 0, 19/1000] to left end INFO: moved translation on intersecting axis [0, 0, 0] to left INFO: [[1, 0, 0, 3/125],[0, 1, 0, 0],[0, 0, 1, 23/200]] INFO: [[cos(j0), -sin(j0), 0, 0],[sin(j0), cos(j0), 0, 0],[0, 0, 1, 0]] INFO: [[1, 0, 0, 33/1000],[0, 0, -1, 0],[0, 1, 0, 0]] INFO: [[cos(j1), -sin(j1), 0, 0],[sin(j1), cos(j1), 0, 0],[0, 0, 1, 0]] INFO: [[1, 0, 0, 0],[0, -1, 0, 31/200],[0, 0, -1, 0]] INFO: [[cos(j2), -sin(j2), 0, 0],[sin(j2), cos(j2), 0, 0],[0, 0, 1, 0]] INFO: [[1, 0, 0, 0],[0, -1, 0, -27/200],[0, 0, -1, 0 ... (more)

edit retag flag offensive close merge delete

Comments

I can't really answer your question, but the Kuka youbot only has 5 DoF.

Martin Günther gravatar image Martin Günther  ( 2013-06-25 22:25:10 -0600 )edit

It has 5 effective DoF, but 6 joints, right? So this would be a 6DoF arm with one redundant joint? I know there's a way to specify redundant joints, but I don't really understand the documentation there.

aespielberg gravatar image aespielberg  ( 2013-06-26 07:52:42 -0600 )edit

Re: Update - Are you planning on using arm_navigation or MoveIt? For MoveIt, there's a tutorial here: http://moveit.ros.org/wiki/PR2/Setup_Assistant/Quick_Start ; for arm_navigation, here: http://ros.org/wiki/arm_navigation/Tutorials/tools/Planning%20Description%20Configuration%20Wizard

Martin Günther gravatar image Martin Günther  ( 2013-07-03 01:31:24 -0600 )edit

Okay, I think I've got it working now, thanks a lot for your help!

aespielberg gravatar image aespielberg  ( 2013-07-03 14:42:48 -0600 )edit

Hey I have the problem now that I cannot create the cpp file. I also use the Kuka Youbot and it doesn't work for youbot with or without base. Could you please provide that cpp file you generatedor tell me how you solved your problem? Was the iktype the only parameter you changed?I am using ros kinetic on Ubuntu 16.04. I always get the error message that my equations are too complex.

awied gravatar image awied  ( 2020-10-26 07:52:54 -0600 )edit

2 Answers

Sort by » oldest newest most voted
2

answered 2013-06-26 23:33:35 -0600

updated 2013-06-28 05:11:29 -0600

If you only consider the arm (not the base), it has 5 controllable joints according to this page ("arm joint 1-5"), plus one fixed joint. This makes it 5DoF.

Not sure what you mean by "redundant joint"; the way I understand the term, if you have a (6 + n) DoF manipulator (which the youbot doesn't), you have n redundant joints (since you only need 6 of the joints to find an inverse kinematic solution).

Since the youbot arm only has 5 joints, ikfast probably can't compute a transform6d IK (that's why it says "need 6 joints"). You can try specifying a translationdirection5d iktype instead; I'm currently trying to do that, but ran into trouble; I'll probably ask a question about how to get translationdirection5d working later today.

UPDATE: I've solved the problem I mentioned above; see this moveit-users post if you plan on creating a TranslationDirection5D ikfast plugin.

edit flag offensive delete link more
1

answered 2013-06-27 04:50:02 -0600

I believe Martin's answer is correct. When I read the YouBot specs here, it explicitly lists the YouBots as 5-DOF robots. For 5-DOF robots, you don't have sufficient degrees of freedom to calculate a full XYZWPR (transform6d) IK solution. Instead, you must use one of the lower-DOF solutions, such as translationdirection5d. See these other discussions:

Even if you were to use IKFast's redundant-joint flag, this will not allow it to create a 6DOF solution for a 5DOF robot. IKFast expects you to specify an arbitrary value for the redundant joint at runtime, and will solve for the remaining joints. This allows for analytic solutions of 7DOF robots: once the redundant joint value is specified, IKFast can treat the links on either side of that joint as a single rigid link, and calculate a normal 6DOF solution for the remaining 6 joints. This means that if you have a 6DOF robot with one redundant ("free") joint, then IKFast is still trying to calculate a 5DOF solution once you have specified the (arbitrary) value for the redundant joint.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2013-06-25 12:02:12 -0600

Seen: 2,978 times

Last updated: Jul 02 '13