From your previous emails I know that you're running Fuerte on a Katana 400 and are using the katana_arm_kinematics node, so I'll explain a bit of background first. There are three IK implementations that can be used with the Katana:
- The KNI-based katana_arm_kinematics node.
- The generic KDL arm kinematics plugin; it's configured for our Katana-based robot in the
fuerte
branch here. - Fuerte: The IKFast-based kinematics plugin katana_ikfast_kinematics_plugin; it's configured for our Katana-based robot in the
ikfast
branch here. Hydro: The IKFast-based kinematics plugin for MoveIt/Hydro is called katana_moveit_ikfast_plugin.
Personally, I never use (1) any more, since it never worked very well. The problem with (2) is that KDL only provides 6DoF IK, but the Katana has 5DoF IK, so almost 100% of IK requests fail in general. That's why I switched to (3): IKFast allows to generate a TranslationDirection5D
IK plugin (allowing rotation around 1 axis), so I always get an IK solution if it exists (I only generated one for the Katana 450 6M90A so far). For your use case, you can generate a Translation3D
IKFast plugin, which is exactly what you want.
On Fuerte/arm_navigation, follow this tutorial: http://wiki.ros.org/Industrial/Tutori... .
On Hydro/MoveIt, follow this tutorial: http://moveit.ros.org/wiki/Kinematics... .
BTW, I would recommend if at all possible not to invest any time for new development on the Fuerte/arm_navigation combo and instead directly switch to Hydro/MoveIt!.