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

Revision history [back]

click to hide/show revision 1
initial version

I finally found a solution for this problems , well i created the plugin with kinetic , in melodic was impossible for me (install openRave https://fsuarez6.github.io/blog/openrave-trusty/ kinetic) , i followed the next steps : http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/ikfast/ikfast_tutorial.html , i created a fake JOINT that doesnt afect to my arm on EEF position , i used TranslationZAxisAngle4D .

To generate the IKFast Plugin i created a file at the same path that my URDF file :

base_link tool0

and i saved it like robot.xml (credits https://answers.ros.org/question/263925/generating-an-ikfast-solution-for-4-dof-arm/?answer=265625#post-id-265625 )

then i used the below command :

openrave0.9.py --database inversekinematics --robot=/ikfast/robot.xml --iktype=translationzaxisangle4d --iktests=1000

i didnt use this

python `openrave-config --python-dir`/openravepy/_openravepy_/ikfast.py --robot="$MYROBOT_NAME".dae --iktype=transform6d --baselink="$BASE_LINK" --eelink="$EEF_LINK" --savefile="$IKFAST_OUTPUT_PATH"

then i created the plugin like page said.

The final step is modify some code line in the plugin packages :

in my case the plugin package its name : brazo_ikfast_arm_plugin and we need to modify the line 546 (in my case ) or found the switch/case : IKP_TranslationXAxisAngle4D

and changed this code :

case IKP_TranslationXAxisAngle4D:
case IKP_TranslationYAxisAngle4D:
case IKP_TranslationZAxisAngle4D:
  ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet.");
  return 0;

for this :

case IKP_TranslationXAxisAngle4D:
      double roll, pitch, yaw;
      pose_frame.M.GetRPY(roll,pitch,yaw);
      ComputeIk(trans, &roll, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
      return IKP_TranslationXAxisAngle4D;

case IKP_TranslationYAxisAngle4D:
       pose_frame.M.GetRPY(roll,pitch,yaw);
      ComputeIk(trans, &pitch, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
      return IKP_TranslationYAxisAngle4D;

case IKP_TranslationZAxisAngle4D:
      pose_frame.M.GetRPY(roll,pitch,yaw);
      ComputeIk(trans, &yaw, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
      return IKP_TranslationZAxisAngle4D;

and that's it , hope that be helpful for someone with the same problem

I finally found a solution for this problems , well i created the plugin with kinetic , in melodic was impossible for me (install openRave https://fsuarez6.github.io/blog/openrave-trusty/ kinetic) , i followed the next steps : http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/ikfast/ikfast_tutorial.html , i created a fake JOINT that doesnt afect to my arm on EEF position , i used TranslationZAxisAngle4D .

To generate the IKFast Plugin i created a file at the same path that my URDF file :

base_link tool0<robot file="$NAME_OF_YOUR_COLLADA_FILE"> <manipulator name="NAME_OF_THE_ROBOT_IN_URDF"> <base>base_link</base> <effector>tool0</effector> </manipulator> </robot>

in my case was like this :

<robot file="brazo.dae"> <manipulator name="brazo.urdf"> <base>base_link</base> <effector>end_effector_link</effector> </manipulator> </robot>

and i saved it like robot.xml (credits https://answers.ros.org/question/263925/generating-an-ikfast-solution-for-4-dof-arm/?answer=265625#post-id-265625 )

then i used the below command :

openrave0.9.py --database inversekinematics --robot=/ikfast/robot.xml --iktype=translationzaxisangle4d --iktests=1000

i didnt use this

python `openrave-config --python-dir`/openravepy/_openravepy_/ikfast.py --robot="$MYROBOT_NAME".dae --iktype=transform6d --baselink="$BASE_LINK" --eelink="$EEF_LINK" --savefile="$IKFAST_OUTPUT_PATH"

then i created the plugin like page said.

The final step is modify some code line in the plugin packages :

in my case the plugin package its name : brazo_ikfast_arm_plugin and we need to modify the line 546 (in my case ) or found the switch/case : IKP_TranslationXAxisAngle4D

and changed this code :

case IKP_TranslationXAxisAngle4D:
case IKP_TranslationYAxisAngle4D:
case IKP_TranslationZAxisAngle4D:
  ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet.");
  return 0;

for this :

case IKP_TranslationXAxisAngle4D:
      double roll, pitch, yaw;
      pose_frame.M.GetRPY(roll,pitch,yaw);
      ComputeIk(trans, &roll, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
      return IKP_TranslationXAxisAngle4D;

case IKP_TranslationYAxisAngle4D:
       pose_frame.M.GetRPY(roll,pitch,yaw);
      ComputeIk(trans, &pitch, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
      return IKP_TranslationYAxisAngle4D;

case IKP_TranslationZAxisAngle4D:
      pose_frame.M.GetRPY(roll,pitch,yaw);
      ComputeIk(trans, &yaw, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
      return IKP_TranslationZAxisAngle4D;

and that's it , hope that be helpful for someone with the same problem

I finally found a solution for this problems , well i created the plugin with kinetic , in melodic was impossible for me (install openRave https://fsuarez6.github.io/blog/openrave-trusty/ kinetic) , i followed the next steps : http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/ikfast/ikfast_tutorial.html , i created a fake JOINT that doesnt afect to my arm on EEF position , i used TranslationZAxisAngle4D .

To generate the IKFast Plugin i created a file at the same path that my URDF file :

<robot file="$NAME_OF_YOUR_COLLADA_FILE">
  <manipulator <Manipulator name="NAME_OF_THE_ROBOT_IN_URDF">
    <base>base_link</base>
    <effector>tool0</effector>
  </manipulator>
</robot>

</Manipulator> </robot>

in my case was like this :

<robot file="brazo.dae">
    <manipulator <Manipulator name="brazo.urdf">
        <base>base_link</base>
        <effector>end_effector_link</effector>
    </manipulator>
</robot>

</Manipulator> </robot>

and i saved it like robot.xml (credits https://answers.ros.org/question/263925/generating-an-ikfast-solution-for-4-dof-arm/?answer=265625#post-id-265625 )

then i used the below command :

openrave0.9.py --database inversekinematics --robot=/ikfast/robot.xml --iktype=translationzaxisangle4d --iktests=1000

i didnt use this

python `openrave-config --python-dir`/openravepy/_openravepy_/ikfast.py --robot="$MYROBOT_NAME".dae --iktype=transform6d --baselink="$BASE_LINK" --eelink="$EEF_LINK" --savefile="$IKFAST_OUTPUT_PATH"

then i created the plugin like page said.

The final step is modify some code line in the plugin packages :

in my case the plugin package its name : brazo_ikfast_arm_plugin and we need to modify the line 546 (in my case ) or found the switch/case : IKP_TranslationXAxisAngle4D

and changed this code :

case IKP_TranslationXAxisAngle4D:
case IKP_TranslationYAxisAngle4D:
case IKP_TranslationZAxisAngle4D:
  ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet.");
  return 0;

for this :

case IKP_TranslationXAxisAngle4D:
      double roll, pitch, yaw;
      pose_frame.M.GetRPY(roll,pitch,yaw);
      ComputeIk(trans, &roll, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
      return IKP_TranslationXAxisAngle4D;

case IKP_TranslationYAxisAngle4D:
       pose_frame.M.GetRPY(roll,pitch,yaw);
      ComputeIk(trans, &pitch, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
      return IKP_TranslationYAxisAngle4D;

case IKP_TranslationZAxisAngle4D:
      pose_frame.M.GetRPY(roll,pitch,yaw);
      ComputeIk(trans, &yaw, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
      return IKP_TranslationZAxisAngle4D;

and that's it , hope that be helpful for someone with the same problem