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

Revision history [back]

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(x, y) 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.

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(x, y)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.

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. :-)