Note: This tutorial assumes that you have completed the previous tutorials: Calling the joint space planner.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Configuring a kinematics plugin

Description: Configuring a kinematics plugin

Tutorial Level: INTERMEDIATE

Next Tutorial: Specifying pose goals

In this tutorial, you will learn how to configure an inverse kinematics plugin package for your arm. You have two choices in configuring this package:

  1. Use the generic arm kinematics plugin - This plugin use the KDL kinematics package and will be able to solve the kinematics for any articulated robot. You will learn to do this in this tutorial.
  2. Implement your own plugin - You will have to use the base class defined in the kinematics_base package to implement this and configure your own plugin. Look at the upcoming tutorials on the kinematics_base wiki page.

Dependencies

In order to use the plugin architecture, the example_planning package you created earlier must now also be dependent on the kinematics_base and pluginlib packages. To establish these dependencies, add the following lines to your manifest:

  <depend package="kinematics_base" />
  <depend package="pluginlib" />

Configuring the parameters for your arm

Note that in all the tutorials we have been following for this section, we have so far been planning for the group named right_arm. We will continue with this example. To configure the inverse kinematics plugin for your arm, you need to know the names of two links/frame:

  1. The tip name: This is the end-effector link that you would like to plan for. Note that the name of this link should match the name of the tip link defined in the group definition (see the Robot planning description section in this tutorial for more details on group configuration). For the PR2 arm, the r_wrist_roll_link is the name of the end-effector link for the right arm.

  2. The root name: This is the name of the root link to which your group is attached to. For example, the base or first link of the PR2 arm is the r_shoulder_pan_link whose parent link is the torso_lift_link (through the r_shoulder_pan_joint). So the root name for the right_arm of the PR2 robot is the torso_lift_link.

In the ompl_planning.yaml file you created in one of the earlier tutorials, put this information under the right_arm field.

right_arm:
  tip_name: r_wrist_roll_link
  root_name: torso_lift_link

Configuring the kinematics plugin

Configuring the kinematics plugin requires only one parameter: the name of the plugin that you would like to use. In this case, we are using the generic plugin from the arm_kinematics_constraint_aware package which has the name arm_kinematics_constraint_aware/KDLArmKinematicsPlugin. Thus, the complete configuration (for kinematics) is:

right_arm:
  tip_name: r_wrist_roll_link
  root_name: torso_lift_link
  kinematics_solver: arm_kinematics_constraint_aware/KDLArmKinematicsPlugin

More details (Optional)

The configuration for the PR2 is done using a custom solver available from the pr2_arm_kinematics package. The corresponding configuration file:

right_arm:
  tip_name: r_wrist_roll_link
  root_name: torso_lift_link
  kinematics_solver: pr2_arm_kinematics/PR2ArmKinematicsPlugin

Wiki: ompl_ros_interface/Tutorials/Configuring a kinematics plugin (last edited 2011-05-23 21:21:33 by SachinChitta)