IK for this IkParameterizationType not implemented yet.
Hi All,
I have followed the instructions for generating an IKFast plugin located here, and have successfully generated an IKFast package using the instructions. Unfortunately the link to the method of running the plugin in Rviz (link) does not have any content so I am once again left guessing.
When I run RViz using:
roslaunch hyd_sys_complete_sldasm_moveit_config demo.launch
I get the following errors repeatedly:
[ERROR] [1409802774.965529932]: IK for this IkParameterizationType not implemented yet.
This does not make sense to me, as when I examine the source code the control type (Translation3d
) was specifically given as an argument for generating the IKFast package, yet it claims there is no implementation for it.
Here's the offending generated code. I am using Translation3D
as my solver yet it is not covered in the solve
function given below.
int IKFastKinematicsPlugin::solve(KDL::Frame &pose_frame, const std::vector<double> &vfree, IkSolutionList<IkReal> &solutions) const
{
// IKFast56/61
solutions.Clear();
double trans[3];
trans[0] = pose_frame.p[0];//-.18;
trans[1] = pose_frame.p[1];
trans[2] = pose_frame.p[2];
KDL::Rotation mult;
KDL::Vector direction;
switch (GetIkType())
{
case IKP_Transform6D:
// For **Transform6D**, eerot is 9 values for the 3x3 rotation matrix.
mult = pose_frame.M;
double vals[9];
vals[0] = mult(0,0);
vals[1] = mult(0,1);
vals[2] = mult(0,2);
vals[3] = mult(1,0);
vals[4] = mult(1,1);
vals[5] = mult(1,2);
vals[6] = mult(2,0);
vals[7] = mult(2,1);
vals[8] = mult(2,2);
// IKFast56/61
ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
return solutions.GetNumSolutions();
case IKP_Direction3D:
case IKP_Ray4D:
case IKP_TranslationDirection5D:
// For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target direction.
direction = pose_frame.M * KDL::Vector(0, 0, 1);
ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
return solutions.GetNumSolutions();
case IKP_TranslationXAxisAngle4D:
case IKP_TranslationYAxisAngle4D:
case IKP_TranslationZAxisAngle4D:
// For **TranslationXAxisAngle4D**, **TranslationYAxisAngle4D**, and **TranslationZAxisAngle4D**, the first value represents the angle.
ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
return 0;
case IKP_TranslationLocalGlobal6D:
// For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end effector coordinate system.
ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
return 0;
case IKP_Rotation3D:
case IKP_Translation3D:
case IKP_Lookat3D:
case IKP_TranslationXY2D:
case IKP_TranslationXYOrientation3D:
case IKP_TranslationXAxisAngleZNorm4D:
case IKP_TranslationYAxisAngleXNorm4D:
case IKP_TranslationZAxisAngleYNorm4D:
ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
return 0;
default:
ROS_ERROR_NAMED("ikfast", "Unknown IkParameterizationType! Was the solver generated with an incompatible version of Openrave?");
return 0;
}
}
Is there something in the kinematics.yaml
file for the RViz plugin I need to change?
I know that the standard kinematic solvers do not work properly for my arm as it only has three degrees of freedom, but unfortunately IKFast has proven much more trouble than it is worth.
Is there a solution to this?
Kind Regards Bart