0
$\begingroup$

Rosanswers logo

I'm working on integrating a robot model consisting of 1 DOF revolute and prismatic joints with moveit and have made a simplified example to make it easier to break down the problems: https://github.com/st3am/KDL-Test (roslaunch kdl_test demol.launch)

image description

I think I'm seeing issues with the KDL kinematics solver. When I have my arm in a configuration of just 2 DOF I can not move the interactive marker. This makes perfect sense to me because the end effector point can not be moved in any direction without increasing the radius from the origin and the chances that I release the marker on the thin spherical shell (.005 thickness defined in the kinematics.yaml) are very low.

The problem occurs when I add the prismatic joint at the end of this arm. The solver can find solutions if I pull the joint out in the axis that is collinear with the axis of the prismatic joint (I manipulate this with the interactive marker on the end effector link), but no solutions are found when I try moving it perpendicular to this radial axis. The sphere of possible solutions is much larger in this case; extending the length between the prismatic joints.

When I add a revolute joint at the end of the prismatic joint and make it the new end effector I can get radial motion perpendicular to the revolute axis because the pose of the end effector does not have to change. By changing the pose and radial position with in steps with the marker I can get the arm to revolve all the way around on a single plane. When I add a second revolute joint perpendicular to the first and make it the new end effector I can move it in either axis, but the first one I move it in subsequently locks the second one. When I try to set a move group goal with all 5 DOF using moveit::planning_interface::MoveGroup.setPositionTarget(), moveit cant find a kinematic solution and times out.

Can anyone tell me if this is a limitation of KDL or if it looks like I'm doing something incorrectly? It seems like in this case the KDL can't find the orientation for a pose either because I'm not giving it what its expecting or because the limited number of DOF's along the prismatic joints somehow cause its root finding algorithms to run into a sort of gimal lock.


Originally posted by St3am on ROS Answers with karma: 170 on 2014-04-13

Post score: 1

$\endgroup$

2 Answers 2

0
$\begingroup$

Rosanswers logo

The KDL solver really only is suitable for use with >= 6 DOF chains. It might find solutions for chains with less DOF (say, when target axes are collinear to main axes), but there is no real support for this so far (unless I missed some new developments). See also this discussion on the MoveIt! user group about a 5DOF arm and this one, too. One thing you could try is generating a MoveIt! ikfast plugin, which should be able to support < 6DOF. You could also give the "approximate IK" and "position only" options for KDL a shot that are talked about in the two links I gave above (more info here).

Another option of course is coding something yourself, either by modifying the KDL based solver, deriving your own analytical solution and putting it into a KinematicsBasePlugin or by using some other libs (for example RBDL).


Originally posted by Stefan Kohlbrecher with karma: 24361 on 2014-04-13

This answer was ACCEPTED on the original site

Post score: 2


Original comments

Comment by St3am on 2014-04-17:
Thanks, adding "position_only_ik: True" to my kinematics.yaml file got me to the point where I could find IK solutions with the interactive marker for my demo. Because the joint angles are fully determined for any possible end effector pose I think the KinematicsBasePlugin is the best end solution

$\endgroup$
0
$\begingroup$

Rosanswers logo

Just to expand on two of the options that Stefan already mentioned:

1. Writing your own MoveIt Kinematics plugin

Follow the Custom Plugin tutorial to get the basic package structure set up. Then implement the getPositionIK() method, which should be relatively straightforward for your arm: You ignore all elements of the requested pose except x and y; then the resulting joint states are something like arctan(y, x) for your revolute joint and sqrt(x^2 + y^2) for your prismatic joint.

2. Using IKFast

Alternatively, you can follow the IKFast tutorial to create an IKFast-based plugin. You'll probably want the TranslationXY2D IK type (see the OpenRAVE doc). There will be one small snag: I didn't implement the wrapper for that IK type (see this line), but it should be super easy. My guess would be that you can call ComputeIK() with trans as the translation, and NULL or something as the rotation, since this IK type only looks at the x and y fields of the translation anyway.

P.S.: If you go with solution (2), it would be great if you could open a pull request for moveit_ikfast with your fix. :-)


Originally posted by Martin Günther with karma: 11816 on 2014-04-13

This answer was NOT ACCEPTED on the original site

Post score: 3


Original comments

Comment by St3am on 2014-04-17:
Thanks for the links, I'm pursuing the plug-in style to start with. I think I might need the TranslationDirection5D because of the wrists degrees of freedom but I would like to learn to use the IKFast generator, I'll try to see if I can add/test the other cases when the semester ends.

Comment by alainsanguinetti on 2016-05-04:
The IKFast tutorial has moved here: http://docs.ros.org/indigo/api/moveit_ikfast/html/doc/ikfast_tutorial.html

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge that you have read and understand our privacy policy and code of conduct.